47TEST(TrajectoryGeneratorTest, TestExceptionErrorCodeMapping)
50 auto tgil_ex = std::make_shared<TrajectoryGeneratorInvalidLimitsException>(
"");
51 EXPECT_EQ(tgil_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::FAILURE);
55 auto vsi_ex = std::make_shared<VelocityScalingIncorrect>(
"");
56 EXPECT_EQ(vsi_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
60 auto asi_ex = std::make_shared<AccelerationScalingIncorrect>(
"");
61 EXPECT_EQ(asi_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
65 auto upg_ex = std::make_shared<UnknownPlanningGroup>(
"");
66 EXPECT_EQ(upg_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME);
70 auto njniss_ex = std::make_shared<NoJointNamesInStartState>(
"");
71 EXPECT_EQ(njniss_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
75 auto smiss_ex = std::make_shared<SizeMismatchInStartState>(
"");
76 EXPECT_EQ(smiss_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
80 auto jofssoor_ex = std::make_shared<JointsOfStartStateOutOfRange>(
"");
81 EXPECT_EQ(jofssoor_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
85 auto nzviss_ex = std::make_shared<NonZeroVelocityInStartState>(
"");
86 EXPECT_EQ(nzviss_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
90 auto neogcg_ex = std::make_shared<NotExactlyOneGoalConstraintGiven>(
"");
91 EXPECT_EQ(neogcg_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
95 auto oogta_ex = std::make_shared<OnlyOneGoalTypeAllowed>(
"");
96 EXPECT_EQ(oogta_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
100 auto ssgsm_ex = std::make_shared<StartStateGoalStateMismatch>(
"");
101 EXPECT_EQ(ssgsm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
105 auto jcdnbtg_ex = std::make_shared<JointConstraintDoesNotBelongToGroup>(
"");
106 EXPECT_EQ(jcdnbtg_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
110 auto jogoor_ex = std::make_shared<JointsOfGoalOutOfRange>(
"");
111 EXPECT_EQ(jogoor_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
115 auto pcnm_ex = std::make_shared<PositionConstraintNameMissing>(
"");
116 EXPECT_EQ(pcnm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
120 auto ocnm_ex = std::make_shared<OrientationConstraintNameMissing>(
"");
121 EXPECT_EQ(ocnm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
125 auto pocnm_ex = std::make_shared<PositionOrientationConstraintNameMismatch>(
"");
126 EXPECT_EQ(pocnm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
130 auto nisa_ex = std::make_shared<NoIKSolverAvailable>(
"");
131 EXPECT_EQ(nisa_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
135 auto nppg_ex = std::make_shared<NoPrimitivePoseGiven>(
"");
136 EXPECT_EQ(nppg_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);