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 
41 #include <vector>
42 namespace
43 {
44 static const rclcpp::Logger LOGGER =
45  rclcpp::get_logger("moveit.pilz_industrial_motion_planner.joint_limits_aggregator");
46 }
47 
50  const rclcpp::Node::SharedPtr& node, const std::string& param_namespace,
51  const std::vector<const moveit::core::JointModel*>& joint_models)
52 {
53  JointLimitsContainer container;
54 
55  RCLCPP_INFO_STREAM(LOGGER, "Reading limits from namespace " << param_namespace);
56 
57  // Iterate over all joint models and generate the map
58  for (auto joint_model : joint_models)
59  {
61 
62  // NOTE: declareParameters fails (=returns false) if the parameters have already been declared.
63  // The function should be checked in the if condition below when we disable
64  // 'NodeOptions::automatically_declare_parameters_from_overrides(true)'
65  joint_limits_interface::declareParameters(joint_model->getName(), param_namespace, node);
66 
67  // If there is something defined for the joint in the node parameters
68  if (joint_limits_interface::getJointLimits(joint_model->getName(), param_namespace, node, joint_limit))
69  {
70  if (joint_limit.has_position_limits)
71  {
72  checkPositionBoundsThrowing(joint_model, joint_limit);
73  }
74  else
75  {
76  updatePositionLimitFromJointModel(joint_model, joint_limit);
77  }
78 
79  if (joint_limit.has_velocity_limits)
80  {
81  checkVelocityBoundsThrowing(joint_model, joint_limit);
82  }
83  else
84  {
85  updateVelocityLimitFromJointModel(joint_model, joint_limit);
86  }
87  }
88  else
89  {
90  // If there is nothing defined for this joint in the node parameters just
91  // update the values by the values of
92  // the urdf
93 
94  updatePositionLimitFromJointModel(joint_model, joint_limit);
95  updateVelocityLimitFromJointModel(joint_model, joint_limit);
96  }
97 
98  // Update max_deceleration if no max_acceleration has been set
99  if (joint_limit.has_acceleration_limits && !joint_limit.has_deceleration_limits)
100  {
101  joint_limit.max_deceleration = -joint_limit.max_acceleration;
102  joint_limit.has_deceleration_limits = true;
103  }
104 
105  // Insert the joint limit into the map
106  container.addLimit(joint_model->getName(), joint_limit);
107  }
108 
109  return container;
110 }
111 
113  const moveit::core::JointModel* joint_model, JointLimit& joint_limit)
114 {
115  switch (joint_model->getVariableBounds().size())
116  {
117  // LCOV_EXCL_START
118  case 0:
119  RCLCPP_WARN_STREAM(LOGGER, "no bounds set for joint " << joint_model->getName());
120  break;
121  // LCOV_EXCL_STOP
122  case 1:
123  joint_limit.has_position_limits = joint_model->getVariableBounds()[0].position_bounded_;
124  joint_limit.min_position = joint_model->getVariableBounds()[0].min_position_;
125  joint_limit.max_position = joint_model->getVariableBounds()[0].max_position_;
126  break;
127  // LCOV_EXCL_START
128  default:
129  RCLCPP_WARN_STREAM(LOGGER, "Multi-DOF-Joint '" << joint_model->getName() << "' not supported.");
130  joint_limit.has_position_limits = true;
131  joint_limit.min_position = 0;
132  joint_limit.max_position = 0;
133  break;
134  // LCOV_EXCL_STOP
135  }
136 
137  RCLCPP_DEBUG_STREAM(LOGGER, "Limit(" << joint_model->getName() << " min:" << joint_limit.min_position
138  << " max:" << joint_limit.max_position);
139 }
140 
142  const moveit::core::JointModel* joint_model, JointLimit& joint_limit)
143 {
144  switch (joint_model->getVariableBounds().size())
145  {
146  // LCOV_EXCL_START
147  case 0:
148  RCLCPP_WARN_STREAM(LOGGER, "no bounds set for joint " << joint_model->getName());
149  break;
150  // LCOV_EXCL_STOP
151  case 1:
152  joint_limit.has_velocity_limits = joint_model->getVariableBounds()[0].velocity_bounded_;
153  joint_limit.max_velocity = joint_model->getVariableBounds()[0].max_velocity_;
154  break;
155  // LCOV_EXCL_START
156  default:
157  RCLCPP_WARN_STREAM(LOGGER, "Multi-DOF-Joint '" << joint_model->getName() << "' not supported.");
158  joint_limit.has_velocity_limits = true;
159  joint_limit.max_velocity = 0;
160  break;
161  // LCOV_EXCL_STOP
162  }
163 }
164 
166  const moveit::core::JointModel* joint_model, const JointLimit& joint_limit)
167 {
168  // Check min position
169  if (!joint_model->satisfiesPositionBounds(&joint_limit.min_position))
170  {
171  throw AggregationBoundsViolationException("min_position of " + joint_model->getName() +
172  " violates min limit from URDF");
173  }
174 
175  // Check max position
176  if (!joint_model->satisfiesPositionBounds(&joint_limit.max_position))
177  {
178  throw AggregationBoundsViolationException("max_position of " + joint_model->getName() +
179  " violates max limit from URDF");
180  }
181 }
182 
184  const moveit::core::JointModel* joint_model, const JointLimit& joint_limit)
185 {
186  // Check min position
187  if (!joint_model->satisfiesVelocityBounds(&joint_limit.max_velocity))
188  {
189  throw AggregationBoundsViolationException("max_velocity of " + joint_model->getName() +
190  " violates velocity limit from URDF");
191  }
192 }
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.
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)
const rclcpp::Logger LOGGER
Definition: async_test.h:31
Extends joint_limits_interface::JointLimits with a deceleration parameter.
double max_deceleration
maximum deceleration MUST(!) be negative