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>
48 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.robot_model_loader");
51 bool load_kinematics_solvers)
55 opt.load_kinematics_solvers_ = load_kinematics_solvers;
73 kinematics_loader_.reset();
83 RCLCPP_ERROR(LOGGER,
"Cannot specify position limits for orientation of planar joint '%s'",
88 RCLCPP_ERROR(LOGGER,
"Cannot specify position limits for orientation of floating joint '%s'",
94 RCLCPP_ERROR(LOGGER,
"Cannot specify position limits for continuous joint '%s'", jmodel->
getName().c_str());
104 void RobotModelLoader::configure(
const Options&
opt)
107 rclcpp::Time start = clock.now();
108 if (!
opt.urdf_string_.empty() && !
opt.srdf_string_.empty())
109 rdf_loader_ = std::make_shared<rdf_loader::RDFLoader>(
opt.urdf_string_,
opt.srdf_string_);
111 rdf_loader_ = std::make_shared<rdf_loader::RDFLoader>(node_,
opt.robot_description_);
112 if (rdf_loader_->getURDF())
114 const srdf::ModelSharedPtr& srdf =
115 rdf_loader_->getSRDF() ? rdf_loader_->getSRDF() : std::make_shared<srdf::Model>();
116 model_ = std::make_shared<moveit::core::RobotModel>(rdf_loader_->getURDF(), srdf);
119 if (model_ && !rdf_loader_->getRobotDescription().empty())
124 std::vector<moveit_msgs::msg::JointLimits> joint_limit = joint_model->getVariableBoundsMsg();
125 for (std::size_t joint_id = 0; joint_id < joint_limit.size(); ++joint_id)
128 rdf_loader_->getRobotDescription() +
"_planning.joint_limits." + joint_limit[joint_id].joint_name +
".";
130 std::string param_name;
133 param_name = prefix +
"max_position";
134 if (!node_->has_parameter(param_name))
136 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_DOUBLE);
139 if (node_->get_parameter(param_name, max_position))
141 if (canSpecifyPosition(joint_model, joint_id))
143 joint_limit[joint_id].has_position_limits =
true;
144 joint_limit[joint_id].max_position = max_position;
148 param_name = prefix +
"min_position";
149 if (!node_->has_parameter(param_name))
151 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_DOUBLE);
154 if (node_->get_parameter(param_name, min_position))
156 if (canSpecifyPosition(joint_model, joint_id))
158 joint_limit[joint_id].has_position_limits =
true;
159 joint_limit[joint_id].min_position = min_position;
164 param_name = prefix +
"has_velocity_limits";
165 if (!node_->has_parameter(param_name))
167 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_BOOL);
169 bool has_vel_limits =
false;
170 if (node_->get_parameter(param_name, has_vel_limits))
171 joint_limit[joint_id].has_velocity_limits = has_vel_limits;
173 param_name = prefix +
"has_acceleration_limits";
174 if (!node_->has_parameter(param_name))
176 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_BOOL);
178 bool has_acc_limits =
false;
179 if (node_->get_parameter(param_name, has_acc_limits))
180 joint_limit[joint_id].has_acceleration_limits = has_acc_limits;
182 param_name = prefix +
"has_jerk_limits";
183 if (!node_->has_parameter(param_name))
185 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_BOOL);
187 bool has_jerk_limits =
false;
188 if (node_->get_parameter(param_name, has_jerk_limits))
189 joint_limit[joint_id].has_jerk_limits = has_jerk_limits;
193 param_name = prefix +
"max_velocity";
194 if (!node_->has_parameter(param_name))
196 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_DOUBLE);
199 if (!node_->get_parameter(param_name, joint_limit[joint_id].max_velocity))
201 RCLCPP_ERROR(LOGGER,
"Specified a velocity limit for joint: %s but did not set a max velocity",
202 joint_limit[joint_id].joint_name.c_str());
208 param_name = prefix +
"max_acceleration";
209 if (!node_->has_parameter(param_name))
211 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_DOUBLE);
214 if (!node_->get_parameter(param_name, joint_limit[joint_id].max_acceleration))
216 RCLCPP_ERROR(LOGGER,
"Specified an acceleration limit for joint: %s but did not set a max acceleration",
217 joint_limit[joint_id].joint_name.c_str());
223 param_name = prefix +
"max_jerk";
224 if (!node_->has_parameter(param_name))
226 node_->declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_DOUBLE);
229 if (!node_->get_parameter(param_name, joint_limit[joint_id].max_jerk))
231 RCLCPP_ERROR(LOGGER,
"Specified a jerk limit for joint: %s but did not set a max jerk",
232 joint_limit[joint_id].joint_name.c_str());
236 catch (
const rclcpp::ParameterTypeException& e)
238 RCLCPP_ERROR_STREAM(LOGGER,
"When getting the parameter " << param_name.c_str() <<
": " << e.what());
241 joint_model->setVariableBounds(joint_limit);
245 if (model_ &&
opt.load_kinematics_solvers_)
248 RCLCPP_DEBUG(node_->get_logger(),
"Loaded kinematic model in %f seconds", (clock.now() - start).seconds());
253 if (rdf_loader_ && model_)
257 kinematics_loader_ = kloader;
260 std::make_shared<kinematics_plugin_loader::KinematicsPluginLoader>(node_, rdf_loader_->getRobotDescription());
262 kinematics_loader_->getLoaderFunction(rdf_loader_->getSRDF());
263 const std::vector<std::string>& groups = kinematics_loader_->getKnownGroups();
264 std::stringstream ss;
265 std::copy(groups.begin(), groups.end(), std::ostream_iterator<std::string>(ss,
" "));
266 RCLCPP_DEBUG(LOGGER,
"Loaded information about the following groups: '%s' ", ss.str().c_str());
267 if (groups.empty() && !model_->getJointModelGroups().empty())
268 RCLCPP_WARN(LOGGER,
"No kinematics plugins defined. Fill and load kinematics.yaml!");
270 std::map<std::string, moveit::core::SolverAllocatorFn> imap;
271 for (
const std::string&
group : groups)
274 if (!model_->hasJointModelGroup(
group))
279 kinematics::KinematicsBasePtr solver = kinematics_allocator(jmg);
282 std::string error_msg;
283 if (solver->supportsGroup(jmg, &error_msg))
285 imap[
group] = kinematics_allocator;
289 const auto& s = *solver;
290 RCLCPP_ERROR(LOGGER,
"Kinematics solver %s does not support joint group %s. Error: %s",
typeid(s).
name(),
291 group.c_str(), error_msg.c_str());
296 RCLCPP_ERROR(LOGGER,
"Kinematics solver could not be instantiated for joint group %s.",
group.c_str());
299 model_->setKinematicsAllocators(imap);
302 const std::map<std::string, double>& timeout = kinematics_loader_->getIKTimeout();
303 for (
const std::pair<const std::string, double>& it : timeout)
305 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.
const rclcpp::Logger LOGGER
Structure that encodes the options to be passed to the RobotModelLoader constructor.