moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
pilz_industrial_motion_planner::CommandPlanner Class Reference

MoveIt Plugin for Planning with Standard Robot Commands This planner is dedicated to return a instance of PlanningContext that corresponds to the requested motion command set as planner_id in the MotionPlanRequest). It can be easily extended with additional commands by creating a class inheriting from PlanningContextLoader. More...

#include <pilz_industrial_motion_planner.h>

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

Public Member Functions

 ~CommandPlanner () override
 
bool initialize (const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string &ns) override
 Initializes the planner Upon initialization this planner will look for plugins implementing pilz_industrial_motion_planner::PlanningContextLoader. More...
 
std::string getDescription () const override
 Description of the planner. More...
 
void getPlanningAlgorithms (std::vector< std::string > &algs) const override
 Returns the available planning commands. More...
 
planning_interface::PlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code) const override
 Returns a PlanningContext that can be used to solve(calculate) the trajectory that corresponds to command given in motion request as planner_id. More...
 
bool canServiceRequest (const planning_interface::MotionPlanRequest &req) const override
 Checks if the request can be handled. More...
 
void registerContextLoader (const pilz_industrial_motion_planner::PlanningContextLoaderPtr &planning_context_loader)
 Register a PlanningContextLoader to be used by the CommandPlanner. More...
 
- Public Member Functions inherited from planning_interface::PlannerManager
 PlannerManager ()
 
virtual ~PlannerManager ()
 
PlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req) const
 Calls the function above but ignores the error_code. More...
 
virtual void setPlannerConfigurations (const PlannerConfigurationMap &pcs)
 Specify the settings to be used for specific algorithms. More...
 
const PlannerConfigurationMapgetPlannerConfigurations () const
 Get the settings for a specific algorithm. More...
 
void terminate () const
 Request termination, if a solve() function is currently computing plans. More...
 

Additional Inherited Members

- Protected Attributes inherited from planning_interface::PlannerManager
PlannerConfigurationMap config_settings_
 All the existing planning configurations. The name of the configuration is the key of the map. This name can be of the form "group_name[config_name]" if there are particular configurations specified for a group, or of the form "group_name" if default settings are to be used. More...
 

Detailed Description

MoveIt Plugin for Planning with Standard Robot Commands This planner is dedicated to return a instance of PlanningContext that corresponds to the requested motion command set as planner_id in the MotionPlanRequest). It can be easily extended with additional commands by creating a class inheriting from PlanningContextLoader.

Definition at line 60 of file pilz_industrial_motion_planner.h.

Constructor & Destructor Documentation

◆ ~CommandPlanner()

pilz_industrial_motion_planner::CommandPlanner::~CommandPlanner ( )
inlineoverride

Definition at line 63 of file pilz_industrial_motion_planner.h.

Member Function Documentation

◆ canServiceRequest()

bool pilz_industrial_motion_planner::CommandPlanner::canServiceRequest ( const planning_interface::MotionPlanRequest req) const
overridevirtual

Checks if the request can be handled.

Parameters
motionrequest containing the planning_id that corresponds to the motion command
Returns
true if the request can be handled

Implements planning_interface::PlannerManager.

Definition at line 165 of file pilz_industrial_motion_planner.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getDescription()

std::string pilz_industrial_motion_planner::CommandPlanner::getDescription ( ) const
overridevirtual

Description of the planner.

Implements planning_interface::PlannerManager.

Definition at line 116 of file pilz_industrial_motion_planner.cpp.

◆ getPlanningAlgorithms()

void pilz_industrial_motion_planner::CommandPlanner::getPlanningAlgorithms ( std::vector< std::string > &  algs) const
overridevirtual

Returns the available planning commands.

Parameters
listwith the planning algorithms
Note
behined each command is a pilz_industrial_motion_planner::PlanningContextLoader loaded as plugin

Reimplemented from planning_interface::PlannerManager.

Definition at line 121 of file pilz_industrial_motion_planner.cpp.

◆ getPlanningContext()

planning_interface::PlanningContextPtr pilz_industrial_motion_planner::CommandPlanner::getPlanningContext ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
moveit_msgs::msg::MoveItErrorCodes &  error_code 
) const
overridevirtual

Returns a PlanningContext that can be used to solve(calculate) the trajectory that corresponds to command given in motion request as planner_id.

Parameters
planning_scene
req
error_code
Returns

Implements planning_interface::PlannerManager.

Definition at line 132 of file pilz_industrial_motion_planner.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ initialize()

bool pilz_industrial_motion_planner::CommandPlanner::initialize ( const moveit::core::RobotModelConstPtr &  model,
const rclcpp::Node::SharedPtr &  node,
const std::string &  ns 
)
overridevirtual

Initializes the planner Upon initialization this planner will look for plugins implementing pilz_industrial_motion_planner::PlanningContextLoader.

Parameters
modelThe robot model
nodeThe node
nsThe namespace
Returns
true on success, false otherwise

Reimplemented from planning_interface::PlannerManager.

Definition at line 64 of file pilz_industrial_motion_planner.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ registerContextLoader()

void pilz_industrial_motion_planner::CommandPlanner::registerContextLoader ( const pilz_industrial_motion_planner::PlanningContextLoaderPtr planning_context_loader)

Register a PlanningContextLoader to be used by the CommandPlanner.

Parameters
planning_context_loader
Exceptions
ContextLoaderRegistrationExceptionif a loader with the same algorithm name is already registered

Definition at line 205 of file pilz_industrial_motion_planner.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

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