moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
joint_limits_interface_extension.h
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2018 Pilz GmbH & Co. KG
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Pilz GmbH & Co. KG nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35#pragma once
36
38#include <limits>
39
41
43{
44namespace joint_limits_interface
45{
49inline bool declareParameters(const std::string& joint_name, const std::string& param_ns,
50 const rclcpp::Node::SharedPtr& node)
51{
52 return joint_limits::declareParameters(joint_name, node, param_ns);
53}
57inline bool getJointLimits(const std::string& joint_name, const std::string& param_ns,
58 const rclcpp::Node::SharedPtr& node, joint_limits_interface::JointLimits& limits)
59{
60 // Load the existing limits
61 if (!joint_limits::getJointLimits(joint_name, node, param_ns, limits))
62 {
63 return false; // LCOV_EXCL_LINE // The case where getJointLimits returns
64 // false is covered above.
65 }
66 try
67 {
68 // Deceleration limits
69 const std::string param_base_name = (param_ns.empty() ? "" : param_ns + ".") + "joint_limits." + joint_name;
70 if (node->has_parameter(param_base_name + ".has_deceleration_limits"))
71 {
72 limits.has_deceleration_limits = node->get_parameter(param_base_name + ".has_deceleration_limits").as_bool();
73 }
74 else
75 {
76 limits.has_deceleration_limits = node->declare_parameter(param_base_name + ".has_deceleration_limits", false);
77 }
78 if (limits.has_deceleration_limits)
79 {
80 if (node->has_parameter(param_base_name + ".max_deceleration"))
81 {
82 limits.max_deceleration = node->get_parameter(param_base_name + ".max_deceleration").as_double();
83 }
84 else
85 {
86 limits.max_deceleration =
87 node->declare_parameter(param_base_name + ".max_deceleration", std::numeric_limits<double>::quiet_NaN());
88 }
89 }
90 }
91 catch (const std::exception& ex)
92 {
93 RCLCPP_WARN_STREAM(node->get_logger(), "Failed loading deceleration limits");
94 limits.has_deceleration_limits = false;
95 }
96
97 return true;
98}
99} // namespace joint_limits_interface
100} // namespace pilz_industrial_motion_planner
bool declareParameters(const std::string &joint_name, const rclcpp::Node::SharedPtr &node, const std::string &param_ns)
bool getJointLimits(const std::string &joint_name, const rclcpp::Node::SharedPtr &node, const std::string &param_ns, JointLimits &limits)
Populate a JointLimits instance from the ROS parameter server.
bool getJointLimits(const std::string &joint_name, const std::string &param_ns, const rclcpp::Node::SharedPtr &node, joint_limits_interface::JointLimits &limits)
bool declareParameters(const std::string &joint_name, const std::string &param_ns, const rclcpp::Node::SharedPtr &node)
Extends joint_limits_interface::JointLimits with a deceleration parameter.