84 const std::string & joint_name,
85 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
86 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf)
88 const std::string param_base_name =
"joint_limits." + joint_name;
91 auto_declare<bool>(param_itf, param_base_name +
".has_position_limits",
false);
93 param_itf, param_base_name +
".min_position", std::numeric_limits<double>::quiet_NaN());
95 param_itf, param_base_name +
".max_position", std::numeric_limits<double>::quiet_NaN());
96 auto_declare<bool>(param_itf, param_base_name +
".has_velocity_limits",
false);
98 param_itf, param_base_name +
".min_velocity", std::numeric_limits<double>::quiet_NaN());
100 param_itf, param_base_name +
".max_velocity", std::numeric_limits<double>::quiet_NaN());
101 auto_declare<bool>(param_itf, param_base_name +
".has_acceleration_limits",
false);
102 auto_declare<double>(
103 param_itf, param_base_name +
".max_acceleration", std::numeric_limits<double>::quiet_NaN());
104 auto_declare<bool>(param_itf, param_base_name +
".has_jerk_limits",
false);
105 auto_declare<double>(
106 param_itf, param_base_name +
".max_jerk", std::numeric_limits<double>::quiet_NaN());
107 auto_declare<bool>(param_itf, param_base_name +
".has_effort_limits",
false);
108 auto_declare<double>(
109 param_itf, param_base_name +
".max_effort", std::numeric_limits<double>::quiet_NaN());
110 auto_declare<bool>(param_itf, param_base_name +
".angle_wraparound",
false);
111 auto_declare<bool>(param_itf, param_base_name +
".has_soft_limits",
false);
112 auto_declare<double>(
113 param_itf, param_base_name +
".k_position", std::numeric_limits<double>::quiet_NaN());
114 auto_declare<double>(
115 param_itf, param_base_name +
".k_velocity", std::numeric_limits<double>::quiet_NaN());
116 auto_declare<double>(
117 param_itf, param_base_name +
".soft_lower_limit", std::numeric_limits<double>::quiet_NaN());
118 auto_declare<double>(
119 param_itf, param_base_name +
".soft_upper_limit", std::numeric_limits<double>::quiet_NaN());
121 catch (
const std::exception & ex)
123 RCLCPP_ERROR(logging_itf->get_logger(),
"%s", ex.what());
218 const std::string & joint_name,
219 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
220 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
223 const std::string param_base_name =
"joint_limits." + joint_name;
227 !param_itf->has_parameter(param_base_name +
".has_position_limits") &&
228 !param_itf->has_parameter(param_base_name +
".min_position") &&
229 !param_itf->has_parameter(param_base_name +
".max_position") &&
230 !param_itf->has_parameter(param_base_name +
".has_velocity_limits") &&
231 !param_itf->has_parameter(param_base_name +
".min_velocity") &&
232 !param_itf->has_parameter(param_base_name +
".max_velocity") &&
233 !param_itf->has_parameter(param_base_name +
".has_acceleration_limits") &&
234 !param_itf->has_parameter(param_base_name +
".max_acceleration") &&
235 !param_itf->has_parameter(param_base_name +
".has_jerk_limits") &&
236 !param_itf->has_parameter(param_base_name +
".max_jerk") &&
237 !param_itf->has_parameter(param_base_name +
".has_effort_limits") &&
238 !param_itf->has_parameter(param_base_name +
".max_effort") &&
239 !param_itf->has_parameter(param_base_name +
".angle_wraparound") &&
240 !param_itf->has_parameter(param_base_name +
".has_soft_limits") &&
241 !param_itf->has_parameter(param_base_name +
".k_position") &&
242 !param_itf->has_parameter(param_base_name +
".k_velocity") &&
243 !param_itf->has_parameter(param_base_name +
".soft_lower_limit") &&
244 !param_itf->has_parameter(param_base_name +
".soft_upper_limit"))
247 logging_itf->get_logger(),
248 "No joint limits specification found for joint '%s' in the parameter server "
250 joint_name.c_str(), param_base_name.c_str());
254 catch (
const std::exception & ex)
256 RCLCPP_ERROR(logging_itf->get_logger(),
"%s", ex.what());
261 if (param_itf->has_parameter(param_base_name +
".has_position_limits"))
263 limits.has_position_limits =
264 param_itf->get_parameter(param_base_name +
".has_position_limits").as_bool();
266 limits.has_position_limits && param_itf->has_parameter(param_base_name +
".min_position") &&
267 param_itf->has_parameter(param_base_name +
".max_position"))
269 limits.min_position = param_itf->get_parameter(param_base_name +
".min_position").as_double();
270 limits.max_position = param_itf->get_parameter(param_base_name +
".max_position").as_double();
274 limits.has_position_limits =
false;
278 !limits.has_position_limits &&
279 param_itf->has_parameter(param_base_name +
".angle_wraparound"))
281 limits.angle_wraparound =
282 param_itf->get_parameter(param_base_name +
".angle_wraparound").as_bool();
287 if (param_itf->has_parameter(param_base_name +
".has_velocity_limits"))
289 limits.has_velocity_limits =
290 param_itf->get_parameter(param_base_name +
".has_velocity_limits").as_bool();
291 if (limits.has_velocity_limits && param_itf->has_parameter(param_base_name +
".max_velocity"))
293 limits.max_velocity = param_itf->get_parameter(param_base_name +
".max_velocity").as_double();
297 limits.has_velocity_limits =
false;
302 if (param_itf->has_parameter(param_base_name +
".has_acceleration_limits"))
304 limits.has_acceleration_limits =
305 param_itf->get_parameter(param_base_name +
".has_acceleration_limits").as_bool();
307 limits.has_acceleration_limits &&
308 param_itf->has_parameter(param_base_name +
".max_acceleration"))
310 limits.max_acceleration =
311 param_itf->get_parameter(param_base_name +
".max_acceleration").as_double();
315 limits.has_acceleration_limits =
false;
320 if (param_itf->has_parameter(param_base_name +
".has_jerk_limits"))
322 limits.has_jerk_limits =
323 param_itf->get_parameter(param_base_name +
".has_jerk_limits").as_bool();
324 if (limits.has_jerk_limits && param_itf->has_parameter(param_base_name +
".max_jerk"))
326 limits.max_jerk = param_itf->get_parameter(param_base_name +
".max_jerk").as_double();
330 limits.has_jerk_limits =
false;
335 if (param_itf->has_parameter(param_base_name +
".has_effort_limits"))
337 limits.has_effort_limits =
338 param_itf->get_parameter(param_base_name +
".has_effort_limits").as_bool();
339 if (limits.has_effort_limits && param_itf->has_parameter(param_base_name +
".max_effort"))
341 limits.has_effort_limits =
true;
342 limits.max_effort = param_itf->get_parameter(param_base_name +
".max_effort").as_double();
346 limits.has_effort_limits =
false;
428 const std::string & joint_name,
429 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
430 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
433 const std::string param_base_name =
"joint_limits." + joint_name;
437 !param_itf->has_parameter(param_base_name +
".has_soft_limits") &&
438 !param_itf->has_parameter(param_base_name +
".k_velocity") &&
439 !param_itf->has_parameter(param_base_name +
".k_position") &&
440 !param_itf->has_parameter(param_base_name +
".soft_lower_limit") &&
441 !param_itf->has_parameter(param_base_name +
".soft_upper_limit"))
444 logging_itf->get_logger(),
445 "No soft joint limits specification found for joint '%s' in the parameter server "
447 joint_name.c_str(), param_base_name.c_str());
451 catch (
const std::exception & ex)
453 RCLCPP_ERROR(logging_itf->get_logger(),
"%s", ex.what());
458 if (param_itf->has_parameter(param_base_name +
".has_soft_limits"))
461 param_itf->get_parameter(param_base_name +
".has_soft_limits").as_bool() &&
462 param_itf->has_parameter(param_base_name +
".k_position") &&
463 param_itf->has_parameter(param_base_name +
".k_velocity") &&
464 param_itf->has_parameter(param_base_name +
".soft_lower_limit") &&
465 param_itf->has_parameter(param_base_name +
".soft_upper_limit"))
467 soft_limits.k_position =
468 param_itf->get_parameter(param_base_name +
".k_position").as_double();
469 soft_limits.k_velocity =
470 param_itf->get_parameter(param_base_name +
".k_velocity").as_double();
471 soft_limits.min_position =
472 param_itf->get_parameter(param_base_name +
".soft_lower_limit").as_double();
473 soft_limits.max_position =
474 param_itf->get_parameter(param_base_name +
".soft_upper_limit").as_double();