87 const std::string & joint_name,
88 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
89 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf)
91 const std::string param_base_name =
"joint_limits." + joint_name;
94 auto_declare<bool>(param_itf, param_base_name +
".has_position_limits",
false);
96 param_itf, param_base_name +
".min_position", std::numeric_limits<double>::quiet_NaN());
98 param_itf, param_base_name +
".max_position", std::numeric_limits<double>::quiet_NaN());
99 auto_declare<bool>(param_itf, param_base_name +
".has_velocity_limits",
false);
100 auto_declare<double>(
101 param_itf, param_base_name +
".max_velocity", std::numeric_limits<double>::quiet_NaN());
102 auto_declare<bool>(param_itf, param_base_name +
".has_acceleration_limits",
false);
103 auto_declare<double>(
104 param_itf, param_base_name +
".max_acceleration", std::numeric_limits<double>::quiet_NaN());
105 auto_declare<bool>(param_itf, param_base_name +
".has_deceleration_limits",
false);
106 auto_declare<double>(
107 param_itf, param_base_name +
".max_deceleration", std::numeric_limits<double>::quiet_NaN());
108 auto_declare<bool>(param_itf, param_base_name +
".has_jerk_limits",
false);
109 auto_declare<double>(
110 param_itf, param_base_name +
".max_jerk", std::numeric_limits<double>::quiet_NaN());
111 auto_declare<bool>(param_itf, param_base_name +
".has_effort_limits",
false);
112 auto_declare<double>(
113 param_itf, param_base_name +
".max_effort", std::numeric_limits<double>::quiet_NaN());
114 auto_declare<bool>(param_itf, param_base_name +
".angle_wraparound",
false);
115 auto_declare<bool>(param_itf, param_base_name +
".has_soft_limits",
false);
116 auto_declare<double>(
117 param_itf, param_base_name +
".k_position", std::numeric_limits<double>::quiet_NaN());
118 auto_declare<double>(
119 param_itf, param_base_name +
".k_velocity", std::numeric_limits<double>::quiet_NaN());
120 auto_declare<double>(
121 param_itf, param_base_name +
".soft_lower_limit", std::numeric_limits<double>::quiet_NaN());
122 auto_declare<double>(
123 param_itf, param_base_name +
".soft_upper_limit", std::numeric_limits<double>::quiet_NaN());
125 catch (
const std::exception & ex)
127 RCLCPP_ERROR(logging_itf->get_logger(),
"%s", ex.what());
226 const std::string & joint_name,
227 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
228 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
231 const std::string param_base_name =
"joint_limits." + joint_name;
235 !param_itf->has_parameter(param_base_name +
".has_position_limits") &&
236 !param_itf->has_parameter(param_base_name +
".min_position") &&
237 !param_itf->has_parameter(param_base_name +
".max_position") &&
238 !param_itf->has_parameter(param_base_name +
".has_velocity_limits") &&
239 !param_itf->has_parameter(param_base_name +
".max_velocity") &&
240 !param_itf->has_parameter(param_base_name +
".has_acceleration_limits") &&
241 !param_itf->has_parameter(param_base_name +
".max_acceleration") &&
242 !param_itf->has_parameter(param_base_name +
".has_deceleration_limits") &&
243 !param_itf->has_parameter(param_base_name +
".max_deceleration") &&
244 !param_itf->has_parameter(param_base_name +
".has_jerk_limits") &&
245 !param_itf->has_parameter(param_base_name +
".max_jerk") &&
246 !param_itf->has_parameter(param_base_name +
".has_effort_limits") &&
247 !param_itf->has_parameter(param_base_name +
".max_effort") &&
248 !param_itf->has_parameter(param_base_name +
".angle_wraparound"))
251 logging_itf->get_logger(),
252 "No joint limits specification found for joint '%s' in the parameter server "
254 joint_name.c_str(), param_base_name.c_str());
258 catch (
const std::exception & ex)
260 RCLCPP_ERROR(logging_itf->get_logger(),
"%s", ex.what());
265 if (param_itf->has_parameter(param_base_name +
".has_position_limits"))
267 limits.has_position_limits =
268 param_itf->get_parameter(param_base_name +
".has_position_limits").as_bool();
270 limits.has_position_limits && param_itf->has_parameter(param_base_name +
".min_position") &&
271 param_itf->has_parameter(param_base_name +
".max_position"))
273 limits.min_position = param_itf->get_parameter(param_base_name +
".min_position").as_double();
274 limits.max_position = param_itf->get_parameter(param_base_name +
".max_position").as_double();
278 limits.has_position_limits =
false;
282 !limits.has_position_limits &&
283 param_itf->has_parameter(param_base_name +
".angle_wraparound"))
285 limits.angle_wraparound =
286 param_itf->get_parameter(param_base_name +
".angle_wraparound").as_bool();
291 if (param_itf->has_parameter(param_base_name +
".has_velocity_limits"))
293 limits.has_velocity_limits =
294 param_itf->get_parameter(param_base_name +
".has_velocity_limits").as_bool();
295 if (limits.has_velocity_limits && param_itf->has_parameter(param_base_name +
".max_velocity"))
297 limits.max_velocity = param_itf->get_parameter(param_base_name +
".max_velocity").as_double();
301 limits.has_velocity_limits =
false;
306 if (param_itf->has_parameter(param_base_name +
".has_acceleration_limits"))
308 limits.has_acceleration_limits =
309 param_itf->get_parameter(param_base_name +
".has_acceleration_limits").as_bool();
311 limits.has_acceleration_limits &&
312 param_itf->has_parameter(param_base_name +
".max_acceleration"))
314 limits.max_acceleration =
315 param_itf->get_parameter(param_base_name +
".max_acceleration").as_double();
319 limits.has_acceleration_limits =
false;
324 if (param_itf->has_parameter(param_base_name +
".has_deceleration_limits"))
326 limits.has_deceleration_limits =
327 param_itf->get_parameter(param_base_name +
".has_deceleration_limits").as_bool();
329 limits.has_deceleration_limits &&
330 param_itf->has_parameter(param_base_name +
".max_deceleration"))
332 limits.max_deceleration =
333 param_itf->get_parameter(param_base_name +
".max_deceleration").as_double();
337 limits.has_deceleration_limits =
false;
342 if (param_itf->has_parameter(param_base_name +
".has_jerk_limits"))
344 limits.has_jerk_limits =
345 param_itf->get_parameter(param_base_name +
".has_jerk_limits").as_bool();
346 if (limits.has_jerk_limits && param_itf->has_parameter(param_base_name +
".max_jerk"))
348 limits.max_jerk = param_itf->get_parameter(param_base_name +
".max_jerk").as_double();
352 limits.has_jerk_limits =
false;
357 if (param_itf->has_parameter(param_base_name +
".has_effort_limits"))
359 limits.has_effort_limits =
360 param_itf->get_parameter(param_base_name +
".has_effort_limits").as_bool();
361 if (limits.has_effort_limits && param_itf->has_parameter(param_base_name +
".max_effort"))
363 limits.has_effort_limits =
true;
364 limits.max_effort = param_itf->get_parameter(param_base_name +
".max_effort").as_double();
368 limits.has_effort_limits =
false;
432 const std::string & joint_name,
const std::vector<rclcpp::Parameter> & parameters,
433 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
436 const std::string param_base_name =
"joint_limits." + joint_name;
437 bool changed =
false;
440 for (
auto & parameter : parameters)
442 const std::string param_name = parameter.get_name();
445 if (param_name == param_base_name +
".min_position")
447 changed = updated_limits.min_position != parameter.get_value<
double>();
448 updated_limits.min_position = parameter.get_value<
double>();
450 else if (param_name == param_base_name +
".max_position")
452 changed = updated_limits.max_position != parameter.get_value<
double>();
453 updated_limits.max_position = parameter.get_value<
double>();
455 else if (param_name == param_base_name +
".max_velocity")
457 changed = updated_limits.max_velocity != parameter.get_value<
double>();
458 updated_limits.max_velocity = parameter.get_value<
double>();
460 else if (param_name == param_base_name +
".max_acceleration")
462 changed = updated_limits.max_acceleration != parameter.get_value<
double>();
463 updated_limits.max_acceleration = parameter.get_value<
double>();
465 else if (param_name == param_base_name +
".max_deceleration")
467 changed = updated_limits.max_deceleration != parameter.get_value<
double>();
468 updated_limits.max_deceleration = parameter.get_value<
double>();
470 else if (param_name == param_base_name +
".max_jerk")
472 changed = updated_limits.max_jerk != parameter.get_value<
double>();
473 updated_limits.max_jerk = parameter.get_value<
double>();
475 else if (param_name == param_base_name +
".max_effort")
477 changed = updated_limits.max_effort != parameter.get_value<
double>();
478 updated_limits.max_effort = parameter.get_value<
double>();
481 catch (
const rclcpp::exceptions::InvalidParameterTypeException & e)
483 RCLCPP_WARN(logging_itf->get_logger(),
"Please use the right type: %s", e.what());
487 for (
auto & parameter : parameters)
489 const std::string param_name = parameter.get_name();
492 if (param_name == param_base_name +
".has_position_limits")
494 updated_limits.has_position_limits = parameter.get_value<
bool>();
495 if (updated_limits.has_position_limits)
497 if (std::isnan(updated_limits.min_position) || std::isnan(updated_limits.max_position))
500 logging_itf->get_logger(),
501 "PARAMETER NOT UPDATED: Position limits can not be used, i.e., "
502 "'has_position_limits' flag can not be set, if 'min_position' "
503 "and 'max_position' are not set or not have valid double values.");
504 updated_limits.has_position_limits =
false;
506 else if (updated_limits.min_position >= updated_limits.max_position)
509 logging_itf->get_logger(),
510 "PARAMETER NOT UPDATED: Position limits can not be used, i.e., "
511 "'has_position_limits' flag can not be set, if not "
512 "'min_position' < 'max_position'");
513 updated_limits.has_position_limits =
false;
521 else if (param_name == param_base_name +
".has_velocity_limits")
523 updated_limits.has_velocity_limits = parameter.get_value<
bool>();
524 if (updated_limits.has_velocity_limits && std::isnan(updated_limits.max_velocity))
527 logging_itf->get_logger(),
528 "PARAMETER NOT UPDATED: 'has_velocity_limits' flag can not be set if 'min_velocity' "
529 "and 'max_velocity' are not set or not have valid double values.");
530 updated_limits.has_velocity_limits =
false;
537 else if (param_name == param_base_name +
".has_acceleration_limits")
539 updated_limits.has_acceleration_limits = parameter.get_value<
bool>();
540 if (updated_limits.has_acceleration_limits && std::isnan(updated_limits.max_acceleration))
543 logging_itf->get_logger(),
544 "PARAMETER NOT UPDATED: 'has_acceleration_limits' flag can not be set if "
545 "'max_acceleration' is not set or not have valid double values.");
546 updated_limits.has_acceleration_limits =
false;
553 else if (param_name == param_base_name +
".has_deceleration_limits")
555 updated_limits.has_deceleration_limits = parameter.get_value<
bool>();
556 if (updated_limits.has_deceleration_limits && std::isnan(updated_limits.max_deceleration))
559 logging_itf->get_logger(),
560 "PARAMETER NOT UPDATED: 'has_deceleration_limits' flag can not be set if "
561 "'max_deceleration' is not set or not have valid double values.");
562 updated_limits.has_deceleration_limits =
false;
569 else if (param_name == param_base_name +
".has_jerk_limits")
571 updated_limits.has_jerk_limits = parameter.get_value<
bool>();
572 if (updated_limits.has_jerk_limits && std::isnan(updated_limits.max_jerk))
575 logging_itf->get_logger(),
576 "PARAMETER NOT UPDATED: 'has_jerk_limits' flag can not be set if 'max_jerk' is not set "
577 "or not have valid double values.");
578 updated_limits.has_jerk_limits =
false;
585 else if (param_name == param_base_name +
".has_effort_limits")
587 updated_limits.has_effort_limits = parameter.get_value<
bool>();
588 if (updated_limits.has_effort_limits && std::isnan(updated_limits.max_effort))
591 logging_itf->get_logger(),
592 "PARAMETER NOT UPDATED: 'has_effort_limits' flag can not be set if 'max_effort' is not "
593 "set or not have valid double values.");
594 updated_limits.has_effort_limits =
false;
601 else if (param_name == param_base_name +
".angle_wraparound")
603 updated_limits.angle_wraparound = parameter.get_value<
bool>();
604 if (updated_limits.angle_wraparound && updated_limits.has_position_limits)
607 logging_itf->get_logger(),
608 "PARAMETER NOT UPDATED: 'angle_wraparound' flag can not be set if "
609 "'has_position_limits' flag is set.");
610 updated_limits.angle_wraparound =
false;
618 catch (
const rclcpp::exceptions::InvalidParameterTypeException & e)
621 logging_itf->get_logger(),
"PARAMETER NOT UPDATED: Please use the right type: %s",
662 const std::string & joint_name,
663 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
664 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
667 const std::string param_base_name =
"joint_limits." + joint_name;
671 !param_itf->has_parameter(param_base_name +
".has_soft_limits") &&
672 !param_itf->has_parameter(param_base_name +
".k_velocity") &&
673 !param_itf->has_parameter(param_base_name +
".k_position") &&
674 !param_itf->has_parameter(param_base_name +
".soft_lower_limit") &&
675 !param_itf->has_parameter(param_base_name +
".soft_upper_limit"))
678 logging_itf->get_logger(),
679 "No soft joint limits specification found for joint '%s' in the parameter server "
681 joint_name.c_str(), param_base_name.c_str());
685 catch (
const std::exception & ex)
687 RCLCPP_ERROR(logging_itf->get_logger(),
"%s", ex.what());
692 if (param_itf->has_parameter(param_base_name +
".has_soft_limits"))
695 param_itf->get_parameter(param_base_name +
".has_soft_limits").as_bool() &&
696 param_itf->has_parameter(param_base_name +
".k_position") &&
697 param_itf->has_parameter(param_base_name +
".k_velocity") &&
698 param_itf->has_parameter(param_base_name +
".soft_lower_limit") &&
699 param_itf->has_parameter(param_base_name +
".soft_upper_limit"))
701 soft_limits.k_position =
702 param_itf->get_parameter(param_base_name +
".k_position").as_double();
703 soft_limits.k_velocity =
704 param_itf->get_parameter(param_base_name +
".k_velocity").as_double();
705 soft_limits.min_position =
706 param_itf->get_parameter(param_base_name +
".soft_lower_limit").as_double();
707 soft_limits.max_position =
708 param_itf->get_parameter(param_base_name +
".soft_upper_limit").as_double();
773 const std::string & joint_name,
const std::vector<rclcpp::Parameter> & parameters,
774 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
777 const std::string param_base_name =
"joint_limits." + joint_name;
778 bool changed =
false;
780 for (
auto & parameter : parameters)
782 const std::string param_name = parameter.get_name();
785 if (param_name == param_base_name +
".has_soft_limits")
787 if (!parameter.get_value<
bool>())
790 logging_itf->get_logger(),
791 "Parameter 'has_soft_limits' is not set, therefore the limits will not be updated!");
796 catch (
const rclcpp::exceptions::InvalidParameterTypeException & e)
798 RCLCPP_INFO(logging_itf->get_logger(),
"Please use the right type: %s", e.what());
802 for (
auto & parameter : parameters)
804 const std::string param_name = parameter.get_name();
807 if (param_name == param_base_name +
".k_position")
809 changed = updated_limits.k_position != parameter.get_value<
double>();
810 updated_limits.k_position = parameter.get_value<
double>();
812 else if (param_name == param_base_name +
".k_velocity")
814 changed = updated_limits.k_velocity != parameter.get_value<
double>();
815 updated_limits.k_velocity = parameter.get_value<
double>();
817 else if (param_name == param_base_name +
".soft_lower_limit")
819 changed = updated_limits.min_position != parameter.get_value<
double>();
820 updated_limits.min_position = parameter.get_value<
double>();
822 else if (param_name == param_base_name +
".soft_upper_limit")
824 changed = updated_limits.max_position != parameter.get_value<
double>();
825 updated_limits.max_position = parameter.get_value<
double>();
828 catch (
const rclcpp::exceptions::InvalidParameterTypeException & e)
830 RCLCPP_INFO(logging_itf->get_logger(),
"Please use the right type: %s", e.what());