ros2_control - rolling
Loading...
Searching...
No Matches
joint_limits_rosparam.hpp
1// Copyright 2020 PAL Robotics S.L.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
16
17#ifndef JOINT_LIMITS__JOINT_LIMITS_ROSPARAM_HPP_
18#define JOINT_LIMITS__JOINT_LIMITS_ROSPARAM_HPP_
19
20#include <limits>
21#include <string>
22#include <vector>
23
24#include "joint_limits/joint_limits.hpp"
25#include "rclcpp/node.hpp"
26#include "rclcpp_lifecycle/lifecycle_node.hpp"
27
28namespace // utilities
29{
31
37template <typename ParameterT>
38auto auto_declare(
39 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
40 const std::string & name, const ParameterT & default_value)
41{
42 if (!param_itf->has_parameter(name))
43 {
44 auto param_default_value = rclcpp::ParameterValue(default_value);
45 param_itf->declare_parameter(name, param_default_value);
46 }
47 return param_itf->get_parameter(name).get_value<ParameterT>();
48}
49} // namespace
50
51namespace joint_limits
52{
87 const std::string & joint_name,
88 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
89 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf)
90{
91 const std::string param_base_name = "joint_limits." + joint_name;
92 try
93 {
94 auto_declare<bool>(param_itf, param_base_name + ".has_position_limits", false);
95 auto_declare<double>(
96 param_itf, param_base_name + ".min_position", std::numeric_limits<double>::quiet_NaN());
97 auto_declare<double>(
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());
124 }
125 catch (const std::exception & ex)
126 {
127 RCLCPP_ERROR(logging_itf->get_logger(), "%s", ex.what());
128 return false;
129 }
130 return true;
131}
132
144inline bool declare_parameters(const std::string & joint_name, const rclcpp::Node::SharedPtr & node)
145{
146 return declare_parameters(
147 joint_name, node->get_node_parameters_interface(), node->get_node_logging_interface());
148}
149
161 const std::string & joint_name, const rclcpp_lifecycle::LifecycleNode::SharedPtr & lifecycle_node)
162{
163 return declare_parameters(
164 joint_name, lifecycle_node->get_node_parameters_interface(),
165 lifecycle_node->get_node_logging_interface());
166}
167
169
226 const std::string & joint_name,
227 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
228 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
229 JointLimits & limits)
230{
231 const std::string param_base_name = "joint_limits." + joint_name;
232 try
233 {
234 if (
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"))
249 {
250 RCLCPP_ERROR(
251 logging_itf->get_logger(),
252 "No joint limits specification found for joint '%s' in the parameter server "
253 "(param name: %s).",
254 joint_name.c_str(), param_base_name.c_str());
255 return false;
256 }
257 }
258 catch (const std::exception & ex)
259 {
260 RCLCPP_ERROR(logging_itf->get_logger(), "%s", ex.what());
261 return false;
262 }
263
264 // Position limits
265 if (param_itf->has_parameter(param_base_name + ".has_position_limits"))
266 {
267 limits.has_position_limits =
268 param_itf->get_parameter(param_base_name + ".has_position_limits").as_bool();
269 if (
270 limits.has_position_limits && param_itf->has_parameter(param_base_name + ".min_position") &&
271 param_itf->has_parameter(param_base_name + ".max_position"))
272 {
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();
275 }
276 else
277 {
278 limits.has_position_limits = false;
279 }
280
281 if (
282 !limits.has_position_limits &&
283 param_itf->has_parameter(param_base_name + ".angle_wraparound"))
284 {
285 limits.angle_wraparound =
286 param_itf->get_parameter(param_base_name + ".angle_wraparound").as_bool();
287 }
288 }
289
290 // Velocity limits
291 if (param_itf->has_parameter(param_base_name + ".has_velocity_limits"))
292 {
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"))
296 {
297 limits.max_velocity = param_itf->get_parameter(param_base_name + ".max_velocity").as_double();
298 }
299 else
300 {
301 limits.has_velocity_limits = false;
302 }
303 }
304
305 // Acceleration limits
306 if (param_itf->has_parameter(param_base_name + ".has_acceleration_limits"))
307 {
308 limits.has_acceleration_limits =
309 param_itf->get_parameter(param_base_name + ".has_acceleration_limits").as_bool();
310 if (
311 limits.has_acceleration_limits &&
312 param_itf->has_parameter(param_base_name + ".max_acceleration"))
313 {
314 limits.max_acceleration =
315 param_itf->get_parameter(param_base_name + ".max_acceleration").as_double();
316 }
317 else
318 {
319 limits.has_acceleration_limits = false;
320 }
321 }
322
323 // Deceleration limits
324 if (param_itf->has_parameter(param_base_name + ".has_deceleration_limits"))
325 {
326 limits.has_deceleration_limits =
327 param_itf->get_parameter(param_base_name + ".has_deceleration_limits").as_bool();
328 if (
329 limits.has_deceleration_limits &&
330 param_itf->has_parameter(param_base_name + ".max_deceleration"))
331 {
332 limits.max_deceleration =
333 param_itf->get_parameter(param_base_name + ".max_deceleration").as_double();
334 }
335 else
336 {
337 limits.has_deceleration_limits = false;
338 }
339 }
340
341 // Jerk limits
342 if (param_itf->has_parameter(param_base_name + ".has_jerk_limits"))
343 {
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"))
347 {
348 limits.max_jerk = param_itf->get_parameter(param_base_name + ".max_jerk").as_double();
349 }
350 else
351 {
352 limits.has_jerk_limits = false;
353 }
354 }
355
356 // Effort limits
357 if (param_itf->has_parameter(param_base_name + ".has_effort_limits"))
358 {
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"))
362 {
363 limits.has_effort_limits = true;
364 limits.max_effort = param_itf->get_parameter(param_base_name + ".max_effort").as_double();
365 }
366 else
367 {
368 limits.has_effort_limits = false;
369 }
370 }
371
372 return true;
373}
374
389 const std::string & joint_name, const rclcpp::Node::SharedPtr & node, JointLimits & limits)
390{
391 return get_joint_limits(
392 joint_name, node->get_node_parameters_interface(), node->get_node_logging_interface(), limits);
393}
394
409 const std::string & joint_name, const rclcpp_lifecycle::LifecycleNode::SharedPtr & lifecycle_node,
410 JointLimits & limits)
411{
412 return get_joint_limits(
413 joint_name, lifecycle_node->get_node_parameters_interface(),
414 lifecycle_node->get_node_logging_interface(), limits);
415}
416
432 const std::string & joint_name, const std::vector<rclcpp::Parameter> & parameters,
433 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
434 JointLimits & updated_limits)
435{
436 const std::string param_base_name = "joint_limits." + joint_name;
437 bool changed = false;
438
439 // update first numerical values to make later checks for "has" limits members
440 for (auto & parameter : parameters)
441 {
442 const std::string param_name = parameter.get_name();
443 try
444 {
445 if (param_name == param_base_name + ".min_position")
446 {
447 changed = updated_limits.min_position != parameter.get_value<double>();
448 updated_limits.min_position = parameter.get_value<double>();
449 }
450 else if (param_name == param_base_name + ".max_position")
451 {
452 changed = updated_limits.max_position != parameter.get_value<double>();
453 updated_limits.max_position = parameter.get_value<double>();
454 }
455 else if (param_name == param_base_name + ".max_velocity")
456 {
457 changed = updated_limits.max_velocity != parameter.get_value<double>();
458 updated_limits.max_velocity = parameter.get_value<double>();
459 }
460 else if (param_name == param_base_name + ".max_acceleration")
461 {
462 changed = updated_limits.max_acceleration != parameter.get_value<double>();
463 updated_limits.max_acceleration = parameter.get_value<double>();
464 }
465 else if (param_name == param_base_name + ".max_deceleration")
466 {
467 changed = updated_limits.max_deceleration != parameter.get_value<double>();
468 updated_limits.max_deceleration = parameter.get_value<double>();
469 }
470 else if (param_name == param_base_name + ".max_jerk")
471 {
472 changed = updated_limits.max_jerk != parameter.get_value<double>();
473 updated_limits.max_jerk = parameter.get_value<double>();
474 }
475 else if (param_name == param_base_name + ".max_effort")
476 {
477 changed = updated_limits.max_effort != parameter.get_value<double>();
478 updated_limits.max_effort = parameter.get_value<double>();
479 }
480 }
481 catch (const rclcpp::exceptions::InvalidParameterTypeException & e)
482 {
483 RCLCPP_WARN(logging_itf->get_logger(), "Please use the right type: %s", e.what());
484 }
485 }
486
487 for (auto & parameter : parameters)
488 {
489 const std::string param_name = parameter.get_name();
490 try
491 {
492 if (param_name == param_base_name + ".has_position_limits")
493 {
494 updated_limits.has_position_limits = parameter.get_value<bool>();
495 if (updated_limits.has_position_limits)
496 {
497 if (std::isnan(updated_limits.min_position) || std::isnan(updated_limits.max_position))
498 {
499 RCLCPP_WARN(
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;
505 }
506 else if (updated_limits.min_position >= updated_limits.max_position)
507 {
508 RCLCPP_WARN(
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;
514 }
515 else
516 {
517 changed = true;
518 }
519 }
520 }
521 else if (param_name == param_base_name + ".has_velocity_limits")
522 {
523 updated_limits.has_velocity_limits = parameter.get_value<bool>();
524 if (updated_limits.has_velocity_limits && std::isnan(updated_limits.max_velocity))
525 {
526 RCLCPP_WARN(
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;
531 }
532 else
533 {
534 changed = true;
535 }
536 }
537 else if (param_name == param_base_name + ".has_acceleration_limits")
538 {
539 updated_limits.has_acceleration_limits = parameter.get_value<bool>();
540 if (updated_limits.has_acceleration_limits && std::isnan(updated_limits.max_acceleration))
541 {
542 RCLCPP_WARN(
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;
547 }
548 else
549 {
550 changed = true;
551 }
552 }
553 else if (param_name == param_base_name + ".has_deceleration_limits")
554 {
555 updated_limits.has_deceleration_limits = parameter.get_value<bool>();
556 if (updated_limits.has_deceleration_limits && std::isnan(updated_limits.max_deceleration))
557 {
558 RCLCPP_WARN(
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;
563 }
564 else
565 {
566 changed = true;
567 }
568 }
569 else if (param_name == param_base_name + ".has_jerk_limits")
570 {
571 updated_limits.has_jerk_limits = parameter.get_value<bool>();
572 if (updated_limits.has_jerk_limits && std::isnan(updated_limits.max_jerk))
573 {
574 RCLCPP_WARN(
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;
579 }
580 else
581 {
582 changed = true;
583 }
584 }
585 else if (param_name == param_base_name + ".has_effort_limits")
586 {
587 updated_limits.has_effort_limits = parameter.get_value<bool>();
588 if (updated_limits.has_effort_limits && std::isnan(updated_limits.max_effort))
589 {
590 RCLCPP_WARN(
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;
595 }
596 else
597 {
598 changed = true;
599 }
600 }
601 else if (param_name == param_base_name + ".angle_wraparound")
602 {
603 updated_limits.angle_wraparound = parameter.get_value<bool>();
604 if (updated_limits.angle_wraparound && updated_limits.has_position_limits)
605 {
606 RCLCPP_WARN(
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;
611 }
612 else
613 {
614 changed = true;
615 }
616 }
617 }
618 catch (const rclcpp::exceptions::InvalidParameterTypeException & e)
619 {
620 RCLCPP_WARN(
621 logging_itf->get_logger(), "PARAMETER NOT UPDATED: Please use the right type: %s",
622 e.what());
623 }
624 }
625
626 return changed;
627}
628
630
662 const std::string & joint_name,
663 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
664 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
665 SoftJointLimits & soft_limits)
666{
667 const std::string param_base_name = "joint_limits." + joint_name;
668 try
669 {
670 if (
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"))
676 {
677 RCLCPP_DEBUG(
678 logging_itf->get_logger(),
679 "No soft joint limits specification found for joint '%s' in the parameter server "
680 "(param name: %s).",
681 joint_name.c_str(), param_base_name.c_str());
682 return false;
683 }
684 }
685 catch (const std::exception & ex)
686 {
687 RCLCPP_ERROR(logging_itf->get_logger(), "%s", ex.what());
688 return false;
689 }
690
691 // Override soft limits if complete specification is found
692 if (param_itf->has_parameter(param_base_name + ".has_soft_limits"))
693 {
694 if (
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"))
700 {
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();
709 return true;
710 }
711 }
712
713 return false;
714}
715
729 const std::string & joint_name, const rclcpp::Node::SharedPtr & node,
730 SoftJointLimits & soft_limits)
731{
732 return get_joint_limits(
733 joint_name, node->get_node_parameters_interface(), node->get_node_logging_interface(),
734 soft_limits);
735}
736
750 const std::string & joint_name, const rclcpp_lifecycle::LifecycleNode::SharedPtr & lifecycle_node,
751 SoftJointLimits & soft_limits)
752{
753 return get_joint_limits(
754 joint_name, lifecycle_node->get_node_parameters_interface(),
755 lifecycle_node->get_node_logging_interface(), soft_limits);
756}
757
773 const std::string & joint_name, const std::vector<rclcpp::Parameter> & parameters,
774 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
775 SoftJointLimits & updated_limits)
776{
777 const std::string param_base_name = "joint_limits." + joint_name;
778 bool changed = false;
779
780 for (auto & parameter : parameters)
781 {
782 const std::string param_name = parameter.get_name();
783 try
784 {
785 if (param_name == param_base_name + ".has_soft_limits")
786 {
787 if (!parameter.get_value<bool>())
788 {
789 RCLCPP_WARN(
790 logging_itf->get_logger(),
791 "Parameter 'has_soft_limits' is not set, therefore the limits will not be updated!");
792 return false;
793 }
794 }
795 }
796 catch (const rclcpp::exceptions::InvalidParameterTypeException & e)
797 {
798 RCLCPP_INFO(logging_itf->get_logger(), "Please use the right type: %s", e.what());
799 }
800 }
801
802 for (auto & parameter : parameters)
803 {
804 const std::string param_name = parameter.get_name();
805 try
806 {
807 if (param_name == param_base_name + ".k_position")
808 {
809 changed = updated_limits.k_position != parameter.get_value<double>();
810 updated_limits.k_position = parameter.get_value<double>();
811 }
812 else if (param_name == param_base_name + ".k_velocity")
813 {
814 changed = updated_limits.k_velocity != parameter.get_value<double>();
815 updated_limits.k_velocity = parameter.get_value<double>();
816 }
817 else if (param_name == param_base_name + ".soft_lower_limit")
818 {
819 changed = updated_limits.min_position != parameter.get_value<double>();
820 updated_limits.min_position = parameter.get_value<double>();
821 }
822 else if (param_name == param_base_name + ".soft_upper_limit")
823 {
824 changed = updated_limits.max_position != parameter.get_value<double>();
825 updated_limits.max_position = parameter.get_value<double>();
826 }
827 }
828 catch (const rclcpp::exceptions::InvalidParameterTypeException & e)
829 {
830 RCLCPP_INFO(logging_itf->get_logger(), "Please use the right type: %s", e.what());
831 }
832 }
833
834 return changed;
835}
836
837} // namespace joint_limits
838
839#endif // JOINT_LIMITS__JOINT_LIMITS_ROSPARAM_HPP_
Definition data_structures.hpp:37
bool check_for_limits_update(const std::string &joint_name, const std::vector< rclcpp::Parameter > &parameters, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf, JointLimits &updated_limits)
Definition joint_limits_rosparam.hpp:431
bool declare_parameters(const std::string &joint_name, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &param_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf)
Definition joint_limits_rosparam.hpp:86
bool get_joint_limits(const std::string &joint_name, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &param_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf, JointLimits &limits)
Populate a JointLimits instance from the node parameters.
Definition joint_limits_rosparam.hpp:225
Definition joint_limits.hpp:35
Definition joint_limits.hpp:113