38#include <rclcpp/clock.hpp>
39#include <rclcpp/duration.hpp>
40#include <rclcpp/logger.hpp>
41#include <rclcpp/logging.hpp>
42#include <rclcpp/parameter_value.hpp>
43#include <rclcpp/time.hpp>
51 bool load_kinematics_solvers)
52 : node_(node), logger_(
moveit::getLogger(
"moveit.ros.robot_model_loader"))
60 : node_(node), logger_(
moveit::getLogger(
"moveit.ros.robot_model_loader"))
74 kinematics_loader_.reset();
79bool canSpecifyPosition(
const moveit::core::JointModel* jmodel,
const unsigned int index,
const rclcpp::Logger& logger)
84 RCLCPP_ERROR(logger,
"Cannot specify position limits for orientation of planar joint '%s'",
89 RCLCPP_ERROR(logger,
"Cannot specify position limits for orientation of floating joint '%s'",
95 RCLCPP_ERROR(logger,
"Cannot specify position limits for continuous joint '%s'", jmodel->
getName().c_str());
105void RobotModelLoader::configure(
const Options& opt)
108 rclcpp::Time start = clock.now();
109 if (!opt.urdf_string_.empty() && !opt.srdf_string.empty())
111 rdf_loader_ = std::make_shared<rdf_loader::RDFLoader>(opt.urdf_string_, opt.srdf_string);
115 rdf_loader_ = std::make_shared<rdf_loader::RDFLoader>(node_, opt.robot_description);
117 if (rdf_loader_->getURDF())
119 const srdf::ModelSharedPtr& srdf =
120 rdf_loader_->getSRDF() ? rdf_loader_->getSRDF() : std::make_shared<srdf::Model>();
121 model_ = std::make_shared<moveit::core::RobotModel>(rdf_loader_->getURDF(), srdf);
124 if (model_ && !rdf_loader_->getRobotDescription().empty())
129 std::vector<moveit_msgs::msg::JointLimits> joint_limit = joint_model->getVariableBoundsMsg();
130 for (std::size_t joint_id = 0; joint_id < joint_limit.size(); ++joint_id)
133 rdf_loader_->getRobotDescription() +
"_planning.joint_limits." + joint_limit[joint_id].joint_name +
".";
135 std::string param_name;
138 param_name = prefix +
"max_position";
139 if (!node_->has_parameter(param_name))
141 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_DOUBLE);
144 if (node_->get_parameter(param_name, max_position))
146 if (canSpecifyPosition(joint_model, joint_id, logger_))
148 joint_limit[joint_id].has_position_limits =
true;
149 joint_limit[joint_id].max_position = max_position;
153 param_name = prefix +
"min_position";
154 if (!node_->has_parameter(param_name))
156 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_DOUBLE);
159 if (node_->get_parameter(param_name, min_position))
161 if (canSpecifyPosition(joint_model, joint_id, logger_))
163 joint_limit[joint_id].has_position_limits =
true;
164 joint_limit[joint_id].min_position = min_position;
169 param_name = prefix +
"has_velocity_limits";
170 if (!node_->has_parameter(param_name))
172 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_BOOL);
174 bool has_vel_limits =
false;
175 if (node_->get_parameter(param_name, has_vel_limits))
176 joint_limit[joint_id].has_velocity_limits = has_vel_limits;
178 param_name = prefix +
"has_acceleration_limits";
179 if (!node_->has_parameter(param_name))
181 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_BOOL);
183 bool has_acc_limits =
false;
184 if (node_->get_parameter(param_name, has_acc_limits))
185 joint_limit[joint_id].has_acceleration_limits = has_acc_limits;
187 param_name = prefix +
"has_jerk_limits";
188 if (!node_->has_parameter(param_name))
190 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_BOOL);
192 bool has_jerk_limits =
false;
193 if (node_->get_parameter(param_name, has_jerk_limits))
194 joint_limit[joint_id].has_jerk_limits = has_jerk_limits;
198 param_name = prefix +
"max_velocity";
199 if (!node_->has_parameter(param_name))
201 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_DOUBLE);
204 if (!node_->get_parameter(param_name, joint_limit[joint_id].max_velocity))
206 RCLCPP_ERROR(logger_,
"Specified a velocity limit for joint: %s but did not set a max velocity",
207 joint_limit[joint_id].joint_name.c_str());
213 param_name = prefix +
"max_acceleration";
214 if (!node_->has_parameter(param_name))
216 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_DOUBLE);
219 if (!node_->get_parameter(param_name, joint_limit[joint_id].max_acceleration))
221 RCLCPP_ERROR(logger_,
"Specified an acceleration limit for joint: %s but did not set a max acceleration",
222 joint_limit[joint_id].joint_name.c_str());
228 param_name = prefix +
"max_jerk";
229 if (!node_->has_parameter(param_name))
231 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_DOUBLE);
234 if (!node_->get_parameter(param_name, joint_limit[joint_id].max_jerk))
236 RCLCPP_ERROR(logger_,
"Specified a jerk limit for joint: %s but did not set a max jerk",
237 joint_limit[joint_id].joint_name.c_str());
241 catch (
const rclcpp::ParameterTypeException& e)
243 RCLCPP_ERROR_STREAM(logger_,
"When getting the parameter " << param_name.c_str() <<
": " << e.what());
246 joint_model->setVariableBounds(joint_limit);
250 if (model_ && opt.load_kinematics_solvers)
253 RCLCPP_DEBUG(logger_,
"Loaded kinematic model in %f seconds", (clock.now() - start).seconds());
258 if (rdf_loader_ && model_)
263 kinematics_loader_ = kloader;
268 std::make_shared<kinematics_plugin_loader::KinematicsPluginLoader>(node_, rdf_loader_->getRobotDescription());
271 kinematics_loader_->getLoaderFunction(rdf_loader_->getSRDF());
272 const std::vector<std::string>& groups = kinematics_loader_->getKnownGroups();
273 std::stringstream ss;
274 std::copy(groups.begin(), groups.end(), std::ostream_iterator<std::string>(ss,
" "));
275 RCLCPP_DEBUG(logger_,
"Loaded information about the following groups: '%s' ", ss.str().c_str());
276 if (groups.empty() && !model_->getJointModelGroups().empty())
277 RCLCPP_WARN(logger_,
"No kinematics plugins defined. Fill and load kinematics.yaml!");
279 std::map<std::string, moveit::core::SolverAllocatorFn> imap;
280 for (
const std::string& group : groups)
283 if (!model_->hasJointModelGroup(group))
288 kinematics::KinematicsBasePtr solver = kinematics_allocator(jmg);
291 std::string error_msg;
292 if (solver->supportsGroup(jmg, &error_msg))
294 imap[group] = kinematics_allocator;
298 const auto& s = *solver;
299 RCLCPP_ERROR(logger_,
"Kinematics solver %s does not support joint group %s. Error: %s",
typeid(s).name(),
300 group.c_str(), error_msg.c_str());
305 RCLCPP_ERROR(logger_,
"Kinematics solver could not be instantiated for joint group %s.", group.c_str());
308 model_->setKinematicsAllocators(imap);
311 const std::map<std::string, double>& timeout = kinematics_loader_->getIKTimeout();
312 for (
const std::pair<const std::string, double>& it : timeout)
314 if (!model_->hasJointModelGroup(it.first))
void setDefaultIKTimeout(double ik_timeout)
Set the default IK timeout.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
const std::string & getName() const
Get the name of the joint.
JointType getType() const
Get the type of joint.
bool isContinuous() const
Check if this joint wraps around.
RobotModelLoader(const rclcpp::Node::SharedPtr &node, const Options &opt=Options())
Default constructor.
void loadKinematicsSolvers(const kinematics_plugin_loader::KinematicsPluginLoaderPtr &kloader=kinematics_plugin_loader::KinematicsPluginLoaderPtr())
Load the kinematics solvers into the kinematic model. This is done by default, unless disabled explic...
std::function< kinematics::KinematicsBasePtr(const JointModelGroup *)> SolverAllocatorFn
Function type that allocates a kinematics solver for a particular group.
Main namespace for MoveIt.
Structure that encodes the options to be passed to the RobotModelLoader constructor.
bool load_kinematics_solvers
Flag indicating whether the kinematics solvers should be loaded as well, using specified ROS paramete...