moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Representation of a particular planning context – the planning scene and the request are known, solution is not yet computed. More...
#include <planning_interface.h>
Public Member Functions | |
PlanningContext (const std::string &name, const std::string &group) | |
Construct a planning context named name for the group group. | |
virtual | ~PlanningContext () |
const std::string & | getGroupName () const |
Get the name of the group this planning context is for. | |
const std::string & | getName () const |
Get the name of this planning context. | |
const planning_scene::PlanningSceneConstPtr & | getPlanningScene () const |
Get the planning scene associated to this planning context. | |
const MotionPlanRequest & | getMotionPlanRequest () const |
Get the motion plan request associated to this planning context. | |
void | setPlanningScene (const planning_scene::PlanningSceneConstPtr &planning_scene) |
Set the planning scene for this context. | |
void | setMotionPlanRequest (const MotionPlanRequest &request) |
Set the planning request for this context. | |
virtual void | solve (MotionPlanResponse &res)=0 |
Solve the motion planning problem and store the result in res. This function should not clear data structures before computing. The constructor and clear() do that. | |
virtual void | solve (MotionPlanDetailedResponse &res)=0 |
Solve the motion planning problem and store the detailed result in res. This function should not clear data structures before computing. The constructor and clear() do that. | |
virtual bool | terminate ()=0 |
If solve() is running, terminate the computation. Return false if termination not possible. No-op if solve() is not running (returns true). | |
virtual void | clear ()=0 |
Clear the data structures used by the planner. | |
Protected Attributes | |
std::string | name_ |
The name of this planning context. | |
std::string | group_ |
The group (as in the SRDF) this planning context is for. | |
planning_scene::PlanningSceneConstPtr | planning_scene_ |
The planning scene for this context. | |
MotionPlanRequest | request_ |
The planning request for this context. | |
Representation of a particular planning context – the planning scene and the request are known, solution is not yet computed.
Definition at line 78 of file planning_interface.h.
planning_interface::PlanningContext::PlanningContext | ( | const std::string & | name, |
const std::string & | group | ||
) |
Construct a planning context named name for the group group.
Definition at line 70 of file planning_interface.cpp.
|
virtual |
Definition at line 77 of file planning_interface.cpp.
|
pure virtual |
Clear the data structures used by the planner.
Implemented in chomp_interface::CHOMPPlanningContext, ompl_interface::ModelBasedPlanningContext, pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >, pilz_industrial_motion_planner::PlanningContextBase< TrajectoryGeneratorCIRC >, pilz_industrial_motion_planner::PlanningContextBase< TrajectoryGeneratorLIN >, pilz_industrial_motion_planner::PlanningContextBase< TrajectoryGeneratorPTP >, stomp_moveit::StompPlanningContext, and planning_pipeline_test::DummyPlanningContext.
|
inline |
Get the name of the group this planning context is for.
Definition at line 87 of file planning_interface.h.
|
inline |
Get the motion plan request associated to this planning context.
Definition at line 105 of file planning_interface.h.
|
inline |
Get the name of this planning context.
Definition at line 93 of file planning_interface.h.
|
inline |
Get the planning scene associated to this planning context.
Definition at line 99 of file planning_interface.h.
void planning_interface::PlanningContext::setMotionPlanRequest | ( | const MotionPlanRequest & | request | ) |
Set the planning request for this context.
Definition at line 89 of file planning_interface.cpp.
void planning_interface::PlanningContext::setPlanningScene | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene | ) |
Set the planning scene for this context.
Definition at line 84 of file planning_interface.cpp.
|
pure virtual |
Solve the motion planning problem and store the detailed result in res. This function should not clear data structures before computing. The constructor and clear() do that.
Implemented in chomp_interface::CHOMPPlanningContext, ompl_interface::ModelBasedPlanningContext, pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >, pilz_industrial_motion_planner::PlanningContextBase< TrajectoryGeneratorCIRC >, pilz_industrial_motion_planner::PlanningContextBase< TrajectoryGeneratorLIN >, pilz_industrial_motion_planner::PlanningContextBase< TrajectoryGeneratorPTP >, stomp_moveit::StompPlanningContext, and planning_pipeline_test::DummyPlanningContext.
|
pure virtual |
Solve the motion planning problem and store the result in res. This function should not clear data structures before computing. The constructor and clear() do that.
Implemented in chomp_interface::CHOMPPlanningContext, ompl_interface::ModelBasedPlanningContext, pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >, pilz_industrial_motion_planner::PlanningContextBase< TrajectoryGeneratorCIRC >, pilz_industrial_motion_planner::PlanningContextBase< TrajectoryGeneratorLIN >, pilz_industrial_motion_planner::PlanningContextBase< TrajectoryGeneratorPTP >, stomp_moveit::StompPlanningContext, and planning_pipeline_test::DummyPlanningContext.
|
pure virtual |
If solve() is running, terminate the computation. Return false if termination not possible. No-op if solve() is not running (returns true).
Implemented in chomp_interface::CHOMPPlanningContext, ompl_interface::ModelBasedPlanningContext, pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >, pilz_industrial_motion_planner::PlanningContextBase< TrajectoryGeneratorCIRC >, pilz_industrial_motion_planner::PlanningContextBase< TrajectoryGeneratorLIN >, pilz_industrial_motion_planner::PlanningContextBase< TrajectoryGeneratorPTP >, stomp_moveit::StompPlanningContext, and planning_pipeline_test::DummyPlanningContext.
|
protected |
The group (as in the SRDF) this planning context is for.
Definition at line 136 of file planning_interface.h.
|
protected |
The name of this planning context.
Definition at line 133 of file planning_interface.h.
|
protected |
The planning scene for this context.
Definition at line 139 of file planning_interface.h.
|
protected |
The planning request for this context.
Definition at line 142 of file planning_interface.h.