moveit2
The MoveIt Motion Planning Framework for ROS 2.
unittest_trajectory_generator.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 <memory>
36 
37 #include <gtest/gtest.h>
38 
40 
41 using namespace pilz_industrial_motion_planner;
42 
47 TEST(TrajectoryGeneratorTest, TestExceptionErrorCodeMapping)
48 {
49  {
50  auto tgil_ex = std::make_shared<TrajectoryGeneratorInvalidLimitsException>("");
51  EXPECT_EQ(tgil_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::FAILURE);
52  }
53 
54  {
55  auto vsi_ex = std::make_shared<VelocityScalingIncorrect>("");
56  EXPECT_EQ(vsi_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
57  }
58 
59  {
60  auto asi_ex = std::make_shared<AccelerationScalingIncorrect>("");
61  EXPECT_EQ(asi_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
62  }
63 
64  {
65  auto upg_ex = std::make_shared<UnknownPlanningGroup>("");
66  EXPECT_EQ(upg_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME);
67  }
68 
69  {
70  auto njniss_ex = std::make_shared<NoJointNamesInStartState>("");
71  EXPECT_EQ(njniss_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
72  }
73 
74  {
75  auto smiss_ex = std::make_shared<SizeMismatchInStartState>("");
76  EXPECT_EQ(smiss_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
77  }
78 
79  {
80  auto jofssoor_ex = std::make_shared<JointsOfStartStateOutOfRange>("");
81  EXPECT_EQ(jofssoor_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
82  }
83 
84  {
85  auto nzviss_ex = std::make_shared<NonZeroVelocityInStartState>("");
86  EXPECT_EQ(nzviss_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
87  }
88 
89  {
90  auto neogcg_ex = std::make_shared<NotExactlyOneGoalConstraintGiven>("");
91  EXPECT_EQ(neogcg_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
92  }
93 
94  {
95  auto oogta_ex = std::make_shared<OnlyOneGoalTypeAllowed>("");
96  EXPECT_EQ(oogta_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
97  }
98 
99  {
100  auto ssgsm_ex = std::make_shared<StartStateGoalStateMismatch>("");
101  EXPECT_EQ(ssgsm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
102  }
103 
104  {
105  auto jcdnbtg_ex = std::make_shared<JointConstraintDoesNotBelongToGroup>("");
106  EXPECT_EQ(jcdnbtg_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
107  }
108 
109  {
110  auto jogoor_ex = std::make_shared<JointsOfGoalOutOfRange>("");
111  EXPECT_EQ(jogoor_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
112  }
113 
114  {
115  auto pcnm_ex = std::make_shared<PositionConstraintNameMissing>("");
116  EXPECT_EQ(pcnm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
117  }
118 
119  {
120  auto ocnm_ex = std::make_shared<OrientationConstraintNameMissing>("");
121  EXPECT_EQ(ocnm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
122  }
123 
124  {
125  auto pocnm_ex = std::make_shared<PositionOrientationConstraintNameMismatch>("");
126  EXPECT_EQ(pocnm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
127  }
128 
129  {
130  auto nisa_ex = std::make_shared<NoIKSolverAvailable>("");
131  EXPECT_EQ(nisa_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
132  }
133 
134  {
135  auto nppg_ex = std::make_shared<NoPrimitivePoseGiven>("");
136  EXPECT_EQ(nppg_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
137  }
138 }
139 
140 int main(int argc, char** argv)
141 {
142  testing::InitGoogleTest(&argc, argv);
143  return RUN_ALL_TESTS();
144 }
TEST(TrajectoryGeneratorTest, TestExceptionErrorCodeMapping)
Checks that each derived MoveItErrorCodeException contains the correct error code.
int main(int argc, char **argv)