moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Functions
planning_pipeline Namespace Reference

Classes

class  PlanningPipeline
 This class facilitates loading planning plugins and planning adapter plugins. It implements functionality to use the loaded plugins in a motion planning pipeline consisting of PlanningRequestAdapters (Pre-processing), a Planner plugin and PlanningResponseAdapters (Post-processing). More...
 

Functions

 MOVEIT_CLASS_FORWARD (PlanningPipeline)
 
template<class TPluginClass >
void loadPluginVector (const std::shared_ptr< rclcpp::Node > &node, const std::unique_ptr< pluginlib::ClassLoader< TPluginClass >> &plugin_loader, std::vector< std::shared_ptr< const TPluginClass >> &plugin_vector, const std::vector< std::string > &plugin_names, const std::string &parameter_namespace)
 Helper function template to load a vector of plugins. More...
 

Function Documentation

◆ loadPluginVector()

template<class TPluginClass >
void planning_pipeline::loadPluginVector ( const std::shared_ptr< rclcpp::Node > &  node,
const std::unique_ptr< pluginlib::ClassLoader< TPluginClass >> &  plugin_loader,
std::vector< std::shared_ptr< const TPluginClass >> &  plugin_vector,
const std::vector< std::string > &  plugin_names,
const std::string &  parameter_namespace 
)

Helper function template to load a vector of plugins.

Template Parameters
TPluginClassPlugin class type, PlanningRequestAdapter or PlanningResponseAdapter
Parameters
plugin_loaderLoader to create the requested plugin
plugin_vectorVector to add the loaded plugin to
plugin_namesNames of the plugins to be loaded

Definition at line 65 of file planning_pipeline.h.

◆ MOVEIT_CLASS_FORWARD()

planning_pipeline::MOVEIT_CLASS_FORWARD ( PlanningPipeline  )