@@ -87,7 +87,7 @@ TEST_F(TesseractPlanningSimplePlannerLVSPlanProfileUnit, InterpolateStateWaypoin
8787 auto cl = cl_profile.generate (instr1, instr1_seed, instr2, instr3, env_, tesseract_common::ManipulatorInfo ());
8888 double dist = (wp1.getPosition () - wp2.getPosition ()).norm ();
8989 int steps = int (dist / longest_valid_segment_length) + 1 ;
90- EXPECT_TRUE (static_cast <int >(cl.size ()) > min_steps);
90+ EXPECT_GT (static_cast <int >(cl.size ()), min_steps);
9191 EXPECT_EQ (cl.size (), steps);
9292}
9393
@@ -143,7 +143,7 @@ TEST_F(TesseractPlanningSimplePlannerLVSPlanProfileUnit, InterpolateStateWaypoin
143143 Eigen::Isometry3d p2 = joint_group->calcFwdKin (wp2.getPosition ()).at (manip_info_.tcp_frame );
144144 double trans_dist = (p2.translation () - p1.translation ()).norm ();
145145 int trans_steps = int (trans_dist / translation_longest_valid_segment_length) + 1 ;
146- EXPECT_TRUE (static_cast <int >(ctl.size ()) > min_steps);
146+ EXPECT_GT (static_cast <int >(ctl.size ()), min_steps);
147147 EXPECT_EQ (ctl.size (), trans_steps);
148148
149149 // Ensure rotation_longest_valid_segment_length is used
@@ -152,7 +152,7 @@ TEST_F(TesseractPlanningSimplePlannerLVSPlanProfileUnit, InterpolateStateWaypoin
152152 auto crl = crl_profile.generate (instr1, instr1_seed, instr2, instr3, env_, tesseract_common::ManipulatorInfo ());
153153 double rot_dist = Eigen::Quaterniond (p1.linear ()).angularDistance (Eigen::Quaterniond (p2.linear ()));
154154 int rot_steps = int (rot_dist / rotation_longest_valid_segment_length) + 1 ;
155- EXPECT_TRUE (static_cast <int >(crl.size ()) > min_steps);
155+ EXPECT_GT (static_cast <int >(crl.size ()), min_steps);
156156 EXPECT_EQ (crl.size (), rot_steps);
157157}
158158
@@ -207,7 +207,7 @@ TEST_F(TesseractPlanningSimplePlannerLVSPlanProfileUnit, InterpolateStateWaypoin
207207 double longest_valid_segment_length = 0.01 ;
208208 SimplePlannerLVSPlanProfile cl_profile (longest_valid_segment_length, 10 , 6.28 , min_steps);
209209 auto cl = cl_profile.generate (instr1, instr1_seed, instr2, instr3, env_, tesseract_common::ManipulatorInfo ());
210- EXPECT_TRUE (static_cast <int >(cl.size ()) > min_steps);
210+ EXPECT_GT (static_cast <int >(cl.size ()), min_steps);
211211}
212212
213213TEST_F (TesseractPlanningSimplePlannerLVSPlanProfileUnit, InterpolateStateWaypoint_JointCart_Linear) // NOLINT
@@ -262,7 +262,7 @@ TEST_F(TesseractPlanningSimplePlannerLVSPlanProfileUnit, InterpolateStateWaypoin
262262 Eigen::Isometry3d p1 = joint_group->calcFwdKin (wp1.getPosition ()).at (manip_info_.tcp_frame );
263263 double trans_dist = (wp2.getTransform ().translation () - p1.translation ()).norm ();
264264 int trans_steps = int (trans_dist / translation_longest_valid_segment_length) + 1 ;
265- EXPECT_TRUE (static_cast <int >(ctl.size ()) > min_steps);
265+ EXPECT_GT (static_cast <int >(ctl.size ()), min_steps);
266266 EXPECT_EQ (ctl.size (), trans_steps);
267267
268268 // Ensure rotation_longest_valid_segment_length is used
@@ -271,7 +271,7 @@ TEST_F(TesseractPlanningSimplePlannerLVSPlanProfileUnit, InterpolateStateWaypoin
271271 auto crl = crl_profile.generate (instr1, instr1_seed, instr2, instr3, env_, tesseract_common::ManipulatorInfo ());
272272 double rot_dist = Eigen::Quaterniond (p1.linear ()).angularDistance (Eigen::Quaterniond (wp2.getTransform ().linear ()));
273273 int rot_steps = int (rot_dist / rotation_longest_valid_segment_length) + 1 ;
274- EXPECT_TRUE (static_cast <int >(crl.size ()) > min_steps);
274+ EXPECT_GT (static_cast <int >(crl.size ()), min_steps);
275275 EXPECT_EQ (crl.size (), rot_steps);
276276}
277277
@@ -324,7 +324,7 @@ TEST_F(TesseractPlanningSimplePlannerLVSPlanProfileUnit, InterpolateStateWaypoin
324324 double longest_valid_segment_length = 0.01 ;
325325 SimplePlannerLVSPlanProfile cl_profile (longest_valid_segment_length, 10 , 6.28 , min_steps);
326326 auto cl = cl_profile.generate (instr1, instr1_seed, instr2, instr3, env_, tesseract_common::ManipulatorInfo ());
327- EXPECT_TRUE (static_cast <int >(cl.size ()) > min_steps);
327+ EXPECT_GT (static_cast <int >(cl.size ()), min_steps);
328328}
329329
330330TEST_F (TesseractPlanningSimplePlannerLVSPlanProfileUnit, InterpolateStateWaypoint_CartJoint_Linear) // NOLINT
@@ -378,7 +378,7 @@ TEST_F(TesseractPlanningSimplePlannerLVSPlanProfileUnit, InterpolateStateWaypoin
378378 Eigen::Isometry3d p2 = joint_group->calcFwdKin (wp2.getPosition ()).at (manip_info_.tcp_frame );
379379 double trans_dist = (p2.translation () - wp1.getTransform ().translation ()).norm ();
380380 int trans_steps = int (trans_dist / translation_longest_valid_segment_length) + 1 ;
381- EXPECT_TRUE (static_cast <int >(ctl.size ()) > min_steps);
381+ EXPECT_GT (static_cast <int >(ctl.size ()), min_steps);
382382 EXPECT_EQ (ctl.size (), trans_steps);
383383
384384 // Ensure rotation_longest_valid_segment_length is used
@@ -387,7 +387,7 @@ TEST_F(TesseractPlanningSimplePlannerLVSPlanProfileUnit, InterpolateStateWaypoin
387387 auto crl = crl_profile.generate (instr1, instr1_seed, instr2, instr3, env_, tesseract_common::ManipulatorInfo ());
388388 double rot_dist = Eigen::Quaterniond (wp1.getTransform ().linear ()).angularDistance (Eigen::Quaterniond (p2.linear ()));
389389 int rot_steps = int (rot_dist / rotation_longest_valid_segment_length) + 1 ;
390- EXPECT_TRUE (static_cast <int >(crl.size ()) > min_steps);
390+ EXPECT_GT (static_cast <int >(crl.size ()), min_steps);
391391 EXPECT_EQ (crl.size (), rot_steps);
392392}
393393
@@ -441,7 +441,7 @@ TEST_F(TesseractPlanningSimplePlannerLVSPlanProfileUnit, InterpolateStateWaypoin
441441 double longest_valid_segment_length = 0.01 ;
442442 SimplePlannerLVSPlanProfile cl_profile (longest_valid_segment_length, 10 , 6.28 , min_steps);
443443 auto cl = cl_profile.generate (instr1, instr1_seed, instr2, instr3, env_, tesseract_common::ManipulatorInfo ());
444- EXPECT_TRUE (static_cast <int >(cl.size ()) > min_steps);
444+ EXPECT_GT (static_cast <int >(cl.size ()), min_steps);
445445}
446446
447447TEST_F (TesseractPlanningSimplePlannerLVSPlanProfileUnit, InterpolateStateWaypoint_CartCart_Linear) // NOLINT
@@ -495,7 +495,7 @@ TEST_F(TesseractPlanningSimplePlannerLVSPlanProfileUnit, InterpolateStateWaypoin
495495 auto ctl = ctl_profile.generate (instr1, instr1_seed, instr2, instr3, env_, tesseract_common::ManipulatorInfo ());
496496 double trans_dist = (wp2.getTransform ().translation () - wp1.getTransform ().translation ()).norm ();
497497 int trans_steps = int (trans_dist / translation_longest_valid_segment_length) + 1 ;
498- EXPECT_TRUE (static_cast <int >(ctl.size ()) > min_steps);
498+ EXPECT_GT (static_cast <int >(ctl.size ()), min_steps);
499499 EXPECT_EQ (ctl.size (), trans_steps);
500500
501501 // Ensure rotation_longest_valid_segment_length is used
@@ -505,7 +505,7 @@ TEST_F(TesseractPlanningSimplePlannerLVSPlanProfileUnit, InterpolateStateWaypoin
505505 double rot_dist =
506506 Eigen::Quaterniond (wp1.getTransform ().linear ()).angularDistance (Eigen::Quaterniond (wp2.getTransform ().linear ()));
507507 int rot_steps = int (rot_dist / rotation_longest_valid_segment_length) + 1 ;
508- EXPECT_TRUE (static_cast <int >(crl.size ()) > min_steps);
508+ EXPECT_GT (static_cast <int >(crl.size ()), min_steps);
509509 EXPECT_EQ (crl.size (), rot_steps);
510510}
511511
0 commit comments