Robowflex
v0.1
Making MoveIt Easy
|
A robowflex::PipelinePlanner that uses the MoveIt! CHOMP planning pipeline. More...
#include <planning.h>
Public Member Functions | |
CHOMPPipelinePlanner (const RobotPtr &robot, const std::string &name="") | |
CHOMPPipelinePlanner (CHOMPPipelinePlanner const &)=delete | |
void | operator= (CHOMPPipelinePlanner const &)=delete |
bool | initialize (const std::string &config_file, const std::string &plugin=DEFAULT_PLUGIN, const std::vector< std::string > &adapters=DEFAULT_ADAPTERS) |
Initialize planning pipeline. Loads CHOMP planning plugin plugin with the planning adapters adapters. Parameters are set on the parameter server from config_file. More... | |
bool | initialize (const CHOMPSettings &settings=CHOMPSettings(), const std::string &plugin=DEFAULT_PLUGIN, const std::vector< std::string > &adapters=DEFAULT_ADAPTERS) |
Initialize planning pipeline. Loads CHOMP planning plugin plugin with the planning adapters adapters. Parameters are set on the parameter server from settings. 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... | |
Protected Member Functions | |
bool | finishInitialize (const std::string &plugin, const std::vector< std::string > &adapters) |
Finalize the initialization process after parameters are set. More... | |
Static Protected Attributes | |
static const std::string | DEFAULT_PLUGIN |
The default CHOMP plugin. More... | |
static const std::vector< std::string > | DEFAULT_ADAPTERS |
The default planning adapters. More... | |
Private Attributes | |
std::vector< std::string > | configs_ |
Planning configurations loaded from config_file. More... | |
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! CHOMP planning pipeline.
Definition at line 444 of file robowflex_library/include/robowflex_library/planning.h.
opt::CHOMPPipelinePlanner::CHOMPPipelinePlanner | ( | const RobotPtr & | robot, |
const std::string & | name = "" |
||
) |
Definition at line 488 of file robowflex_library/src/planning.cpp.
|
delete |
|
protected |
Finalize the initialization process after parameters are set.
[in] | plugin | Planning plugin to load. |
[in] | adapters | Planning adapters to load. |
Definition at line 509 of file robowflex_library/src/planning.cpp.
|
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 530 of file robowflex_library/src/planning.cpp.
bool opt::CHOMPPipelinePlanner::initialize | ( | const CHOMPSettings & | settings = CHOMPSettings() , |
const std::string & | plugin = DEFAULT_PLUGIN , |
||
const std::vector< std::string > & | adapters = DEFAULT_ADAPTERS |
||
) |
Initialize planning pipeline. Loads CHOMP planning plugin plugin with the planning adapters adapters. Parameters are set on the parameter server from settings.
[in] | settings | Planner settings. |
[in] | plugin | Planning plugin to load. |
[in] | adapters | Planning adapters to load. |
Definition at line 493 of file robowflex_library/src/planning.cpp.
bool opt::CHOMPPipelinePlanner::initialize | ( | const std::string & | config_file, |
const std::string & | plugin = DEFAULT_PLUGIN , |
||
const std::vector< std::string > & | adapters = DEFAULT_ADAPTERS |
||
) |
Initialize planning pipeline. Loads CHOMP planning plugin plugin with the planning adapters adapters. Parameters are set on the parameter server from config_file.
[in] | config_file | A YAML file containing CHOMP configuration. |
[in] | plugin | Planning plugin to load. |
[in] | adapters | Planning adapters to load. |
Definition at line 500 of file robowflex_library/src/planning.cpp.
|
delete |
|
private |
Planning configurations loaded from config_file.
Definition at line 490 of file robowflex_library/include/robowflex_library/planning.h.
|
staticprotected |
The default planning adapters.
Definition at line 487 of file robowflex_library/include/robowflex_library/planning.h.
|
staticprotected |
The default CHOMP plugin.
Definition at line 486 of file robowflex_library/include/robowflex_library/planning.h.