Class CommandPlanner

Inheritance Relationships

Base Type

  • public planning_interface::PlannerManager

Class Documentation

class CommandPlanner : public planning_interface::PlannerManager

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.

Public Functions

inline ~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.

Parameters:
  • model – The robot model

  • node – The node

  • ns – The namespace

Returns:

true on success, false otherwise

std::string getDescription() const override

Description of the planner.

void getPlanningAlgorithms(std::vector<std::string> &algs) const override

Returns the available planning commands.

Note

behined each command is a pilz_industrial_motion_planner::PlanningContextLoader loaded as plugin

Parameters:

list – with the planning algorithms

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.

Parameters:
  • planning_scene

  • req

  • error_code

Returns:

bool canServiceRequest(const planning_interface::MotionPlanRequest &req) const override

Checks if the request can be handled.

Parameters:

motion – request containing the planning_id that corresponds to the motion command

Returns:

true if the request can be handled

void registerContextLoader(const pilz_industrial_motion_planner::PlanningContextLoaderPtr &planning_context_loader)

Register a PlanningContextLoader to be used by the CommandPlanner.

Parameters:

planning_context_loader

Throws:

ContextLoaderRegistrationException – if a loader with the same algorithm name is already registered