ros2_control - humble
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
23#include "joint_limits/joint_limits.hpp"
24#include "rclcpp/rclcpp.hpp"
25#include "rclcpp_lifecycle/lifecycle_node.hpp"
26
27namespace // utilities
28{
30
36template <typename ParameterT>
37auto auto_declare(
38 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
39 const std::string & name, const ParameterT & default_value)
40{
41 if (!param_itf->has_parameter(name))
42 {
43 auto param_default_value = rclcpp::ParameterValue(default_value);
44 param_itf->declare_parameter(name, param_default_value);
45 }
46 return param_itf->get_parameter(name).get_value<ParameterT>();
47}
48} // namespace
49
50namespace joint_limits
51{
84 const std::string & joint_name,
85 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
86 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf)
87{
88 const std::string param_base_name = "joint_limits." + joint_name;
89 try
90 {
91 auto_declare<bool>(param_itf, param_base_name + ".has_position_limits", false);
92 auto_declare<double>(
93 param_itf, param_base_name + ".min_position", std::numeric_limits<double>::quiet_NaN());
94 auto_declare<double>(
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);
97 auto_declare<double>(
98 param_itf, param_base_name + ".min_velocity", std::numeric_limits<double>::quiet_NaN());
99 auto_declare<double>(
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());
120 }
121 catch (const std::exception & ex)
122 {
123 RCLCPP_ERROR(logging_itf->get_logger(), "%s", ex.what());
124 return false;
125 }
126 return true;
127}
128
140inline bool declare_parameters(const std::string & joint_name, const rclcpp::Node::SharedPtr & node)
141{
142 return declare_parameters(
143 joint_name, node->get_node_parameters_interface(), node->get_node_logging_interface());
144}
145
157 const std::string & joint_name, const rclcpp_lifecycle::LifecycleNode::SharedPtr & lifecycle_node)
158{
159 return declare_parameters(
160 joint_name, lifecycle_node->get_node_parameters_interface(),
161 lifecycle_node->get_node_logging_interface());
162}
163
165
218 const std::string & joint_name,
219 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
220 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
221 JointLimits & limits)
222{
223 const std::string param_base_name = "joint_limits." + joint_name;
224 try
225 {
226 if (
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"))
245 {
246 RCLCPP_ERROR(
247 logging_itf->get_logger(),
248 "No joint limits specification found for joint '%s' in the parameter server "
249 "(param name: %s).",
250 joint_name.c_str(), param_base_name.c_str());
251 return false;
252 }
253 }
254 catch (const std::exception & ex)
255 {
256 RCLCPP_ERROR(logging_itf->get_logger(), "%s", ex.what());
257 return false;
258 }
259
260 // Position limits
261 if (param_itf->has_parameter(param_base_name + ".has_position_limits"))
262 {
263 limits.has_position_limits =
264 param_itf->get_parameter(param_base_name + ".has_position_limits").as_bool();
265 if (
266 limits.has_position_limits && param_itf->has_parameter(param_base_name + ".min_position") &&
267 param_itf->has_parameter(param_base_name + ".max_position"))
268 {
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();
271 }
272 else
273 {
274 limits.has_position_limits = false;
275 }
276
277 if (
278 !limits.has_position_limits &&
279 param_itf->has_parameter(param_base_name + ".angle_wraparound"))
280 {
281 limits.angle_wraparound =
282 param_itf->get_parameter(param_base_name + ".angle_wraparound").as_bool();
283 }
284 }
285
286 // Velocity limits
287 if (param_itf->has_parameter(param_base_name + ".has_velocity_limits"))
288 {
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"))
292 {
293 limits.max_velocity = param_itf->get_parameter(param_base_name + ".max_velocity").as_double();
294 }
295 else
296 {
297 limits.has_velocity_limits = false;
298 }
299 }
300
301 // Acceleration limits
302 if (param_itf->has_parameter(param_base_name + ".has_acceleration_limits"))
303 {
304 limits.has_acceleration_limits =
305 param_itf->get_parameter(param_base_name + ".has_acceleration_limits").as_bool();
306 if (
307 limits.has_acceleration_limits &&
308 param_itf->has_parameter(param_base_name + ".max_acceleration"))
309 {
310 limits.max_acceleration =
311 param_itf->get_parameter(param_base_name + ".max_acceleration").as_double();
312 }
313 else
314 {
315 limits.has_acceleration_limits = false;
316 }
317 }
318
319 // Jerk limits
320 if (param_itf->has_parameter(param_base_name + ".has_jerk_limits"))
321 {
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"))
325 {
326 limits.max_jerk = param_itf->get_parameter(param_base_name + ".max_jerk").as_double();
327 }
328 else
329 {
330 limits.has_jerk_limits = false;
331 }
332 }
333
334 // Effort limits
335 if (param_itf->has_parameter(param_base_name + ".has_effort_limits"))
336 {
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"))
340 {
341 limits.has_effort_limits = true;
342 limits.max_effort = param_itf->get_parameter(param_base_name + ".max_effort").as_double();
343 }
344 else
345 {
346 limits.has_effort_limits = false;
347 }
348 }
349
350 return true;
351}
352
367 const std::string & joint_name, const rclcpp::Node::SharedPtr & node, JointLimits & limits)
368{
369 return get_joint_limits(
370 joint_name, node->get_node_parameters_interface(), node->get_node_logging_interface(), limits);
371}
372
387 const std::string & joint_name, const rclcpp_lifecycle::LifecycleNode::SharedPtr & lifecycle_node,
388 JointLimits & limits)
389{
390 return get_joint_limits(
391 joint_name, lifecycle_node->get_node_parameters_interface(),
392 lifecycle_node->get_node_logging_interface(), limits);
393}
394
396
428 const std::string & joint_name,
429 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
430 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
431 SoftJointLimits & soft_limits)
432{
433 const std::string param_base_name = "joint_limits." + joint_name;
434 try
435 {
436 if (
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"))
442 {
443 RCLCPP_DEBUG(
444 logging_itf->get_logger(),
445 "No soft joint limits specification found for joint '%s' in the parameter server "
446 "(param name: %s).",
447 joint_name.c_str(), param_base_name.c_str());
448 return false;
449 }
450 }
451 catch (const std::exception & ex)
452 {
453 RCLCPP_ERROR(logging_itf->get_logger(), "%s", ex.what());
454 return false;
455 }
456
457 // Override soft limits if complete specification is found
458 if (param_itf->has_parameter(param_base_name + ".has_soft_limits"))
459 {
460 if (
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"))
466 {
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();
475 return true;
476 }
477 }
478
479 return false;
480}
481
495 const std::string & joint_name, const rclcpp::Node::SharedPtr & node,
496 SoftJointLimits & soft_limits)
497{
498 return get_joint_limits(
499 joint_name, node->get_node_parameters_interface(), node->get_node_logging_interface(),
500 soft_limits);
501}
502
516 const std::string & joint_name, const rclcpp_lifecycle::LifecycleNode::SharedPtr & lifecycle_node,
517 SoftJointLimits & soft_limits)
518{
519 return get_joint_limits(
520 joint_name, lifecycle_node->get_node_parameters_interface(),
521 lifecycle_node->get_node_logging_interface(), soft_limits);
522}
523
524} // namespace joint_limits
525
526#endif // JOINT_LIMITS__JOINT_LIMITS_ROSPARAM_HPP_
Definition joint_limits.hpp:25
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:83
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:217
Definition joint_limits.hpp:35
Definition joint_limits.hpp:107