|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
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>


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... | |
| void | setPlannerConfigurations (const planning_interface::PlannerConfigurationMap &pcs) override |
| Specify the settings to be used for an algorithms. 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... | |
| const PlannerConfigurationMap & | getPlannerConfigurations () 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... | |
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 58 of file pilz_industrial_motion_planner.h.
|
inlineoverride |
Definition at line 61 of file pilz_industrial_motion_planner.h.
|
overridevirtual |
Checks if the request can be handled.
| motion | request containing the planning_id that corresponds to the motion command |
Implements planning_interface::PlannerManager.
Definition at line 169 of file pilz_industrial_motion_planner.cpp.

|
overridevirtual |
Description of the planner.
Reimplemented from planning_interface::PlannerManager.
Definition at line 121 of file pilz_industrial_motion_planner.cpp.
|
overridevirtual |
Returns the available planning commands.
| list | with the planning algorithms |
Reimplemented from planning_interface::PlannerManager.
Definition at line 126 of file pilz_industrial_motion_planner.cpp.
|
overridevirtual |
Returns a PlanningContext that can be used to solve(calculate) the trajectory that corresponds to command given in motion request as planner_id.
| planning_scene | |
| req | |
| error_code |
Implements planning_interface::PlannerManager.
Definition at line 137 of file pilz_industrial_motion_planner.cpp.


|
overridevirtual |
Initializes the planner Upon initialization this planner will look for plugins implementing pilz_industrial_motion_planner::PlanningContextLoader.
| model | The robot model |
| node | The node |
| ns | The namespace |
Reimplemented from planning_interface::PlannerManager.
Definition at line 57 of file pilz_industrial_motion_planner.cpp.

| 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.
| planning_context_loader |
| ContextLoaderRegistrationException | if a loader with the same algorithm name is already registered |
Definition at line 174 of file pilz_industrial_motion_planner.cpp.

|
overridevirtual |
Specify the settings to be used for an algorithms.
| pcs | Map of planner configurations |
Implements planning_interface::PlannerManager.
Definition at line 190 of file pilz_industrial_motion_planner.cpp.
