Skip to content

Commit f60a807

Browse files
committed
Change to 50ms
Signed-off-by: Maurice <[email protected]>
1 parent 723ac34 commit f60a807

File tree

1 file changed

+18
-18
lines changed

1 file changed

+18
-18
lines changed

nav2_docking/opennav_docking/test/test_controller.cpp

Lines changed: 18 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -304,23 +304,23 @@ TEST(ControllerTests, CollisionCheckerDockForward) {
304304
// Publish an empty costmap
305305
// It should not hit anything in an empty costmap
306306
collision_tester->publishCostmap();
307-
executor.spin_all(std::chrono::milliseconds(50));
307+
executor.spin_all(50ms);
308308
EXPECT_TRUE(controller->isTrajectoryCollisionFree(dock_pose, true, false));
309309

310310
// Set a dock in the costmap of 0.2x1.5m at 2m in front of the robot
311311
// It should hit the dock because the robot is 0.5m wide and the dock pose is at 1.75
312312
// But it does not hit because the collision tolerance is 0.3m
313313
collision_tester->setRectangle(0.2, 1.5, 2.0, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE);
314314
collision_tester->publishCostmap();
315-
executor.spin_all(std::chrono::milliseconds(50));
315+
executor.spin_all(50ms);
316316
EXPECT_TRUE(controller->isTrajectoryCollisionFree(dock_pose, true, false));
317317

318318
// Set an object between the robot and the dock
319319
// It should hit the object
320320
collision_tester->clearCostmap();
321321
collision_tester->setRectangle(0.2, 0.2, 1.0, -0.1, nav2_costmap_2d::LETHAL_OBSTACLE);
322322
collision_tester->publishCostmap();
323-
executor.spin_all(std::chrono::milliseconds(50));
323+
executor.spin_all(50ms);
324324
EXPECT_FALSE(controller->isTrajectoryCollisionFree(dock_pose, true, false));
325325

326326
// Set the collision tolerance to 0 to ensure all obstacles in the path are detected
@@ -331,7 +331,7 @@ TEST(ControllerTests, CollisionCheckerDockForward) {
331331
collision_tester->clearCostmap();
332332
collision_tester->setRectangle(0.2, 1.5, 2.0, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE);
333333
collision_tester->publishCostmap();
334-
executor.spin_all(std::chrono::milliseconds(50));
334+
executor.spin_all(50ms);
335335
EXPECT_FALSE(controller->isTrajectoryCollisionFree(dock_pose, true, false));
336336

337337
collision_tester->deactivate();
@@ -371,23 +371,23 @@ TEST(ControllerTests, CollisionCheckerDockBackward) {
371371
// Publish an empty costmap
372372
// It should not hit anything in an empty costmap
373373
collision_tester->publishCostmap();
374-
executor.spin_all(std::chrono::milliseconds(50));
374+
executor.spin_all(50ms);
375375
EXPECT_TRUE(controller->isTrajectoryCollisionFree(dock_pose, true, true));
376376

377377
// Set a dock in the costmap of 0.2x1.5m at 2m behind the robot
378378
// It should hit the dock because the robot is 0.5m wide and the dock pose is at -1.75
379379
// But it does not hit because the collision tolerance is 0.3m
380380
collision_tester->setRectangle(0.2, 1.5, -2.1, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE);
381381
collision_tester->publishCostmap();
382-
executor.spin_all(std::chrono::milliseconds(50));
382+
executor.spin_all(50ms);
383383
EXPECT_TRUE(controller->isTrajectoryCollisionFree(dock_pose, true, true));
384384

385385
// Set an object between the robot and the dock
386386
// It should hit the object
387387
collision_tester->clearCostmap();
388388
collision_tester->setRectangle(0.2, 0.2, -1.0, 0.0, nav2_costmap_2d::LETHAL_OBSTACLE);
389389
collision_tester->publishCostmap();
390-
executor.spin_all(std::chrono::milliseconds(50));
390+
executor.spin_all(50ms);
391391
EXPECT_FALSE(controller->isTrajectoryCollisionFree(dock_pose, true, true));
392392

393393
// Set the collision tolerance to 0 to ensure all obstacles in the path are detected
@@ -398,7 +398,7 @@ TEST(ControllerTests, CollisionCheckerDockBackward) {
398398
collision_tester->clearCostmap();
399399
collision_tester->setRectangle(0.2, 1.5, -2.1, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE);
400400
collision_tester->publishCostmap();
401-
executor.spin_all(std::chrono::milliseconds(50));
401+
executor.spin_all(50ms);
402402
EXPECT_FALSE(controller->isTrajectoryCollisionFree(dock_pose, true, true));
403403

404404
collision_tester->deactivate();
@@ -438,31 +438,31 @@ TEST(ControllerTests, CollisionCheckerUndockBackward) {
438438
// Publish an empty costmap
439439
// It should not hit anything in an empty costmap
440440
collision_tester->publishCostmap();
441-
executor.spin_all(std::chrono::milliseconds(50));
441+
executor.spin_all(50ms);
442442
EXPECT_TRUE(controller->isTrajectoryCollisionFree(staging_pose, false, true));
443443

444444
// Set a dock in the costmap of 0.2x1.5m in front of the robot. The robot is docked
445445
// It should hit the dock because the robot is 0.5m wide and the robot pose is at 1.75
446446
// But it does not hit because the collision tolerance is 0.3m
447447
collision_tester->setRectangle(0.2, 1.5, 0.25, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE);
448448
collision_tester->publishCostmap();
449-
executor.spin_all(std::chrono::milliseconds(50));
449+
executor.spin_all(50ms);
450450
EXPECT_TRUE(controller->isTrajectoryCollisionFree(staging_pose, false, true));
451451

452452
// Set an object beyond the staging pose
453453
// It should hit the object
454454
collision_tester->clearCostmap();
455455
collision_tester->setRectangle(0.2, 0.2, -1.75 - 0.5, -0.1, nav2_costmap_2d::LETHAL_OBSTACLE);
456456
collision_tester->publishCostmap();
457-
executor.spin_all(std::chrono::milliseconds(50));
457+
executor.spin_all(50ms);
458458
EXPECT_FALSE(controller->isTrajectoryCollisionFree(staging_pose, false, true));
459459

460460
// Set an object between the robot and the staging pose
461461
// It should hit the object
462462
collision_tester->clearCostmap();
463463
collision_tester->setRectangle(0.2, 0.2, -1.0, -0.1, nav2_costmap_2d::LETHAL_OBSTACLE);
464464
collision_tester->publishCostmap();
465-
executor.spin_all(std::chrono::milliseconds(50));
465+
executor.spin_all(50ms);
466466
EXPECT_FALSE(controller->isTrajectoryCollisionFree(staging_pose, false, true));
467467

468468
// Set the collision tolerance to 0 to ensure all obstacles in the path are detected
@@ -473,7 +473,7 @@ TEST(ControllerTests, CollisionCheckerUndockBackward) {
473473
collision_tester->clearCostmap();
474474
collision_tester->setRectangle(0.2, 1.5, 0.25, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE);
475475
collision_tester->publishCostmap();
476-
executor.spin_all(std::chrono::milliseconds(50));
476+
executor.spin_all(50ms);
477477
EXPECT_FALSE(controller->isTrajectoryCollisionFree(staging_pose, false, true));
478478

479479
collision_tester->deactivate();
@@ -513,30 +513,30 @@ TEST(ControllerTests, CollisionCheckerUndockForward) {
513513
// Publish an empty costmap
514514
// It should not hit anything in an empty costmap
515515
collision_tester->publishCostmap();
516-
executor.spin_all(std::chrono::milliseconds(50));
516+
executor.spin_all(50ms);
517517
EXPECT_TRUE(controller->isTrajectoryCollisionFree(staging_pose, false, false));
518518

519519
// Set a dock in the costmap of 0.2x1.5m at 0.5m behind the robot. The robot is docked
520520
// It should not hit anything because the robot is docked and the trajectory is backward
521521
collision_tester->setRectangle(0.2, 1.5, -0.35, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE);
522522
collision_tester->publishCostmap();
523-
executor.spin_all(std::chrono::milliseconds(50));
523+
executor.spin_all(50ms);
524524
EXPECT_TRUE(controller->isTrajectoryCollisionFree(staging_pose, false, false));
525525

526526
// Set an object beyond the staging pose
527527
// It should hit the object
528528
collision_tester->clearCostmap();
529529
collision_tester->setRectangle(0.2, 0.3, 1.75 + 0.5, 0.0, nav2_costmap_2d::LETHAL_OBSTACLE);
530530
collision_tester->publishCostmap();
531-
executor.spin_all(std::chrono::milliseconds(50));
531+
executor.spin_all(50ms);
532532
EXPECT_FALSE(controller->isTrajectoryCollisionFree(staging_pose, false, false));
533533

534534
// Set an object between the robot and the staging pose
535535
// It should hit the object
536536
collision_tester->clearCostmap();
537537
collision_tester->setRectangle(0.2, 0.2, 1.0, 0.0, nav2_costmap_2d::LETHAL_OBSTACLE);
538538
collision_tester->publishCostmap();
539-
executor.spin_all(std::chrono::milliseconds(50));
539+
executor.spin_all(50ms);
540540
EXPECT_FALSE(controller->isTrajectoryCollisionFree(staging_pose, false, false));
541541

542542
// Set the collision tolerance to 0 to ensure all obstacles in the path are detected
@@ -547,7 +547,7 @@ TEST(ControllerTests, CollisionCheckerUndockForward) {
547547
collision_tester->clearCostmap();
548548
collision_tester->setRectangle(0.2, 1.5, -0.35, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE);
549549
collision_tester->publishCostmap();
550-
executor.spin_all(std::chrono::milliseconds(50));
550+
executor.spin_all(50ms);
551551
EXPECT_FALSE(controller->isTrajectoryCollisionFree(staging_pose, false, false));
552552

553553
collision_tester->deactivate();

0 commit comments

Comments
 (0)