moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
joint_limits_validator.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
42
45{
46 return validateWithEqualFunc(&pilz_industrial_motion_planner::JointLimitsValidator::positionEqual, joint_limits);
47}
48
51{
52 return validateWithEqualFunc(&pilz_industrial_motion_planner::JointLimitsValidator::velocityEqual, joint_limits);
53}
54
57{
58 return validateWithEqualFunc(&pilz_industrial_motion_planner::JointLimitsValidator::accelerationEqual, joint_limits);
59}
60
63{
64 return validateWithEqualFunc(&pilz_industrial_motion_planner::JointLimitsValidator::decelerationEqual, joint_limits);
65}
66
67bool pilz_industrial_motion_planner::JointLimitsValidator::validateWithEqualFunc(
68 bool (*eq_func)(const JointLimit&, const JointLimit&),
70{
71 // If there are no joint_limits it is considered equal
72 if (joint_limits.empty())
73 {
74 return true;
75 }
76
78
79 for (auto it = std::next(joint_limits.begin()); it != joint_limits.end(); ++it)
80 {
81 if (!eq_func(reference, it->second))
82 {
83 return false;
84 }
85 }
86
87 return true;
88}
89
90bool pilz_industrial_motion_planner::JointLimitsValidator::positionEqual(const JointLimit& lhs, const JointLimit& rhs)
91{
92 // Return false if .has_velocity_limits differs
93 if (lhs.has_position_limits != rhs.has_position_limits)
94 {
95 return false;
96 }
97
98 // If velocity limits are the same make sure they are equal
99 if (lhs.has_position_limits && ((lhs.max_position != rhs.max_position) || (lhs.min_position != rhs.min_position)))
100 {
101 return false;
102 }
103 return true;
104}
105
106bool pilz_industrial_motion_planner::JointLimitsValidator::velocityEqual(const JointLimit& lhs, const JointLimit& rhs)
107{
108 // Return false if .has_velocity_limits differs
109 if (lhs.has_velocity_limits != rhs.has_velocity_limits)
110 {
111 return false;
112 }
113
114 // If velocity limits are the same make sure they are equal
115 if (lhs.has_velocity_limits && (lhs.max_velocity != rhs.max_velocity))
116 {
117 return false;
118 }
119
120 return true;
121}
122
123bool pilz_industrial_motion_planner::JointLimitsValidator::accelerationEqual(const JointLimit& lhs,
124 const JointLimit& rhs)
125{
126 // Return false if .has_acceleration_limits differs
127 if (lhs.has_acceleration_limits != rhs.has_acceleration_limits)
128 {
129 return false;
130 }
131
132 // If velocity limits are the same make sure they are equal
133 if (lhs.has_acceleration_limits && (lhs.max_acceleration != rhs.max_acceleration))
134 {
135 return false;
136 }
137
138 return true;
139}
140
141bool pilz_industrial_motion_planner::JointLimitsValidator::decelerationEqual(const JointLimit& lhs,
142 const JointLimit& rhs)
143{
144 // Return false if .has_acceleration_limits differs
145 if (lhs.has_deceleration_limits != rhs.has_deceleration_limits)
146 {
147 return false;
148 }
149
150 // If velocity limits are the same make sure they are equal
151 if (lhs.has_deceleration_limits && (lhs.max_deceleration != rhs.max_deceleration))
152 {
153 return false;
154 }
155
156 return true;
157}
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
static bool validateAllPositionLimitsEqual(const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits)
Validates that the position limits of all limits are equal.
static bool validateAllDecelerationLimitsEqual(const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits)
Validates that the deceleration of all limits is equal.
static bool validateAllVelocityLimitsEqual(const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits)
Validates that the velocity of all limits is equal.
static bool validateAllAccelerationLimitsEqual(const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits)
Validates that the acceleration of all limits is equal.
joint_limits_interface::JointLimits JointLimit
Extends joint_limits_interface::JointLimits with a deceleration parameter.