Robowflex
v0.1
Making MoveIt Easy
|
A robowflex::PipelinePlanner that uses the MoveIt! default OMPL planning pipeline. More...
#include <planning.h>
Public Member Functions | |
OMPLPipelinePlanner (const RobotPtr &robot, const std::string &name="") | |
OMPLPipelinePlanner (OMPLPipelinePlanner const &)=delete | |
void | operator= (OMPLPipelinePlanner const &)=delete |
bool | initialize (const std::string &config_file="", const Settings &settings=Settings(), const std::string &plugin=DEFAULT_PLUGIN, const std::vector< std::string > &adapters=DEFAULT_ADAPTERS) |
Initialize planning pipeline. Loads OMPL planning plugin plugin with the planning adapters adapters. Parameters are set on the parameter server from settings and planning configurations are loaded from the YAML file config_file. More... | |
std::vector< std::string > | getPlannerConfigs () const override |
Return all planner configurations offered by this planner. Any of the configurations returned can be set as the planner for a motion planning query sent to plan(). More... | |
Public Member Functions inherited from robowflex::PipelinePlanner | |
PipelinePlanner (const RobotPtr &robot, const std::string &name="") | |
Constructor. More... | |
PipelinePlanner (PipelinePlanner const &)=delete | |
void | operator= (PipelinePlanner const &)=delete |
planning_interface::MotionPlanResponse | plan (const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request) override |
Plan a motion given a request and a scene. Uses the planning pipeline's generatePlan() method, which goes through planning adapters. More... | |
template<typename T > | |
std::shared_ptr< T > | extractPlanningContext (const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request) const |
Retrieve planning context and dynamically cast to desired type from planning pipeline. More... | |
Public Member Functions inherited from robowflex::Planner | |
Planner (const RobotPtr &robot, const std::string &name="") | |
Constructor. Takes in a robot description and an optional namespace name. If name is specified, planner parameters are namespaced under the namespace of robot. More... | |
Planner (Planner const &)=delete | |
void | operator= (Planner const &)=delete |
virtual std::map< std::string, ProgressProperty > | getProgressProperties (const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request) const |
Retrieve the planner progress property map for this planner given a specific request. More... | |
const RobotPtr | getRobot () const |
Return the robot for this planner. More... | |
const std::string & | getName () const |
Get the name of the planner. More... | |
virtual void | preRun (const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request) |
This function is called before benchmarking. More... | |
Static Protected Attributes | |
static const std::string | DEFAULT_PLUGIN |
The default OMPL plugin. More... | |
static const std::vector< std::string > | DEFAULT_ADAPTERS |
The default planning adapters. More... | |
Private Attributes | |
std::vector< std::string > | configs_ |
Additional Inherited Members | |
Public Types inherited from robowflex::Planner | |
using | ProgressProperty = std::function< std::string()> |
A function that returns the value of a planner property over the course of a run. More... | |
Protected Attributes inherited from robowflex::PipelinePlanner | |
planning_pipeline::PlanningPipelinePtr | pipeline_ |
Loaded planning pipeline plugin. More... | |
Protected Attributes inherited from robowflex::Planner | |
RobotPtr | robot_ |
The robot to plan for. More... | |
IO::Handler | handler_ |
The parameter handler for the planner. More... | |
const std::string | name_ |
Namespace for the planner. More... | |
A robowflex::PipelinePlanner that uses the MoveIt! default OMPL planning pipeline.
Definition at line 339 of file robowflex_library/include/robowflex_library/planning.h.
OMPL::OMPLPipelinePlanner::OMPLPipelinePlanner | ( | const RobotPtr & | robot, |
const std::string & | name = "" |
||
) |
Definition at line 346 of file robowflex_library/src/planning.cpp.
|
delete |
|
overridevirtual |
Return all planner configurations offered by this planner. Any of the configurations returned can be set as the planner for a motion planning query sent to plan().
Implements robowflex::Planner.
Definition at line 377 of file robowflex_library/src/planning.cpp.
bool OMPL::OMPLPipelinePlanner::initialize | ( | const std::string & | config_file = "" , |
const Settings & | settings = Settings() , |
||
const std::string & | plugin = DEFAULT_PLUGIN , |
||
const std::vector< std::string > & | adapters = DEFAULT_ADAPTERS |
||
) |
Initialize planning pipeline. Loads OMPL planning plugin plugin with the planning adapters adapters. Parameters are set on the parameter server from settings and planning configurations are loaded from the YAML file config_file.
[in] | config_file | A YAML file containing OMPL planner configurations. |
[in] | settings | Settings to set on the parameter server. |
[in] | plugin | Planning plugin to load. |
[in] | adapters | Planning adapters to load. |
Definition at line 351 of file robowflex_library/src/planning.cpp.
|
delete |
|
private |
Planning configurations loaded from config_file in initialize()
Definition at line 369 of file robowflex_library/include/robowflex_library/planning.h.
|
staticprotected |
The default planning adapters.
Definition at line 366 of file robowflex_library/include/robowflex_library/planning.h.
|
staticprotected |
The default OMPL plugin.
OMPL::PipelinePlanner
Definition at line 365 of file robowflex_library/include/robowflex_library/planning.h.