diff --git a/tesseract_motion_planners/simple/test/simple_planner_fixed_size_assign_position.cpp b/tesseract_motion_planners/simple/test/simple_planner_fixed_size_assign_position.cpp index 7364a9dbfb..114a1d8160 100644 --- a/tesseract_motion_planners/simple/test/simple_planner_fixed_size_assign_position.cpp +++ b/tesseract_motion_planners/simple/test/simple_planner_fixed_size_assign_position.cpp @@ -34,7 +34,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP #include #include #include -#include +#include #include #include #include @@ -43,7 +43,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP using namespace tesseract_environment; using namespace tesseract_planning; -class TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit : public ::testing::Test +class TesseractPlanningSimplePlannerFixedSizeAssignNoIKPositionUnit : public ::testing::Test { protected: Environment::Ptr env_; @@ -66,7 +66,7 @@ class TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit : public ::testi } }; -TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit, JointCartesian_AssignJointPosition) // NOLINT +TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignNoIKPositionUnit, JointCartesian_AssignJointPosition) // NOLINT { PlannerRequest request; request.env = env_; @@ -81,7 +81,7 @@ TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit, JointCartesian InstructionPoly instr3; - SimplePlannerFixedSizeAssignPlanProfile profile(10, 10); + SimplePlannerFixedSizeAssignNoIKPlanProfile profile(10, 10); std::vector move_instructions = profile.generate(instr1, instr1_seed, instr2, instr3, request, tesseract_common::ManipulatorInfo()); EXPECT_EQ(move_instructions.size(), 10); @@ -108,7 +108,7 @@ TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit, JointCartesian EXPECT_EQ(mi.getPathProfile(), instr2.getPathProfile()); } -TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit, CartesianJoint_AssignJointPosition) // NOLINT +TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignNoIKPositionUnit, CartesianJoint_AssignJointPosition) // NOLINT { PlannerRequest request; request.env = env_; @@ -123,7 +123,7 @@ TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit, CartesianJoint InstructionPoly instr3; - SimplePlannerFixedSizeAssignPlanProfile profile(10, 10); + SimplePlannerFixedSizeAssignNoIKPlanProfile profile(10, 10); std::vector move_instructions = profile.generate(instr1, instr1_seed, instr2, instr3, request, tesseract_common::ManipulatorInfo()); EXPECT_EQ(move_instructions.size(), 10); @@ -149,7 +149,7 @@ TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit, CartesianJoint EXPECT_EQ(mi.getPathProfile(), instr2.getPathProfile()); } -TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit, CartesianCartesian_AssignJointPosition) // NOLINT +TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignNoIKPositionUnit, CartesianCartesian_AssignJointPosition) // NOLINT { PlannerRequest request; request.env = env_; @@ -164,7 +164,7 @@ TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit, CartesianCarte InstructionPoly instr3; - SimplePlannerFixedSizeAssignPlanProfile profile(10, 10); + SimplePlannerFixedSizeAssignNoIKPlanProfile profile(10, 10); std::vector move_instructions = profile.generate(instr1, instr1_seed, instr2, instr3, request, tesseract_common::ManipulatorInfo()); auto fwd_kin = env_->getJointGroup(manip_info_.manipulator);