Robowflex  v0.1
Making MoveIt Easy
robowflex::opt::CHOMPPipelinePlanner Class Reference

A robowflex::PipelinePlanner that uses the MoveIt! CHOMP planning pipeline. More...

#include <planning.h>

+ Inheritance diagram for robowflex::opt::CHOMPPipelinePlanner:

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::stringgetPlannerConfigs () 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, ProgressPropertygetProgressProperties (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::stringgetName () 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::stringDEFAULT_ADAPTERS
 The default planning adapters. More...
 

Private Attributes

std::vector< std::stringconfigs_
 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...
 

Detailed Description

A robowflex::PipelinePlanner that uses the MoveIt! CHOMP planning pipeline.

Definition at line 444 of file robowflex_library/include/robowflex_library/planning.h.

Constructor & Destructor Documentation

◆ CHOMPPipelinePlanner() [1/2]

opt::CHOMPPipelinePlanner::CHOMPPipelinePlanner ( const RobotPtr robot,
const std::string name = "" 
)

Definition at line 488 of file robowflex_library/src/planning.cpp.

489  : PipelinePlanner(robot, name)
490 {
491 }
PipelinePlanner(const RobotPtr &robot, const std::string &name="")
Constructor.
Functions for loading and animating robots in Blender.

◆ CHOMPPipelinePlanner() [2/2]

robowflex::opt::CHOMPPipelinePlanner::CHOMPPipelinePlanner ( CHOMPPipelinePlanner const &  )
delete

Member Function Documentation

◆ finishInitialize()

bool opt::CHOMPPipelinePlanner::finishInitialize ( const std::string plugin,
const std::vector< std::string > &  adapters 
)
protected

Finalize the initialization process after parameters are set.

Parameters
[in]pluginPlanning plugin to load.
[in]adaptersPlanning adapters to load.
Returns
True upon success, false on failure.

Definition at line 509 of file robowflex_library/src/planning.cpp.

511 {
512  configs_.emplace_back("chomp");
513  handler_.setParam("planning_plugin", plugin);
514 
516  for (std::size_t i = 0; i < adapters.size(); ++i)
517  {
518  ss << adapters[i];
519  if (i < adapters.size() - 1)
520  ss << " ";
521  }
522 
523  handler_.setParam("request_adapters", ss.str());
524  pipeline_.reset(new planning_pipeline::PlanningPipeline(robot_->getModelConst(), handler_.getHandle(),
525  "planning_plugin", "request_adapters"));
526 
527  return true;
528 }
void setParam(const std::string &key, const T &value)
Sets a parameter on the parameter server.
Definition: handler.h:53
const ros::NodeHandle & getHandle() const
Gets the node handle.
planning_pipeline::PlanningPipelinePtr pipeline_
Loaded planning pipeline plugin.
IO::Handler handler_
The parameter handler for the planner.
std::vector< std::string > configs_
Planning configurations loaded from config_file.
T emplace_back(T... args)
T size(T... args)
T str(T... args)

◆ getPlannerConfigs()

std::vector< std::string > opt::CHOMPPipelinePlanner::getPlannerConfigs ( ) const
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().

Returns
A vector of strings of planner configuration names.

Implements robowflex::Planner.

Definition at line 530 of file robowflex_library/src/planning.cpp.

531 {
532  return configs_;
533 }

◆ initialize() [1/2]

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.

Parameters
[in]settingsPlanner settings.
[in]pluginPlanning plugin to load.
[in]adaptersPlanning adapters to load.
Returns
True upon success, false on failure.

Definition at line 493 of file robowflex_library/src/planning.cpp.

495 {
496  settings.setParam(handler_);
497  return finishInitialize(plugin, adapters);
498 }
bool finishInitialize(const std::string &plugin, const std::vector< std::string > &adapters)
Finalize the initialization process after parameters are set.

◆ initialize() [2/2]

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.

Parameters
[in]config_fileA YAML file containing CHOMP configuration.
[in]pluginPlanning plugin to load.
[in]adaptersPlanning adapters to load.
Returns
True upon success, false on failure.

Definition at line 500 of file robowflex_library/src/planning.cpp.

502 {
503  if (!loadConfig(handler_, config_file))
504  return false;
505 
506  return finishInitialize(plugin, adapters);
507 }
bool loadConfig(IO::Handler &handler, const std::string &config_file)
Loads configuration YAML file onto the parameter server.

◆ operator=()

void robowflex::opt::CHOMPPipelinePlanner::operator= ( CHOMPPipelinePlanner const &  )
delete

Member Data Documentation

◆ configs_

std::vector<std::string> robowflex::opt::CHOMPPipelinePlanner::configs_
private

Planning configurations loaded from config_file.

Definition at line 490 of file robowflex_library/include/robowflex_library/planning.h.

◆ DEFAULT_ADAPTERS

const std::vector< std::string > opt::CHOMPPipelinePlanner::DEFAULT_ADAPTERS
staticprotected

The default planning adapters.

Definition at line 487 of file robowflex_library/include/robowflex_library/planning.h.

◆ DEFAULT_PLUGIN

const std::string opt::CHOMPPipelinePlanner::DEFAULT_PLUGIN
staticprotected

The default CHOMP plugin.

opt::CHOMPPipelinePlanner

Definition at line 486 of file robowflex_library/include/robowflex_library/planning.h.


The documentation for this class was generated from the following files: