moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
unittest_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
35#include <gtest/gtest.h>
36
39
40using namespace pilz_industrial_motion_planner;
41
42class JointLimitsContainerTest : public ::testing::Test
43{
44protected:
45 void SetUp() override
46 {
48 lim1.has_position_limits = true;
49 lim1.min_position = -2;
50 lim1.max_position = 2;
51 lim1.has_acceleration_limits = true;
52 lim1.max_acceleration = 3; //<- Expected for common_limit_.max_acceleration
53
55 lim2.has_position_limits = true;
56 lim2.min_position = -1; //<- Expected for common_limit_.min_position
57 lim2.max_position = 1; //<- Expected for common_limit_.max_position
58 lim2.has_deceleration_limits = true;
59 lim2.max_deceleration = -5; //<- Expected for common_limit_.max_deceleration
60
62 lim3.has_velocity_limits = true;
63 lim3.max_velocity = 10;
64
66 lim4.has_position_limits = true;
67 lim4.min_position = -1;
68 lim4.max_position = 1;
69 lim4.has_acceleration_limits = true;
70 lim4.max_acceleration = 400;
71 lim4.has_deceleration_limits = false;
72 lim4.max_deceleration = -1;
73
75 lim5.has_position_limits = true;
76 lim5.min_position = -1;
77 lim5.max_position = 1;
78 lim5.has_acceleration_limits = false;
79 lim5.max_acceleration = 1;
80
82 lim6.has_velocity_limits = true;
83 lim6.max_velocity = 2; //<- Expected for common_limit_.max_velocity
84 lim6.has_deceleration_limits = true;
85 lim6.max_deceleration = -100;
86
87 container_.addLimit("joint1", lim1);
88 container_.addLimit("joint2", lim2);
89 container_.addLimit("joint3", lim3);
90 container_.addLimit("joint4", lim4);
91 container_.addLimit("joint5", lim5);
92 container_.addLimit("joint6", lim6);
93
95 }
96
99};
100
104TEST_F(JointLimitsContainerTest, CheckPositionUnification)
105{
106 EXPECT_EQ(-1, common_limit_.min_position);
107 EXPECT_EQ(1, common_limit_.max_position);
108}
109
113TEST_F(JointLimitsContainerTest, CheckVelocityUnification)
114{
115 EXPECT_EQ(2, common_limit_.max_velocity);
116}
117
121TEST_F(JointLimitsContainerTest, CheckAccelerationUnification)
122{
123 EXPECT_EQ(3, common_limit_.max_acceleration);
124}
125
129TEST_F(JointLimitsContainerTest, CheckDecelerationUnification)
130{
131 EXPECT_EQ(-5, common_limit_.max_deceleration);
132}
133
137TEST_F(JointLimitsContainerTest, CheckAddLimitDeceleration)
138{
140 lim_invalid1.has_deceleration_limits = true;
141 lim_invalid1.max_deceleration = 0;
142
144 lim_invalid2.has_deceleration_limits = true;
145 lim_invalid2.max_deceleration = 1;
146
148 lim_valid.has_deceleration_limits = true;
149 lim_valid.max_deceleration = -1;
150
152
153 EXPECT_EQ(false, container.addLimit("joint_invalid1", lim_invalid1));
154 EXPECT_EQ(false, container.addLimit("joint_invalid2", lim_invalid2));
155 EXPECT_EQ(true, container.addLimit("joint_valid", lim_valid));
156}
157
161TEST_F(JointLimitsContainerTest, CheckAddLimitAlreadyContained)
162{
164 lim_valid.has_deceleration_limits = true;
165 lim_valid.max_deceleration = -1;
166
168 ASSERT_TRUE(container.addLimit("joint_valid", lim_valid));
169 EXPECT_FALSE(container.addLimit("joint_valid", lim_valid));
170}
171
175TEST_F(JointLimitsContainerTest, CheckEmptyContainer)
176{
179 EXPECT_FALSE(limits.has_position_limits);
180 EXPECT_FALSE(limits.has_velocity_limits);
181 EXPECT_FALSE(limits.has_acceleration_limits);
182}
183
188{
190
192 lim2.has_position_limits = true;
193 lim2.min_position = -1; //<- Expected for common_limit_.min_position
194 lim2.max_position = 1; //<- Expected for common_limit_.max_position
195
197 container.addLimit("joint1", lim1);
198 container.addLimit("joint2", lim2);
199
201 EXPECT_TRUE(limits.has_position_limits);
202 EXPECT_EQ(1, limits.max_position);
203 EXPECT_EQ(-1, limits.min_position);
204}
205
206int main(int argc, char** argv)
207{
208 testing::InitGoogleTest(&argc, argv);
209 return RUN_ALL_TESTS();
210}
pilz_industrial_motion_planner::JointLimitsContainer container_
pilz_industrial_motion_planner::JointLimit common_limit_
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.
JointLimit getCommonLimit() const
Returns joint limit fusion of all(position, velocity, acceleration, deceleration) limits for all join...
TEST_F(GetSolverTipFrameIntegrationTest, TestHasSolverManipulator)
Check if hasSolver() can be called successfully for the manipulator group.
Extends joint_limits_interface::JointLimits with a deceleration parameter.
int main(int argc, char **argv)