moveit2
The MoveIt Motion Planning Framework for ROS 2.
joint_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 
37 
40 #include <moveit/utils/logger.hpp>
41 
42 #include <vector>
43 namespace
44 {
45 rclcpp::Logger getLogger()
46 {
47  return moveit::getLogger("moveit.planners.pilz.joint_limits_aggregator");
48 }
49 } // namespace
50 
53  const rclcpp::Node::SharedPtr& node, const std::string& param_namespace,
54  const std::vector<const moveit::core::JointModel*>& joint_models)
55 {
56  JointLimitsContainer container;
57 
58  RCLCPP_INFO_STREAM(getLogger(), "Reading limits from namespace " << param_namespace);
59 
60  // Iterate over all joint models and generate the map
61  for (auto joint_model : joint_models)
62  {
64 
65  // NOTE: declareParameters fails (=returns false) if the parameters have already been declared.
66  // The function should be checked in the if condition below when we disable
67  // 'NodeOptions::automatically_declare_parameters_from_overrides(true)'
68  joint_limits_interface::declareParameters(joint_model->getName(), param_namespace, node);
69 
70  // If there is something defined for the joint in the node parameters
71  if (joint_limits_interface::getJointLimits(joint_model->getName(), param_namespace, node, joint_limit))
72  {
73  if (joint_limit.has_position_limits)
74  {
75  checkPositionBoundsThrowing(joint_model, joint_limit);
76  }
77  else
78  {
79  updatePositionLimitFromJointModel(joint_model, joint_limit);
80  }
81 
82  if (joint_limit.has_velocity_limits)
83  {
84  checkVelocityBoundsThrowing(joint_model, joint_limit);
85  }
86  else
87  {
88  updateVelocityLimitFromJointModel(joint_model, joint_limit);
89  }
90  }
91  else
92  {
93  // If there is nothing defined for this joint in the node parameters just
94  // update the values by the values of
95  // the urdf
96 
97  updatePositionLimitFromJointModel(joint_model, joint_limit);
98  updateVelocityLimitFromJointModel(joint_model, joint_limit);
99  }
100 
101  // Update max_deceleration if no max_acceleration has been set
102  if (joint_limit.has_acceleration_limits && !joint_limit.has_deceleration_limits)
103  {
104  joint_limit.max_deceleration = -joint_limit.max_acceleration;
105  joint_limit.has_deceleration_limits = true;
106  }
107 
108  // Insert the joint limit into the map
109  container.addLimit(joint_model->getName(), joint_limit);
110  }
111 
112  return container;
113 }
114 
116  const moveit::core::JointModel* joint_model, JointLimit& joint_limit)
117 {
118  switch (joint_model->getVariableBounds().size())
119  {
120  // LCOV_EXCL_START
121  case 0:
122  RCLCPP_WARN_STREAM(getLogger(), "no bounds set for joint " << joint_model->getName());
123  break;
124  // LCOV_EXCL_STOP
125  case 1:
126  joint_limit.has_position_limits = joint_model->getVariableBounds()[0].position_bounded_;
127  joint_limit.min_position = joint_model->getVariableBounds()[0].min_position_;
128  joint_limit.max_position = joint_model->getVariableBounds()[0].max_position_;
129  break;
130  // LCOV_EXCL_START
131  default:
132  RCLCPP_WARN_STREAM(getLogger(), "Multi-DOF-Joint '" << joint_model->getName() << "' not supported.");
133  joint_limit.has_position_limits = true;
134  joint_limit.min_position = 0;
135  joint_limit.max_position = 0;
136  break;
137  // LCOV_EXCL_STOP
138  }
139 
140  RCLCPP_DEBUG_STREAM(getLogger(), "Limit(" << joint_model->getName() << " min:" << joint_limit.min_position
141  << " max:" << joint_limit.max_position);
142 }
143 
145  const moveit::core::JointModel* joint_model, JointLimit& joint_limit)
146 {
147  switch (joint_model->getVariableBounds().size())
148  {
149  // LCOV_EXCL_START
150  case 0:
151  RCLCPP_WARN_STREAM(getLogger(), "no bounds set for joint " << joint_model->getName());
152  break;
153  // LCOV_EXCL_STOP
154  case 1:
155  joint_limit.has_velocity_limits = joint_model->getVariableBounds()[0].velocity_bounded_;
156  joint_limit.max_velocity = joint_model->getVariableBounds()[0].max_velocity_;
157  break;
158  // LCOV_EXCL_START
159  default:
160  RCLCPP_WARN_STREAM(getLogger(), "Multi-DOF-Joint '" << joint_model->getName() << "' not supported.");
161  joint_limit.has_velocity_limits = true;
162  joint_limit.max_velocity = 0;
163  break;
164  // LCOV_EXCL_STOP
165  }
166 }
167 
169  const moveit::core::JointModel* joint_model, const JointLimit& joint_limit)
170 {
171  // Check min position
172  if (!joint_model->satisfiesPositionBounds(&joint_limit.min_position))
173  {
174  throw AggregationBoundsViolationException("min_position of " + joint_model->getName() +
175  " violates min limit from URDF");
176  }
177 
178  // Check max position
179  if (!joint_model->satisfiesPositionBounds(&joint_limit.max_position))
180  {
181  throw AggregationBoundsViolationException("max_position of " + joint_model->getName() +
182  " violates max limit from URDF");
183  }
184 }
185 
187  const moveit::core::JointModel* joint_model, const JointLimit& joint_limit)
188 {
189  // Check min position
190  if (!joint_model->satisfiesVelocityBounds(&joint_limit.max_velocity))
191  {
192  throw AggregationBoundsViolationException("max_velocity of " + joint_model->getName() +
193  " violates velocity limit from URDF");
194  }
195 }
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
bool satisfiesVelocityBounds(const double *values, double margin=0.0) const
Check if the set of velocities for the variables of this joint are within bounds.
Definition: joint_model.h:311
const std::string & getName() const
Get the name of the joint.
Definition: joint_model.h:145
bool satisfiesPositionBounds(const double *values, double margin=0.0) const
Check if the set of values for the variables of this joint are within bounds.
Definition: joint_model.h:280
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
static void checkPositionBoundsThrowing(const moveit::core::JointModel *joint_model, const JointLimit &joint_limit)
Checks if the position limits from the given joint_limit are stricter than the limits of the joint_mo...
static void updateVelocityLimitFromJointModel(const moveit::core::JointModel *joint_model, JointLimit &joint_limit)
Update the velocity limit with the one from the joint_model.
static JointLimitsContainer getAggregatedLimits(const rclcpp::Node::SharedPtr &node, const std::string &param_namespace, const std::vector< const moveit::core::JointModel * > &joint_models)
Aggregates(combines) the joint limits from joint model and node parameters. The rules for the combina...
static void updatePositionLimitFromJointModel(const moveit::core::JointModel *joint_model, JointLimit &joint_limit)
Update the position limits with the ones from the joint_model.
static void checkVelocityBoundsThrowing(const moveit::core::JointModel *joint_model, const JointLimit &joint_limit)
Checks if the velocity limit from the given joint_limit are stricter than the limit of the joint_mode...
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
bool addLimit(const std::string &joint_name, JointLimit joint_limit)
Add a limit.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
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.
double max_deceleration
maximum deceleration MUST(!) be negative