moveit2
The MoveIt Motion Planning Framework for ROS 2.
unittest_joint_limit.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 <rclcpp/rclcpp.hpp>
36 
37 #include <gtest/gtest.h>
38 
41 
42 using namespace pilz_industrial_motion_planner;
44 
46 {
47 class JointLimitTest : public ::testing::Test
48 {
49 protected:
50  void SetUp() override
51  {
52  node_ = rclcpp::Node::make_shared("unittest_joint_limits_extended");
53  }
54  rclcpp::Node::SharedPtr node_;
55 };
56 
57 TEST_F(JointLimitTest, SimpleRead)
58 {
59  // Joints limits interface
60  JointLimits joint_limits_extended;
61 
62  EXPECT_TRUE(declareParameters("joint_1", "", node_));
63  EXPECT_TRUE(getJointLimits("joint_1", "", node_, joint_limits_extended));
64 
65  EXPECT_EQ(1, joint_limits_extended.max_acceleration);
66  EXPECT_EQ(-1, joint_limits_extended.max_deceleration);
67 }
68 
69 TEST_F(JointLimitTest, readNonExistingJointLimit)
70 {
71  // Joints limits interface
72  JointLimits joint_limits_extended;
73 
74  EXPECT_FALSE(getJointLimits("anything", "", node_, joint_limits_extended));
75 }
76 
82 TEST_F(JointLimitTest, readInvalidParameterName)
83 {
84  // Joints limits interface
85  JointLimits joint_limits_extended;
86 
87  EXPECT_FALSE(getJointLimits("~anything", "", node_, joint_limits_extended));
88 }
89 
91 {
92  // Joints limits interface
94 
95  EXPECT_TRUE(declareParameters("joint_1", "", node_));
96  EXPECT_TRUE(getJointLimits("joint_1", "", node_, joint_limits));
97 
98  EXPECT_EQ(1, joint_limits.max_acceleration);
99 }
100 } // namespace pilz_extensions_tests
101 
102 int main(int argc, char** argv)
103 {
104  rclcpp::init(argc, argv);
105  testing::InitGoogleTest(&argc, argv);
106  return RUN_ALL_TESTS();
107 }
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)
TEST_F(GetSolverTipFrameIntegrationTest, TestHasSolverManipulator)
Check if hasSolver() can be called successfully for the manipulator group.
Extends joint_limits_interface::JointLimits with a deceleration parameter.
double max_deceleration
maximum deceleration MUST(!) be negative
int main(int argc, char **argv)