@@ -34,7 +34,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
3434#include < tesseract_environment/environment.h>
3535#include < tesseract_motion_planners/core/types.h>
3636#include < tesseract_motion_planners/simple/simple_motion_planner.h>
37- #include < tesseract_motion_planners/simple/profile/simple_planner_fixed_size_assign_plan_profile .h>
37+ #include < tesseract_motion_planners/simple/profile/simple_planner_fixed_size_assign_no_ik_plan_profile .h>
3838#include < tesseract_command_language/joint_waypoint.h>
3939#include < tesseract_command_language/cartesian_waypoint.h>
4040#include < tesseract_command_language/move_instruction.h>
@@ -43,7 +43,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
4343using namespace tesseract_environment ;
4444using namespace tesseract_planning ;
4545
46- class TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit : public ::testing::Test
46+ class TesseractPlanningSimplePlannerFixedSizeAssignNoIKPositionUnit : public ::testing::Test
4747{
4848protected:
4949 Environment::Ptr env_;
@@ -66,7 +66,7 @@ class TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit : public ::testi
6666 }
6767};
6868
69- TEST_F (TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit , JointCartesian_AssignJointPosition) // NOLINT
69+ TEST_F (TesseractPlanningSimplePlannerFixedSizeAssignNoIKPositionUnit , JointCartesian_AssignJointPosition) // NOLINT
7070{
7171 PlannerRequest request;
7272 request.env = env_;
@@ -81,7 +81,7 @@ TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit, JointCartesian
8181
8282 InstructionPoly instr3;
8383
84- SimplePlannerFixedSizeAssignPlanProfile profile (10 , 10 );
84+ SimplePlannerFixedSizeAssignNoIKPlanProfile profile (10 , 10 );
8585 std::vector<MoveInstructionPoly> move_instructions =
8686 profile.generate (instr1, instr1_seed, instr2, instr3, request, tesseract_common::ManipulatorInfo ());
8787 EXPECT_EQ (move_instructions.size (), 10 );
@@ -108,7 +108,7 @@ TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit, JointCartesian
108108 EXPECT_EQ (mi.getPathProfile (), instr2.getPathProfile ());
109109}
110110
111- TEST_F (TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit , CartesianJoint_AssignJointPosition) // NOLINT
111+ TEST_F (TesseractPlanningSimplePlannerFixedSizeAssignNoIKPositionUnit , CartesianJoint_AssignJointPosition) // NOLINT
112112{
113113 PlannerRequest request;
114114 request.env = env_;
@@ -123,7 +123,7 @@ TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit, CartesianJoint
123123
124124 InstructionPoly instr3;
125125
126- SimplePlannerFixedSizeAssignPlanProfile profile (10 , 10 );
126+ SimplePlannerFixedSizeAssignNoIKPlanProfile profile (10 , 10 );
127127 std::vector<MoveInstructionPoly> move_instructions =
128128 profile.generate (instr1, instr1_seed, instr2, instr3, request, tesseract_common::ManipulatorInfo ());
129129 EXPECT_EQ (move_instructions.size (), 10 );
@@ -149,7 +149,7 @@ TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit, CartesianJoint
149149 EXPECT_EQ (mi.getPathProfile (), instr2.getPathProfile ());
150150}
151151
152- TEST_F (TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit , CartesianCartesian_AssignJointPosition) // NOLINT
152+ TEST_F (TesseractPlanningSimplePlannerFixedSizeAssignNoIKPositionUnit , CartesianCartesian_AssignJointPosition) // NOLINT
153153{
154154 PlannerRequest request;
155155 request.env = env_;
@@ -164,7 +164,7 @@ TEST_F(TesseractPlanningSimplePlannerFixedSizeAssignPositionUnit, CartesianCarte
164164
165165 InstructionPoly instr3;
166166
167- SimplePlannerFixedSizeAssignPlanProfile profile (10 , 10 );
167+ SimplePlannerFixedSizeAssignNoIKPlanProfile profile (10 , 10 );
168168 std::vector<MoveInstructionPoly> move_instructions =
169169 profile.generate (instr1, instr1_seed, instr2, instr3, request, tesseract_common::ManipulatorInfo ());
170170 auto fwd_kin = env_->getJointGroup (manip_info_.manipulator );
0 commit comments