moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
unittest_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
35#include <gtest/gtest.h>
36
39
43
44#include <rclcpp/rclcpp.hpp>
45
49class JointLimitsAggregator : public ::testing::Test
50{
51protected:
52 void SetUp() override
53 {
54 rclcpp::NodeOptions node_options;
55 // node_options.automatically_declare_parameters_from_overrides(true);
56 node_ = rclcpp::Node::make_shared("unittest_joint_limits_aggregator", node_options);
57
58 // load robot model
59 rm_loader_ = std::make_unique<robot_model_loader::RobotModelLoader>(node_);
60 robot_model_ = rm_loader_->getModel();
61 ASSERT_TRUE(bool(robot_model_)) << "Failed to load robot model";
62 }
63
64 void TearDown() override
65 {
66 robot_model_.reset();
67 }
68
69protected:
70 rclcpp::Node::SharedPtr node_;
71 moveit::core::RobotModelConstPtr robot_model_;
72 std::unique_ptr<robot_model_loader::RobotModelLoader> rm_loader_;
73};
74
80{
83 robot_model_->getActiveJointModels());
84
85 EXPECT_EQ(robot_model_->getActiveJointModels().size(), container.getCount());
86}
87
92TEST_F(JointLimitsAggregator, CorrectOverwriteByParamterPosition)
93{
96 robot_model_->getActiveJointModels());
97
98 for (const auto& lim : container)
99 {
100 // Check for the overwrite
101 if (lim.first == "prbt_joint_1")
102 {
103 EXPECT_EQ(2, container.getLimit(lim.first).max_position);
104 EXPECT_EQ(-2, container.getLimit(lim.first).min_position);
105 }
106 // Check that nothing else changed
107 else
108 {
109 EXPECT_EQ(robot_model_->getJointModel(lim.first)->getVariableBounds()[0].min_position_,
110 container.getLimit(lim.first).min_position);
111 EXPECT_EQ(robot_model_->getJointModel(lim.first)->getVariableBounds()[0].max_position_,
112 container.getLimit(lim.first).max_position);
113 }
114 }
115}
116
121TEST_F(JointLimitsAggregator, CorrectOverwriteByParamterVelocity)
122{
125 robot_model_->getActiveJointModels());
126
127 for (const auto& lim : container)
128 {
129 // Check that velocity was only changed in joint "prbt_joint_3"
130 if (lim.first == "prbt_joint_3")
131 {
132 EXPECT_EQ(1.1, container.getLimit(lim.first).max_velocity);
133 }
134 else
135 {
136 EXPECT_EQ(robot_model_->getJointModel(lim.first)->getVariableBounds()[0].max_velocity_,
137 container.getLimit(lim.first).max_velocity);
138 }
139 }
140}
141
145TEST_F(JointLimitsAggregator, CorrectSettingAccelerationAndDeceleration)
146{
149 robot_model_->getActiveJointModels());
150
151 for (const auto& lim : container)
152 {
153 if (lim.first == "prbt_joint_4")
154 {
155 EXPECT_EQ(5.5, container.getLimit(lim.first).max_acceleration) << lim.first;
156 EXPECT_EQ(-5.5, container.getLimit(lim.first).max_deceleration) << lim.first;
157 }
158 else if (lim.first == "prbt_joint_5")
159 {
160 EXPECT_TRUE(std::isnan(container.getLimit(lim.first).max_acceleration)) << lim.first;
161 EXPECT_EQ(-6.6, container.getLimit(lim.first).max_deceleration) << lim.first;
162 }
163 else
164 {
165 EXPECT_TRUE(std::isnan(container.getLimit(lim.first).max_acceleration)) << lim.first;
166 EXPECT_EQ(0, container.getLimit(lim.first).max_deceleration) << lim.first;
167 }
168 }
169}
170
174TEST_F(JointLimitsAggregator, LimitsViolationPosition)
175{
177 node_, "violate_position_min", robot_model_->getActiveJointModels()),
179
181 node_, "violate_position_max", robot_model_->getActiveJointModels()),
183}
184
188TEST_F(JointLimitsAggregator, LimitsViolationVelocity)
189{
191 node_, "violate_velocity", robot_model_->getActiveJointModels()),
193}
194
195int main(int argc, char** argv)
196{
197 rclcpp::init(argc, argv);
198 testing::InitGoogleTest(&argc, argv);
199 return RUN_ALL_TESTS();
200}
Unittest of the JointLimitsAggregator class.
moveit::core::RobotModelConstPtr robot_model_
std::unique_ptr< robot_model_loader::RobotModelLoader > rm_loader_
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...
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
JointLimit getLimit(const std::string &joint_name) const
getLimit get the limit for the given joint name
size_t getCount() const
Get Number of limits in the container.
TEST_F(JointLimitsAggregator, ExpectedMapSize)
Check for that the size of the map and the size of the given joint models is equal.
int main(int argc, char **argv)