Public Types | Public 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 = boost::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)>
 

Public Member Functions

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...
 
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 std::string getDescription () const
 Get a short string that identifies the planning request adapter. More...
 
virtual void initialize (const ros::NodeHandle &node_handle)=0
 Initialize parameters using the passed NodeHandle if no initialization is needed, simply implement as empty. More...
 
 PlanningRequestAdapter ()
 
virtual ~PlanningRequestAdapter ()
 

Detailed Description

Definition at line 81 of file planning_request_adapter.h.

Member Typedef Documentation

◆ PlannerFn

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

Definition at line 86 of file planning_request_adapter.h.

Constructor & Destructor Documentation

◆ PlanningRequestAdapter()

planning_request_adapter::PlanningRequestAdapter::PlanningRequestAdapter ( )
inline

Definition at line 88 of file planning_request_adapter.h.

◆ ~PlanningRequestAdapter()

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

Definition at line 92 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

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.

Implemented in AppendingPlanningRequestAdapter, and PrependingPlanningRequestAdapter.

◆ 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 128 of file planning_request_adapter.cpp.

◆ 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 114 of file planning_request_adapter.cpp.

◆ getDescription()

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

Get a short string that identifies the planning request adapter.

Definition at line 101 of file planning_request_adapter.h.

◆ initialize()

virtual void planning_request_adapter::PlanningRequestAdapter::initialize ( const ros::NodeHandle node_handle)
pure virtual

Initialize parameters using the passed NodeHandle if no initialization is needed, simply implement as empty.

Implemented in AppendingPlanningRequestAdapter, and PrependingPlanningRequestAdapter.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Apr 18 2024 02:23:41