ros2_control - rolling
Loading...
Searching...
No Matches
joint_limiter_interface.hpp
1// Copyright (c) 2024, Stogl Robotics Consulting UG (haftungsbeschränkt)
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_LIMITER_INTERFACE_HPP_
18#define JOINT_LIMITS__JOINT_LIMITER_INTERFACE_HPP_
19
20#include <string>
21#include <vector>
22
23#include "joint_limits/joint_limits.hpp"
24#include "joint_limits/joint_limits_rosparam.hpp"
25#include "rclcpp/node.hpp"
26#include "rclcpp_lifecycle/lifecycle_node.hpp"
27#include "realtime_tools/realtime_buffer.hpp"
28#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
29
30namespace joint_limits
31{
32
33template <typename JointLimitsStateDataType>
35{
36public:
37 JointLimiterInterface() = default;
38
39 virtual ~JointLimiterInterface() = default;
40
42
54 virtual bool init(
55 const std::vector<std::string> & joint_names,
56 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
57 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
58 const std::string & robot_description_topic = "/robot_description")
59 {
60 number_of_joints_ = joint_names.size();
61 joint_names_ = joint_names;
62 joint_limits_.resize(number_of_joints_);
63 node_param_itf_ = param_itf;
64 node_logging_itf_ = logging_itf;
65
66 bool result = true;
67
68 // TODO(destogl): get limits from URDF
69
70 // Initialize and get joint limits from parameter server
72 {
73 for (size_t i = 0; i < number_of_joints_; ++i)
74 {
75 if (!declare_parameters(joint_names[i], node_param_itf_, node_logging_itf_))
76 {
77 RCLCPP_ERROR(
78 node_logging_itf_->get_logger(),
79 "JointLimiter: Joint '%s': parameter declaration has failed", joint_names[i].c_str());
80 result = false;
81 break;
82 }
83 if (!get_joint_limits(joint_names[i], node_param_itf_, node_logging_itf_, joint_limits_[i]))
84 {
85 RCLCPP_ERROR(
86 node_logging_itf_->get_logger(),
87 "JointLimiter: Joint '%s': getting parameters has failed", joint_names[i].c_str());
88 result = false;
89 break;
90 }
91 RCLCPP_INFO(
92 node_logging_itf_->get_logger(), "Limits for joint %zu (%s) are:\n%s", i,
93 joint_names[i].c_str(), joint_limits_[i].to_string().c_str());
94 }
95 updated_limits_.writeFromNonRT(joint_limits_);
96
97 auto on_parameter_event_callback = [this](const std::vector<rclcpp::Parameter> & parameters)
98 {
99 rcl_interfaces::msg::SetParametersResult set_parameters_result;
100 set_parameters_result.successful = true;
101
102 std::vector<joint_limits::JointLimits> updated_joint_limits = joint_limits_;
103 bool changed = false;
104
105 for (size_t i = 0; i < number_of_joints_; ++i)
106 {
108 joint_names_[i], parameters, node_logging_itf_, updated_joint_limits[i]);
109 }
110
111 if (changed)
112 {
113 updated_limits_.writeFromNonRT(updated_joint_limits);
114 RCLCPP_INFO(node_logging_itf_->get_logger(), "Limits are dynamically updated!");
115 }
116
117 return set_parameters_result;
118 };
119
120 parameter_callback_ =
121 node_param_itf_->add_on_set_parameters_callback(on_parameter_event_callback);
122 }
123
124 if (result)
125 {
126 result = on_init();
127 }
128
129 (void)robot_description_topic; // avoid linters output
130
131 return result;
132 }
133
137 virtual bool init(
138 const std::vector<std::string> & joint_names,
139 const std::vector<joint_limits::JointLimits> & joint_limits,
140 const std::vector<joint_limits::SoftJointLimits> & soft_joint_limits,
141 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
142 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf)
143 {
144 number_of_joints_ = joint_names.size();
145 joint_names_ = joint_names;
146 joint_limits_ = joint_limits;
147 soft_joint_limits_ = soft_joint_limits;
148 node_param_itf_ = param_itf;
149 node_logging_itf_ = logging_itf;
150 updated_limits_.writeFromNonRT(joint_limits_);
151
152 if ((number_of_joints_ != joint_limits_.size()) && has_logging_interface())
153 {
154 RCLCPP_ERROR(
155 node_logging_itf_->get_logger(),
156 "JointLimiter: Number of joint names and limits do not match: %zu != %zu",
157 number_of_joints_, joint_limits_.size());
158 }
159 return (number_of_joints_ == joint_limits_.size()) && on_init();
160 }
161
166 virtual bool init(
167 const std::vector<std::string> & joint_names, const rclcpp::Node::SharedPtr & node,
168 const std::string & robot_description_topic = "/robot_description")
169 {
170 return init(
171 joint_names, node->get_node_parameters_interface(), node->get_node_logging_interface(),
172 robot_description_topic);
173 }
174
179 virtual bool init(
180 const std::vector<std::string> & joint_names,
181 const rclcpp_lifecycle::LifecycleNode::SharedPtr & lifecycle_node,
182 const std::string & robot_description_topic = "/robot_description")
183 {
184 return init(
185 joint_names, lifecycle_node->get_node_parameters_interface(),
186 lifecycle_node->get_node_logging_interface(), robot_description_topic);
187 }
188
189 virtual bool configure(const JointLimitsStateDataType & current_joint_states)
190 {
191 return on_configure(current_joint_states);
192 }
193
203 virtual bool enforce(
204 const JointLimitsStateDataType & current_joint_states,
205 JointLimitsStateDataType & desired_joint_states, const rclcpp::Duration & dt)
206 {
207 joint_limits_ = *(updated_limits_.readFromRT());
208 return on_enforce(current_joint_states, desired_joint_states, dt);
209 }
210
211protected:
217 virtual bool on_init() = 0;
218
224 virtual bool on_configure(const JointLimitsStateDataType & current_joint_states) = 0;
225
236 virtual bool on_enforce(
237 const JointLimitsStateDataType & current_joint_states,
238 JointLimitsStateDataType & desired_joint_states, const rclcpp::Duration & dt) = 0;
239
246 bool has_logging_interface() const { return node_logging_itf_ != nullptr; }
247
254 bool has_parameter_interface() const { return node_param_itf_ != nullptr; }
255
256 size_t number_of_joints_;
257 std::vector<std::string> joint_names_;
258 std::vector<joint_limits::JointLimits> joint_limits_;
259 std::vector<joint_limits::SoftJointLimits> soft_joint_limits_;
260 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_param_itf_;
261 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_itf_;
262
263private:
264 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr parameter_callback_;
266};
267
268} // namespace joint_limits
269
270#endif // JOINT_LIMITS__JOINT_LIMITER_INTERFACE_HPP_
Definition joint_limiter_interface.hpp:35
virtual bool on_init()=0
Method is realized by an implementation.
virtual bool init(const std::vector< std::string > &joint_names, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &param_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf, const std::string &robot_description_topic="/robot_description")
Initialization of every JointLimiter.
Definition joint_limiter_interface.hpp:54
bool has_logging_interface() const
Checks if the logging interface is set.
Definition joint_limiter_interface.hpp:246
bool has_parameter_interface() const
Checks if the parameter interface is set.
Definition joint_limiter_interface.hpp:254
virtual bool on_enforce(const JointLimitsStateDataType &current_joint_states, JointLimitsStateDataType &desired_joint_states, const rclcpp::Duration &dt)=0
Method is realized by an implementation.
virtual bool enforce(const JointLimitsStateDataType &current_joint_states, JointLimitsStateDataType &desired_joint_states, const rclcpp::Duration &dt)
Enforce joint limits to desired joint state for multiple physical quantities.
Definition joint_limiter_interface.hpp:203
virtual bool on_configure(const JointLimitsStateDataType &current_joint_states)=0
Method is realized by an implementation.
virtual bool init(const std::vector< std::string > &joint_names, const rclcpp_lifecycle::LifecycleNode::SharedPtr &lifecycle_node, const std::string &robot_description_topic="/robot_description")
Definition joint_limiter_interface.hpp:179
virtual bool init(const std::vector< std::string > &joint_names, const rclcpp::Node::SharedPtr &node, const std::string &robot_description_topic="/robot_description")
Definition joint_limiter_interface.hpp:166
virtual bool init(const std::vector< std::string > &joint_names, const std::vector< joint_limits::JointLimits > &joint_limits, const std::vector< joint_limits::SoftJointLimits > &soft_joint_limits, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &param_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf)
Definition joint_limiter_interface.hpp:137
Definition realtime_buffer.hpp:44
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