37 #include <rclcpp/rclcpp.hpp> 
   45 #include <pluginlib/class_loader.hpp> 
   74   bool initialize(
const moveit::core::RobotModelConstPtr& model, 
const rclcpp::Node::SharedPtr& node,
 
   75                   const std::string& ns) 
override;
 
   97   planning_interface::PlanningContextPtr
 
  100                      moveit_msgs::msg::MoveItErrorCodes& error_code) 
const override;
 
  126   std::unique_ptr<pluginlib::ClassLoader<PlanningContextLoader>> planner_context_loader;
 
  129   std::map<std::string, pilz_industrial_motion_planner::PlanningContextLoaderPtr> context_loader_map_;
 
  132   moveit::core::RobotModelConstPtr model_;
 
  135   std::string namespace_;
 
Set of cartesian limits, has values for velocity, acceleration and deceleration of both the translati...
 
MoveIt Plugin for Planning with Standard Robot Commands This planner is dedicated to return a instanc...
 
bool canServiceRequest(const planning_interface::MotionPlanRequest &req) const override
Checks if the request can be handled.
 
~CommandPlanner() override
 
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pcs) override
Specify the settings to be used for an 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 com...
 
void getPlanningAlgorithms(std::vector< std::string > &algs) const override
Returns the available planning commands.
 
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_indu...
 
void registerContextLoader(const pilz_industrial_motion_planner::PlanningContextLoaderPtr &planning_context_loader)
Register a PlanningContextLoader to be used by the CommandPlanner.
 
std::string getDescription() const override
Description of the planner.
 
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
 
Base class for a MoveIt planner.
 
MOVEIT_CLASS_FORWARD(CommandPlanner)
 
std::shared_ptr< PlanningContextLoader > PlanningContextLoaderPtr
 
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
 
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
 
This namespace includes the central class for representing planning contexts.