moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Public Attributes | Protected Attributes | List of all members
pilz_industrial_motion_planner::PlanningContextBase< GeneratorT > Class Template Reference

PlanningContext for obtaining trajectories. More...

#include <planning_context_base.h>

Inheritance diagram for pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >:
Inheritance graph
[legend]
Collaboration diagram for pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >:
Collaboration graph
[legend]

Public Member Functions

 PlanningContextBase (const std::string &name, const std::string &group, const moveit::core::RobotModelConstPtr &model, const pilz_industrial_motion_planner::LimitsContainer &limits)
 
 ~PlanningContextBase () override
 
bool solve (planning_interface::MotionPlanResponse &res) override
 Calculates a trajectory for the request this context is currently set for. More...
 
bool solve (planning_interface::MotionPlanDetailedResponse &res) override
 Will return the same trajectory as solve(planning_interface::MotionPlanResponse& res) This function just delegates to the common response however here the same trajectory is stored with the descriptions "plan", "simplify", "interpolate". More...
 
bool terminate () override
 Will terminate solve() More...
 
void clear () override
 Clear the data structures used by the planner. More...
 
- Public Member Functions inherited from planning_interface::PlanningContext
 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...
 

Public Attributes

std::atomic_bool terminated_
 Flag if terminated. More...
 
moveit::core::RobotModelConstPtr model_
 The robot model. More...
 
pilz_industrial_motion_planner::LimitsContainer limits_
 Joint limits to be used during planning. More...
 

Protected Attributes

GeneratorT generator_
 
- Protected Attributes inherited from planning_interface::PlanningContext
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

template<typename GeneratorT>
class pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >

PlanningContext for obtaining trajectories.

Definition at line 56 of file planning_context_base.h.

Constructor & Destructor Documentation

◆ PlanningContextBase()

template<typename GeneratorT >
pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >::PlanningContextBase ( const std::string &  name,
const std::string &  group,
const moveit::core::RobotModelConstPtr &  model,
const pilz_industrial_motion_planner::LimitsContainer limits 
)
inline

Definition at line 177 of file planning_context_base.h.

◆ ~PlanningContextBase()

template<typename GeneratorT >
pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >::~PlanningContextBase ( )
inlineoverride

Definition at line 70 of file planning_context_base.h.

Member Function Documentation

◆ clear()

template<typename GeneratorT >
void pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >::clear
overridevirtual

Clear the data structures used by the planner.

Implements planning_interface::PlanningContext.

Definition at line 177 of file planning_context_base.h.

◆ solve() [1/2]

template<typename GeneratorT >
bool pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >::solve ( planning_interface::MotionPlanDetailedResponse res)
overridevirtual

Will return the same trajectory as solve(planning_interface::MotionPlanResponse& res) This function just delegates to the common response however here the same trajectory is stored with the descriptions "plan", "simplify", "interpolate".

Parameters
resThe detailed response
Returns
true on success, false otherwise

Implements planning_interface::PlanningContext.

Definition at line 144 of file planning_context_base.h.

◆ solve() [2/2]

template<typename GeneratorT >
bool pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >::solve ( planning_interface::MotionPlanResponse res)
overridevirtual

Calculates a trajectory for the request this context is currently set for.

Parameters
resThe result containing the respective trajectory, or error_code on failure
Returns
true on success, false otherwise

Implements planning_interface::PlanningContext.

Definition at line 120 of file planning_context_base.h.

Here is the call graph for this function:

◆ terminate()

template<typename GeneratorT >
bool pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >::terminate
overridevirtual

Will terminate solve()

Returns
Note
Currently will not stop a running solve but not start future solves.

Implements planning_interface::PlanningContext.

Definition at line 168 of file planning_context_base.h.

Member Data Documentation

◆ generator_

template<typename GeneratorT >
GeneratorT pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >::generator_
protected

Definition at line 116 of file planning_context_base.h.

◆ limits_

Joint limits to be used during planning.

Definition at line 113 of file planning_context_base.h.

◆ model_

template<typename GeneratorT >
moveit::core::RobotModelConstPtr pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >::model_

The robot model.

Definition at line 110 of file planning_context_base.h.

◆ terminated_

template<typename GeneratorT >
std::atomic_bool pilz_industrial_motion_planner::PlanningContextBase< GeneratorT >::terminated_

Flag if terminated.

Definition at line 107 of file planning_context_base.h.


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