35#include <rclcpp/logging.hpp>
43#include "cartesian_limits_parameters.hpp"
46#include <pluginlib/class_list_macros.hpp>
48#include <pluginlib/class_loader.hpp>
65 const std::string& ns)
81 params_ = param_listener_->get_params();
84 planner_context_loader_ = std::make_unique<pluginlib::ClassLoader<PlanningContextLoader>>(
85 "pilz_industrial_motion_planner",
"pilz_industrial_motion_planner::PlanningContextLoader");
88 const std::vector<std::string>& factories = planner_context_loader_->getDeclaredClasses();
90 for (
const auto& factory : factories)
95 RCLCPP_INFO_STREAM(getLogger(),
"Available plugins: " << ss.str());
98 for (
const auto& factory : factories)
100 RCLCPP_INFO_STREAM(getLogger(),
"About to load: " << factory);
107 loader_pointer->setLimits(limits);
108 loader_pointer->setModel(model_);
118 return "Pilz Industrial Motion Planner";
125 for (
const auto& context_loader : context_loader_map_)
127 algs.push_back(context_loader.first);
131planning_interface::PlanningContextPtr
133 const moveit_msgs::msg::MotionPlanRequest& req,
134 moveit_msgs::msg::MoveItErrorCodes& error_code)
const
138 RCLCPP_DEBUG(getLogger(),
"Loading PlanningContext");
143 RCLCPP_ERROR_STREAM(getLogger(),
"No ContextLoader for planner_id '" << req.planner_id.c_str()
144 <<
"' found. Planning not possible.");
148 planning_interface::PlanningContextPtr planning_context;
150 if (context_loader_map_.at(req.planner_id)->loadContext(planning_context, req.planner_id, req.group_name))
152 RCLCPP_DEBUG_STREAM(getLogger(),
153 "Found planning context loader for " << req.planner_id <<
" group:" << req.group_name);
154 planning_context->setMotionPlanRequest(req);
156 return planning_context;
160 error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
167 if (context_loader_map_.find(req.planner_id) == context_loader_map_.end())
169 RCLCPP_ERROR(getLogger(),
"Cannot service planning request because planner ID '%s' does not exist.",
170 req.planner_id.c_str());
174 if (req.group_name.empty())
176 RCLCPP_ERROR(getLogger(),
"Cannot service planning request because group name is not specified.");
180 auto joint_mode_group_ptr = model_->getJointModelGroup(req.group_name);
181 if (joint_mode_group_ptr ==
nullptr)
183 RCLCPP_ERROR(getLogger(),
"Cannot service planning request because group '%s' does not exist.",
184 req.group_name.c_str());
188 if (joint_mode_group_ptr->getSolverInstance() ==
nullptr)
190 RCLCPP_ERROR(getLogger(),
"Cannot service planning request because group '%s' does have an IK solver instance.",
191 req.group_name.c_str());
195 if (!req.trajectory_constraints.constraints.empty())
197 RCLCPP_ERROR(getLogger(),
198 "Cannot service planning request because PILZ does not support 'trajectory constraints'.");
209 if (context_loader_map_.find(planning_context_loader->getAlgorithm()) == context_loader_map_.end())
211 context_loader_map_[planning_context_loader->getAlgorithm()] = planning_context_loader;
212 RCLCPP_INFO_STREAM(getLogger(),
"Registered Algorithm [" << planning_context_loader->getAlgorithm() <<
']');
217 "] is already registered");
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
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.
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(cartesian_limits::Params &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)
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
std::shared_ptr< PlanningContextLoader > PlanningContextLoaderPtr
This namespace includes the central class for representing planning contexts.
const std::string PARAM_NAMESPACE_LIMITS