moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Namespaces | Functions
planning_pipeline.h File Reference
#include <atomic>
#include <moveit/planning_interface/planning_interface.h>
#include <moveit/planning_interface/planning_request_adapter.h>
#include <moveit/planning_interface/planning_response_adapter.h>
#include <pluginlib/class_loader.hpp>
#include <rclcpp/rclcpp.hpp>
#include <moveit_msgs/msg/pipeline_state.hpp>
#include <memory>
#include <moveit_planning_pipeline_export.h>
#include <planning_pipeline_parameters.hpp>
Include dependency graph for planning_pipeline.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  planning_pipeline::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...
 

Namespaces

 planning_pipeline
 

Functions

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. More...
 
 planning_pipeline::MOVEIT_CLASS_FORWARD (PlanningPipeline)