moveit2
The MoveIt Motion Planning Framework for ROS 2.
cartesian_limits_aggregator.cpp
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 #include <rclcpp/exceptions/exceptions.hpp>
36 #include <rclcpp/logging.hpp>
37 #include <rclcpp/node.hpp>
38 #include <rclcpp/parameter_value.hpp>
39 #include <limits>
40 
42 
43 static const std::string PARAM_CARTESIAN_LIMITS_NS = "cartesian_limits";
44 
45 static const std::string PARAM_MAX_TRANS_VEL = "max_trans_vel";
46 static const std::string PARAM_MAX_TRANS_ACC = "max_trans_acc";
47 static const std::string PARAM_MAX_TRANS_DEC = "max_trans_dec";
48 static const std::string PARAM_MAX_ROT_VEL = "max_rot_vel";
49 static const std::string PARAM_MAX_ROT_ACC = "max_rot_acc";
50 static const std::string PARAM_MAX_ROT_DEC = "max_rot_dec";
51 
52 // TODO(sjahr) Refactor and use repository wide solution
53 bool declareAndGetParam(double& output_value, const std::string& param_name, const rclcpp::Node::SharedPtr& node)
54 {
55  try
56  {
57  if (!node->has_parameter(param_name))
58  {
59  node->declare_parameter<double>(param_name, std::numeric_limits<double>::quiet_NaN());
60  }
61  node->get_parameter<double>(param_name, output_value);
62  if (std::isnan(output_value))
63  {
64  RCLCPP_ERROR(node->get_logger(), "Parameter \'%s\', is not set in the config file.", param_name.c_str());
65  return false;
66  }
67  return true;
68  }
69  catch (const rclcpp::exceptions::InvalidParameterTypeException& e)
70  {
71  RCLCPP_WARN(node->get_logger(), "InvalidParameterTypeException(\'%s\'): %s", param_name.c_str(), e.what());
72  RCLCPP_ERROR(node->get_logger(), "Error getting parameter \'%s\', check parameter type in YAML file",
73  param_name.c_str());
74  throw e;
75  }
76 }
77 
80  const std::string& param_namespace)
81 {
82  std::string param_prefix = param_namespace + "." + PARAM_CARTESIAN_LIMITS_NS + ".";
83 
85 
86  // translational velocity
87  double max_trans_vel;
88  if (declareAndGetParam(max_trans_vel, param_prefix + PARAM_MAX_TRANS_VEL, node))
89  {
90  cartesian_limit.setMaxTranslationalVelocity(max_trans_vel);
91  }
92 
93  // translational acceleration
94  double max_trans_acc;
95  if (declareAndGetParam(max_trans_acc, param_prefix + PARAM_MAX_TRANS_ACC, node))
96  {
97  cartesian_limit.setMaxTranslationalAcceleration(max_trans_acc);
98  }
99 
100  // translational deceleration
101  double max_trans_dec;
102  if (declareAndGetParam(max_trans_dec, param_prefix + PARAM_MAX_TRANS_DEC, node))
103  {
104  cartesian_limit.setMaxTranslationalDeceleration(max_trans_dec);
105  }
106 
107  // rotational velocity
108  double max_rot_vel;
109  if (declareAndGetParam(max_rot_vel, param_prefix + PARAM_MAX_ROT_VEL, node))
110  {
111  cartesian_limit.setMaxRotationalVelocity(max_rot_vel);
112  }
113 
114  // rotational acceleration + deceleration deprecated
115  // LCOV_EXCL_START
116  if (node->has_parameter(param_prefix + PARAM_MAX_ROT_ACC) || node->has_parameter(param_prefix + PARAM_MAX_ROT_DEC))
117  {
118  RCLCPP_WARN(node->get_logger(),
119  "Ignoring cartesian limits parameters for rotational acceleration / deceleration; these parameters are "
120  "deprecated and are automatically calculated from translational to rotational ratio.");
121  }
122  // LCOV_EXCL_STOP
123 
124  return cartesian_limit;
125 }
bool declareAndGetParam(double &output_value, const std::string &param_name, const rclcpp::Node::SharedPtr &node)
Set of cartesian limits, has values for velocity, acceleration and deceleration of both the translati...
void setMaxRotationalVelocity(double max_rot_vel)
Set the maximum rotational velocity.
void setMaxTranslationalVelocity(double max_trans_vel)
Set the maximal translational velocity.
void setMaxTranslationalAcceleration(double max_trans_acc)
Set the maximum translational acceleration.
void setMaxTranslationalDeceleration(double max_trans_dec)
Set the maximum translational deceleration.
static CartesianLimit getAggregatedLimits(const rclcpp::Node::SharedPtr &node, const std::string &param_namespace)
Loads cartesian limits from the node parameters.