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

Base class for all PlanningContextLoaders. Since planning_interface::PlanningContext has a non empty ctor, classes derived from it can not be plugins. This class serves as base class for wrappers. More...

#include <planning_context_loader.h>

Inheritance diagram for pilz_industrial_motion_planner::PlanningContextLoader:
Inheritance graph
[legend]
Collaboration diagram for pilz_industrial_motion_planner::PlanningContextLoader:
Collaboration graph
[legend]

Public Member Functions

 PlanningContextLoader ()
 
virtual ~PlanningContextLoader ()
 
virtual std::string getAlgorithm () const
 Return the algorithm the loader uses. More...
 
virtual bool setModel (const moveit::core::RobotModelConstPtr &model)
 Sets the robot model that can be passed to the planning context. More...
 
virtual bool setLimits (const pilz_industrial_motion_planner::LimitsContainer &limits)
 Sets limits the planner can pass to the contexts. More...
 
virtual bool loadContext (planning_interface::PlanningContextPtr &planning_context, const std::string &name, const std::string &group) const =0
 Return the planning context. More...
 

Protected Member Functions

template<typename T >
bool loadContext (planning_interface::PlanningContextPtr &planning_context, const std::string &name, const std::string &group) const
 Return the planning context of type T. More...
 

Protected Attributes

std::string alg_
 Name of the algorithm. More...
 
bool limits_set_
 True if limits are set. More...
 
pilz_industrial_motion_planner::LimitsContainer limits_
 Limits to be used during planning. More...
 
bool model_set_
 True if model is set. More...
 
moveit::core::RobotModelConstPtr model_
 The robot model. More...
 

Detailed Description

Base class for all PlanningContextLoaders. Since planning_interface::PlanningContext has a non empty ctor, classes derived from it can not be plugins. This class serves as base class for wrappers.

Definition at line 54 of file planning_context_loader.h.

Constructor & Destructor Documentation

◆ PlanningContextLoader()

pilz_industrial_motion_planner::PlanningContextLoader::PlanningContextLoader ( )

Definition at line 37 of file planning_context_loader.cpp.

◆ ~PlanningContextLoader()

pilz_industrial_motion_planner::PlanningContextLoader::~PlanningContextLoader ( )
virtual

Definition at line 41 of file planning_context_loader.cpp.

Member Function Documentation

◆ getAlgorithm()

std::string pilz_industrial_motion_planner::PlanningContextLoader::getAlgorithm ( ) const
virtual

Return the algorithm the loader uses.

Definition at line 60 of file planning_context_loader.cpp.

◆ loadContext() [1/2]

template<typename T >
bool pilz_industrial_motion_planner::PlanningContextLoader::loadContext ( planning_interface::PlanningContextPtr &  planning_context,
const std::string &  name,
const std::string &  group 
) const
protected

Return the planning context of type T.

Parameters
planning_context
namecontext name
groupname of the planning group
Returns
true on success, false otherwise

Definition at line 121 of file planning_context_loader.h.

◆ loadContext() [2/2]

virtual bool pilz_industrial_motion_planner::PlanningContextLoader::loadContext ( planning_interface::PlanningContextPtr &  planning_context,
const std::string &  name,
const std::string &  group 
) const
pure virtual

Return the planning context.

Parameters
planning_context
namecontext name
groupname of the planning group
Returns
true on success, false otherwise

Implemented in pilz_industrial_motion_planner::PlanningContextLoaderPTP, pilz_industrial_motion_planner::PlanningContextLoaderLIN, and pilz_industrial_motion_planner::PlanningContextLoaderCIRC.

◆ setLimits()

bool pilz_industrial_motion_planner::PlanningContextLoader::setLimits ( const pilz_industrial_motion_planner::LimitsContainer limits)
virtual

Sets limits the planner can pass to the contexts.

Parameters
limitscontainer of limits, no guarantee to contain the limits for all joints of the model
Returns
true if limits could be set

Definition at line 52 of file planning_context_loader.cpp.

◆ setModel()

bool pilz_industrial_motion_planner::PlanningContextLoader::setModel ( const moveit::core::RobotModelConstPtr &  model)
virtual

Sets the robot model that can be passed to the planning context.

Parameters
modelThe robot model
Returns
false if could not be set

Definition at line 45 of file planning_context_loader.cpp.

Member Data Documentation

◆ alg_

std::string pilz_industrial_motion_planner::PlanningContextLoader::alg_
protected

Name of the algorithm.

Definition at line 102 of file planning_context_loader.h.

◆ limits_

pilz_industrial_motion_planner::LimitsContainer pilz_industrial_motion_planner::PlanningContextLoader::limits_
protected

Limits to be used during planning.

Definition at line 108 of file planning_context_loader.h.

◆ limits_set_

bool pilz_industrial_motion_planner::PlanningContextLoader::limits_set_
protected

True if limits are set.

Definition at line 105 of file planning_context_loader.h.

◆ model_

moveit::core::RobotModelConstPtr pilz_industrial_motion_planner::PlanningContextLoader::model_
protected

The robot model.

Definition at line 114 of file planning_context_loader.h.

◆ model_set_

bool pilz_industrial_motion_planner::PlanningContextLoader::model_set_
protected

True if model is set.

Definition at line 111 of file planning_context_loader.h.


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