moveit2
The MoveIt Motion Planning Framework for ROS 2.
joint_limits_container.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 
36 #include <cmath>
37 
38 #include <rclcpp/logger.hpp>
39 #include <rclcpp/logging.hpp>
40 #include <stdexcept>
41 #include <moveit/utils/logger.hpp>
42 
44 {
45 namespace
46 {
47 rclcpp::Logger getLogger()
48 {
49  return moveit::getLogger("moveit.planners.pilz.joint_limits_container");
50 }
51 } // namespace
52 bool JointLimitsContainer::addLimit(const std::string& joint_name,
54 {
55  if (joint_limit.has_deceleration_limits && joint_limit.max_deceleration >= 0)
56  {
57  RCLCPP_ERROR_STREAM(getLogger(), "joint_limit.max_deceleration MUST be negative!");
58  return false;
59  }
60  const auto& insertion_result{ container_.insert(std::pair<std::string, JointLimit>(joint_name, joint_limit)) };
61  if (!insertion_result.second)
62  {
63  RCLCPP_ERROR_STREAM(getLogger(), "joint_limit for joint " << joint_name << " already contained.");
64  return false;
65  }
66  return true;
67 }
68 
69 bool JointLimitsContainer::hasLimit(const std::string& joint_name) const
70 {
71  return container_.find(joint_name) != container_.end();
72 }
73 
75 {
76  return container_.size();
77 }
78 
80 {
81  return container_.empty();
82 }
83 
85 {
87  for (const auto& limit : container_)
88  {
89  updateCommonLimit(limit.second, common_limit);
90  }
91  return common_limit;
92 }
93 
94 JointLimit JointLimitsContainer::getCommonLimit(const std::vector<std::string>& joint_names) const
95 {
97  for (const auto& joint_name : joint_names)
98  {
99  updateCommonLimit(container_.at(joint_name), common_limit);
100  }
101  return common_limit;
102 }
103 
104 JointLimit JointLimitsContainer::getLimit(const std::string& joint_name) const
105 {
106  return container_.at(joint_name);
107 }
108 
109 std::map<std::string, JointLimit>::const_iterator JointLimitsContainer::begin() const
110 {
111  return container_.begin();
112 }
113 
114 std::map<std::string, JointLimit>::const_iterator JointLimitsContainer::end() const
115 {
116  return container_.end();
117 }
118 
119 bool JointLimitsContainer::verifyPositionLimit(const std::string& joint_name, double joint_position) const
120 {
121  return !hasLimit(joint_name) || !getLimit(joint_name).has_position_limits ||
122  (joint_position >= getLimit(joint_name).min_position && joint_position <= getLimit(joint_name).max_position);
123 }
124 
125 bool JointLimitsContainer::verifyVelocityLimit(const std::string& joint_name, double joint_velocity) const
126 {
127  return !hasLimit(joint_name) || !getLimit(joint_name).has_velocity_limits ||
128  fabs(joint_velocity) <= getLimit(joint_name).max_velocity;
129 }
130 
131 bool JointLimitsContainer::verifyAccelerationLimit(const std::string& joint_name, double joint_acceleration) const
132 {
133  return !hasLimit(joint_name) || !getLimit(joint_name).has_acceleration_limits ||
134  fabs(joint_acceleration) <= getLimit(joint_name).max_acceleration;
135 }
136 
137 bool JointLimitsContainer::verifyDecelerationLimit(const std::string& joint_name, double joint_acceleration) const
138 {
139  return !hasLimit(joint_name) || !getLimit(joint_name).has_deceleration_limits ||
140  fabs(joint_acceleration) <= -1.0 * getLimit(joint_name).max_deceleration;
141 }
142 
143 void JointLimitsContainer::updateCommonLimit(const JointLimit& joint_limit, JointLimit& common_limit)
144 {
145  // check position limits
146  if (joint_limit.has_position_limits)
147  {
148  double min_position = joint_limit.min_position;
149  double max_position = joint_limit.max_position;
150 
151  common_limit.min_position =
152  (!common_limit.has_position_limits) ? min_position : std::max(common_limit.min_position, min_position);
153  common_limit.max_position =
154  (!common_limit.has_position_limits) ? max_position : std::min(common_limit.max_position, max_position);
155  common_limit.has_position_limits = true;
156  }
157 
158  // check velocity limits
159  if (joint_limit.has_velocity_limits)
160  {
161  double max_velocity = joint_limit.max_velocity;
162  common_limit.max_velocity =
163  (!common_limit.has_velocity_limits) ? max_velocity : std::min(common_limit.max_velocity, max_velocity);
164  common_limit.has_velocity_limits = true;
165  }
166 
167  // check acceleration limits
168  if (joint_limit.has_acceleration_limits)
169  {
170  double max_acc = joint_limit.max_acceleration;
171  common_limit.max_acceleration =
172  (!common_limit.has_acceleration_limits) ? max_acc : std::min(common_limit.max_acceleration, max_acc);
173  common_limit.has_acceleration_limits = true;
174  }
175 
176  // check deceleration limits
177  if (joint_limit.has_deceleration_limits)
178  {
179  double max_dec = joint_limit.max_deceleration;
180  common_limit.max_deceleration =
181  (!common_limit.has_deceleration_limits) ? max_dec : std::max(common_limit.max_deceleration, max_dec);
182  common_limit.has_deceleration_limits = true;
183  }
184 }
185 
186 } // namespace pilz_industrial_motion_planner
JointLimit getLimit(const std::string &joint_name) const
getLimit get the limit for the given joint name
bool hasLimit(const std::string &joint_name) const
Check if there is a limit for a joint with the given name in this container.
std::map< std::string, JointLimit >::const_iterator end() const
ConstIterator to the underlying data structure.
std::map< std::string, JointLimit > container_
Actual container object containing the data.
bool addLimit(const std::string &joint_name, JointLimit joint_limit)
Add a limit.
std::map< std::string, JointLimit >::const_iterator begin() const
ConstIterator to the underlying data structure.
size_t getCount() const
Get Number of limits in the container.
bool empty() const
Returns whether the container is empty.
bool verifyVelocityLimit(const std::string &joint_name, double joint_velocity) const
verify velocity limit of single joint
bool verifyPositionLimit(const std::string &joint_name, double joint_position) const
verify position limit of single joint
bool verifyAccelerationLimit(const std::string &joint_name, double joint_acceleration) const
verify acceleration limit of single joint
bool verifyDecelerationLimit(const std::string &joint_name, double joint_acceleration) const
verify deceleration limit of single joint
JointLimit getCommonLimit() const
Returns joint limit fusion of all(position, velocity, acceleration, deceleration) limits for all join...
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
Extends joint_limits_interface::JointLimits with a deceleration parameter.
double max_deceleration
maximum deceleration MUST(!) be negative