moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Types | Public Member Functions | Protected Member Functions | List of all members
planning_request_adapter::PlanningRequestAdapter Class Referenceabstract

#include <planning_request_adapter.h>

Inheritance diagram for planning_request_adapter::PlanningRequestAdapter:
Inheritance graph
[legend]

Public Types

using PlannerFn = std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)>
 

Public Member Functions

 PlanningRequestAdapter ()
 
virtual ~PlanningRequestAdapter ()
 
virtual void initialize (const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace)=0
 Initialize parameters using the passed Node and parameter namespace. If no initialization is needed, simply implement as empty. More...
 
virtual std::string getDescription () const
 Get a short string that identifies the planning request adapter. More...
 
bool adaptAndPlan (const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const
 
bool adaptAndPlan (const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const
 
virtual bool adaptAndPlan (const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const =0
 Adapt the planning request if needed, call the planner function planner and update the planning response if needed. If the response is changed, the index values of the states added without planning are added to added_path_index. More...
 

Protected Member Functions

template<typename T >
getParam (const rclcpp::Node::SharedPtr &node, const rclcpp::Logger &logger, const std::string &parameter_namespace, const std::string &parameter_name, T default_value={}) const
 Helper param for getting a parameter using a namespace. More...
 

Detailed Description

Definition at line 51 of file planning_request_adapter.h.

Member Typedef Documentation

◆ PlannerFn

Definition at line 54 of file planning_request_adapter.h.

Constructor & Destructor Documentation

◆ PlanningRequestAdapter()

planning_request_adapter::PlanningRequestAdapter::PlanningRequestAdapter ( )
inline

Definition at line 58 of file planning_request_adapter.h.

◆ ~PlanningRequestAdapter()

virtual planning_request_adapter::PlanningRequestAdapter::~PlanningRequestAdapter ( )
inlinevirtual

Definition at line 62 of file planning_request_adapter.h.

Member Function Documentation

◆ adaptAndPlan() [1/3]

virtual bool planning_request_adapter::PlanningRequestAdapter::adaptAndPlan ( const PlannerFn planner,
const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
planning_interface::MotionPlanResponse res,
std::vector< std::size_t > &  added_path_index 
) const
pure virtual

◆ adaptAndPlan() [2/3]

bool planning_request_adapter::PlanningRequestAdapter::adaptAndPlan ( const planning_interface::PlannerManagerPtr &  planner,
const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
planning_interface::MotionPlanResponse res 
) const

Definition at line 94 of file planning_request_adapter.cpp.

Here is the caller graph for this function:

◆ adaptAndPlan() [3/3]

bool planning_request_adapter::PlanningRequestAdapter::adaptAndPlan ( const planning_interface::PlannerManagerPtr &  planner,
const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
planning_interface::MotionPlanResponse res,
std::vector< std::size_t > &  added_path_index 
) const

Definition at line 80 of file planning_request_adapter.cpp.

Here is the call graph for this function:

◆ getDescription()

virtual std::string planning_request_adapter::PlanningRequestAdapter::getDescription ( ) const
inlinevirtual

◆ getParam()

template<typename T >
T planning_request_adapter::PlanningRequestAdapter::getParam ( const rclcpp::Node::SharedPtr &  node,
const rclcpp::Logger &  logger,
const std::string &  parameter_namespace,
const std::string &  parameter_name,
default_value = {} 
) const
inlineprotected

Helper param for getting a parameter using a namespace.

Definition at line 99 of file planning_request_adapter.h.

Here is the caller graph for this function:

◆ initialize()

virtual void planning_request_adapter::PlanningRequestAdapter::initialize ( const rclcpp::Node::SharedPtr &  node,
const std::string &  parameter_namespace 
)
pure virtual

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