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

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

#include <planning.h>

+ Inheritance diagram for robowflex::opt::TrajOptPipelinePlanner:

Public Member Functions

 TrajOptPipelinePlanner (const RobotPtr &robot, const std::string &name="")
 
 TrajOptPipelinePlanner (TrajOptPipelinePlanner const &)=delete
 
void operator= (TrajOptPipelinePlanner 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 TrajOpt 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...
 
- 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::vector< std::stringgetPlannerConfigs () const =0
 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...
 
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...
 

Static Protected Attributes

static const std::string DEFAULT_PLUGIN
 The default TrajOpt plugin. More...
 
static const std::vector< std::stringDEFAULT_ADAPTERS
 The default planning adapters. 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! TrajOpt planning pipeline.

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

Constructor & Destructor Documentation

◆ TrajOptPipelinePlanner() [1/2]

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

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

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

◆ TrajOptPipelinePlanner() [2/2]

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

Member Function Documentation

◆ initialize()

bool opt::TrajOptPipelinePlanner::initialize ( const std::string config_file = "",
const std::string plugin = DEFAULT_PLUGIN,
const std::vector< std::string > &  adapters = DEFAULT_ADAPTERS 
)

Initialize planning pipeline. Loads TrajOpt 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.

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

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

555 {
556  if (!loadConfig(handler_, config_file))
557  return false;
558 
559  handler_.setParam("planning_plugin", plugin);
560 
562  for (std::size_t i = 0; i < adapters.size(); ++i)
563  {
564  ss << adapters[i];
565  if (i < adapters.size() - 1)
566  ss << " ";
567  }
568 
569  handler_.setParam("request_adapters", ss.str());
570 
571  pipeline_.reset(new planning_pipeline::PlanningPipeline(robot_->getModelConst(), handler_.getHandle(),
572  "planning_plugin", "request_adapters"));
573 
574  return true;
575 }
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.
bool loadConfig(IO::Handler &handler, const std::string &config_file)
Loads configuration YAML file onto the parameter server.
T size(T... args)
T str(T... args)

◆ operator=()

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

Member Data Documentation

◆ DEFAULT_ADAPTERS

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

The default planning adapters.

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

◆ DEFAULT_PLUGIN

const std::string opt::TrajOptPipelinePlanner::DEFAULT_PLUGIN
staticprotected

The default TrajOpt plugin.

opt::TrajOptPipelinePlanner

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


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