35 #include <rclcpp/logging.hpp>
46 #include <pluginlib/class_list_macros.hpp>
48 #include <pluginlib/class_loader.hpp>
54 static const std::string PARAM_NAMESPACE_LIMITS =
"robot_description_planning";
55 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit.pilz_industrial_motion_planner");
58 const std::string& ns)
69 node, PARAM_NAMESPACE_LIMITS, model->getActiveJointModels());
76 planner_context_loader = std::make_unique<pluginlib::ClassLoader<PlanningContextLoader>>(
77 "pilz_industrial_motion_planner",
"pilz_industrial_motion_planner::PlanningContextLoader");
80 const std::vector<std::string>& factories = planner_context_loader->getDeclaredClasses();
82 for (
const auto& factory : factories)
87 RCLCPP_INFO_STREAM(LOGGER,
"Available plugins: " << ss.str());
90 for (
const auto& factory : factories)
92 RCLCPP_INFO_STREAM(LOGGER,
"About to load: " << factory);
99 loader_pointer->setLimits(limits);
100 loader_pointer->setModel(model_);
108 for (
const auto&
group : model_->getJointModelGroupNames())
111 group,
group, std::map<std::string, std::string>()
113 pconfig[planner_config_settings.name] = planner_config_settings;
123 return "Pilz Industrial Motion Planner";
130 for (
const auto& context_loader : context_loader_map_)
132 algs.push_back(context_loader.first);
136 planning_interface::PlanningContextPtr
139 moveit_msgs::msg::MoveItErrorCodes& error_code)
const
143 RCLCPP_DEBUG(LOGGER,
"Loading PlanningContext");
148 RCLCPP_ERROR_STREAM(LOGGER,
"No ContextLoader for planner_id '" << req.planner_id.c_str()
149 <<
"' found. Planning not possible.");
153 planning_interface::PlanningContextPtr planning_context;
155 if (context_loader_map_.at(req.planner_id)->loadContext(planning_context, req.planner_id, req.group_name))
157 RCLCPP_DEBUG_STREAM(LOGGER,
"Found planning context loader for " << req.planner_id <<
" group:" << req.group_name);
158 planning_context->setMotionPlanRequest(req);
160 return planning_context;
164 error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
171 return context_loader_map_.find(req.planner_id) != context_loader_map_.end();
178 if (context_loader_map_.find(planning_context_loader->getAlgorithm()) == context_loader_map_.end())
180 context_loader_map_[planning_context_loader->getAlgorithm()] = planning_context_loader;
181 RCLCPP_INFO_STREAM(LOGGER,
"Registered Algorithm [" << planning_context_loader->getAlgorithm() <<
"]");
186 "] is already registered");
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
static CartesianLimit getAggregatedLimits(const rclcpp::Node::SharedPtr &node, const std::string ¶m_namespace)
Loads cartesian limits from the node parameters.
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.
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.
static JointLimitsContainer getAggregatedLimits(const rclcpp::Node::SharedPtr &node, const std::string ¶m_namespace, const std::vector< const moveit::core::JointModel * > &joint_models)
Aggregates(combines) the joint limits from joint model and node parameters. The rules for the combina...
This class combines CartesianLimit and JointLimits into on single class.
void setCartesianLimits(CartesianLimit &cartesian_limit)
Set cartesian limits.
void setJointLimits(JointLimitsContainer &joint_limits)
Set joint limits.
Base class for a MoveIt planner.
virtual bool initialize(const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace)
PlannerConfigurationMap config_settings_
All the existing planning configurations. The name of the configuration is the key of the map....
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.
Specify the settings for a particular planning algorithm, for a particular group. The Planner plugin ...