#include <planning_request_adapter.h>
|
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 () |
|
Definition at line 81 of file planning_request_adapter.h.
◆ PlannerFn
◆ PlanningRequestAdapter()
planning_request_adapter::PlanningRequestAdapter::PlanningRequestAdapter |
( |
| ) |
|
|
inline |
◆ ~PlanningRequestAdapter()
virtual planning_request_adapter::PlanningRequestAdapter::~PlanningRequestAdapter |
( |
| ) |
|
|
inlinevirtual |
◆ adaptAndPlan() [1/3]
◆ adaptAndPlan() [2/3]
◆ adaptAndPlan() [3/3]
◆ getDescription()
virtual std::string planning_request_adapter::PlanningRequestAdapter::getDescription |
( |
| ) |
const |
|
inlinevirtual |
◆ initialize()
virtual void planning_request_adapter::PlanningRequestAdapter::initialize |
( |
const ros::NodeHandle & |
node_handle | ) |
|
|
pure virtual |
The documentation for this class was generated from the following files: