37 #include <gtest/gtest.h> 
   47 TEST(TrajectoryGeneratorTest, TestExceptionErrorCodeMapping)
 
   50     std::shared_ptr<TrajectoryGeneratorInvalidLimitsException> tgil_ex{ 
new TrajectoryGeneratorInvalidLimitsException(
 
   52     EXPECT_EQ(tgil_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::FAILURE);
 
   56     std::shared_ptr<VelocityScalingIncorrect> vsi_ex{ 
new VelocityScalingIncorrect(
"") };
 
   57     EXPECT_EQ(vsi_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
 
   61     std::shared_ptr<AccelerationScalingIncorrect> asi_ex{ 
new AccelerationScalingIncorrect(
"") };
 
   62     EXPECT_EQ(asi_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
 
   66     std::shared_ptr<UnknownPlanningGroup> upg_ex{ 
new UnknownPlanningGroup(
"") };
 
   67     EXPECT_EQ(upg_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME);
 
   71     std::shared_ptr<NoJointNamesInStartState> njniss_ex{ 
new NoJointNamesInStartState(
"") };
 
   72     EXPECT_EQ(njniss_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
 
   76     std::shared_ptr<SizeMismatchInStartState> smiss_ex{ 
new SizeMismatchInStartState(
"") };
 
   77     EXPECT_EQ(smiss_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
 
   81     std::shared_ptr<JointsOfStartStateOutOfRange> jofssoor_ex{ 
new JointsOfStartStateOutOfRange(
"") };
 
   82     EXPECT_EQ(jofssoor_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
 
   86     std::shared_ptr<NonZeroVelocityInStartState> nzviss_ex{ 
new NonZeroVelocityInStartState(
"") };
 
   87     EXPECT_EQ(nzviss_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
 
   91     std::shared_ptr<NotExactlyOneGoalConstraintGiven> neogcg_ex{ 
new NotExactlyOneGoalConstraintGiven(
"") };
 
   92     EXPECT_EQ(neogcg_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
 
   96     std::shared_ptr<OnlyOneGoalTypeAllowed> oogta_ex{ 
new OnlyOneGoalTypeAllowed(
"") };
 
   97     EXPECT_EQ(oogta_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
 
  101     std::shared_ptr<StartStateGoalStateMismatch> ssgsm_ex{ 
new StartStateGoalStateMismatch(
"") };
 
  102     EXPECT_EQ(ssgsm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
 
  106     std::shared_ptr<JointConstraintDoesNotBelongToGroup> jcdnbtg_ex{ 
new JointConstraintDoesNotBelongToGroup(
"") };
 
  107     EXPECT_EQ(jcdnbtg_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
 
  111     std::shared_ptr<JointsOfGoalOutOfRange> jogoor_ex{ 
new JointsOfGoalOutOfRange(
"") };
 
  112     EXPECT_EQ(jogoor_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
 
  116     std::shared_ptr<PositionConstraintNameMissing> pcnm_ex{ 
new PositionConstraintNameMissing(
"") };
 
  117     EXPECT_EQ(pcnm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
 
  121     std::shared_ptr<OrientationConstraintNameMissing> ocnm_ex{ 
new OrientationConstraintNameMissing(
"") };
 
  122     EXPECT_EQ(ocnm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
 
  126     std::shared_ptr<PositionOrientationConstraintNameMismatch> pocnm_ex{ 
new PositionOrientationConstraintNameMismatch(
 
  128     EXPECT_EQ(pocnm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
 
  132     std::shared_ptr<NoIKSolverAvailable> nisa_ex{ 
new NoIKSolverAvailable(
"") };
 
  133     EXPECT_EQ(nisa_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
 
  137     std::shared_ptr<NoPrimitivePoseGiven> nppg_ex{ 
new NoPrimitivePoseGiven(
"") };
 
  138     EXPECT_EQ(nppg_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
 
  142 int main(
int argc, 
char** argv)
 
  144   testing::InitGoogleTest(&argc, argv);
 
  145   return RUN_ALL_TESTS();
 
TEST(TrajectoryGeneratorTest, TestExceptionErrorCodeMapping)
Checks that each derived MoveItErrorCodeException contains the correct error code.
 
int main(int argc, char **argv)