moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Protected Attributes | List of all members
planning_interface::PlanningContext Class Referenceabstract

Representation of a particular planning context – the planning scene and the request are known, solution is not yet computed. More...

#include <planning_interface.h>

Inheritance diagram for planning_interface::PlanningContext:
Inheritance graph
[legend]

Public Member Functions

 PlanningContext (const std::string &name, const std::string &group)
 Construct a planning context named name for the group group. More...
 
virtual ~PlanningContext ()
 
const std::string & getGroupName () const
 Get the name of the group this planning context is for. More...
 
const std::string & getName () const
 Get the name of this planning context. More...
 
const planning_scene::PlanningSceneConstPtr & getPlanningScene () const
 Get the planning scene associated to this planning context. More...
 
const MotionPlanRequestgetMotionPlanRequest () const
 Get the motion plan request associated to this planning context. More...
 
void setPlanningScene (const planning_scene::PlanningSceneConstPtr &planning_scene)
 Set the planning scene for this context. More...
 
void setMotionPlanRequest (const MotionPlanRequest &request)
 Set the planning request for this context. More...
 
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. More...
 
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. More...
 
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). More...
 
virtual void clear ()=0
 Clear the data structures used by the planner. More...
 

Protected Attributes

std::string name_
 The name of this planning context. More...
 
std::string group_
 The group (as in the SRDF) this planning context is for. More...
 
planning_scene::PlanningSceneConstPtr planning_scene_
 The planning scene for this context. More...
 
MotionPlanRequest request_
 The planning request for this context. More...
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ PlanningContext()

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.

◆ ~PlanningContext()

planning_interface::PlanningContext::~PlanningContext ( )
virtual

Definition at line 77 of file planning_interface.cpp.

Member Function Documentation

◆ clear()

virtual void planning_interface::PlanningContext::clear ( )
pure virtual

◆ getGroupName()

const std::string& planning_interface::PlanningContext::getGroupName ( ) const
inline

Get the name of the group this planning context is for.

Definition at line 87 of file planning_interface.h.

Here is the caller graph for this function:

◆ getMotionPlanRequest()

const MotionPlanRequest& planning_interface::PlanningContext::getMotionPlanRequest ( ) const
inline

Get the motion plan request associated to this planning context.

Definition at line 105 of file planning_interface.h.

Here is the caller graph for this function:

◆ getName()

const std::string& planning_interface::PlanningContext::getName ( ) const
inline

Get the name of this planning context.

Definition at line 93 of file planning_interface.h.

Here is the caller graph for this function:

◆ getPlanningScene()

const planning_scene::PlanningSceneConstPtr& planning_interface::PlanningContext::getPlanningScene ( ) const
inline

Get the planning scene associated to this planning context.

Definition at line 99 of file planning_interface.h.

Here is the caller graph for this function:

◆ setMotionPlanRequest()

void planning_interface::PlanningContext::setMotionPlanRequest ( const MotionPlanRequest request)

Set the planning request for this context.

Definition at line 89 of file planning_interface.cpp.

Here is the call graph for this function:

◆ setPlanningScene()

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.

Here is the caller graph for this function:

◆ solve() [1/2]

virtual void planning_interface::PlanningContext::solve ( MotionPlanDetailedResponse res)
pure virtual

◆ solve() [2/2]

virtual void planning_interface::PlanningContext::solve ( MotionPlanResponse res)
pure virtual

◆ terminate()

virtual bool planning_interface::PlanningContext::terminate ( )
pure virtual

Member Data Documentation

◆ group_

std::string planning_interface::PlanningContext::group_
protected

The group (as in the SRDF) this planning context is for.

Definition at line 136 of file planning_interface.h.

◆ name_

std::string planning_interface::PlanningContext::name_
protected

The name of this planning context.

Definition at line 133 of file planning_interface.h.

◆ planning_scene_

planning_scene::PlanningSceneConstPtr planning_interface::PlanningContext::planning_scene_
protected

The planning scene for this context.

Definition at line 139 of file planning_interface.h.

◆ request_

MotionPlanRequest planning_interface::PlanningContext::request_
protected

The planning request for this context.

Definition at line 142 of file planning_interface.h.


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