@@ -304,23 +304,23 @@ TEST(ControllerTests, CollisionCheckerDockForward) {
304
304
// Publish an empty costmap
305
305
// It should not hit anything in an empty costmap
306
306
collision_tester->publishCostmap ();
307
- executor.spin_some ( );
307
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
308
308
EXPECT_TRUE (controller->isTrajectoryCollisionFree (dock_pose, true , false ));
309
309
310
310
// Set a dock in the costmap of 0.2x1.5m at 2m in front of the robot
311
311
// It should hit the dock because the robot is 0.5m wide and the dock pose is at 1.75
312
312
// But it does not hit because the collision tolerance is 0.3m
313
313
collision_tester->setRectangle (0.2 , 1.5 , 2.0 , -0.75 , nav2_costmap_2d::LETHAL_OBSTACLE);
314
314
collision_tester->publishCostmap ();
315
- executor.spin_some ( );
315
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
316
316
EXPECT_TRUE (controller->isTrajectoryCollisionFree (dock_pose, true , false ));
317
317
318
318
// Set an object between the robot and the dock
319
319
// It should hit the object
320
320
collision_tester->clearCostmap ();
321
321
collision_tester->setRectangle (0.2 , 0.2 , 1.0 , -0.1 , nav2_costmap_2d::LETHAL_OBSTACLE);
322
322
collision_tester->publishCostmap ();
323
- executor.spin_some ( );
323
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
324
324
EXPECT_FALSE (controller->isTrajectoryCollisionFree (dock_pose, true , false ));
325
325
326
326
// Set the collision tolerance to 0 to ensure all obstacles in the path are detected
@@ -331,7 +331,7 @@ TEST(ControllerTests, CollisionCheckerDockForward) {
331
331
collision_tester->clearCostmap ();
332
332
collision_tester->setRectangle (0.2 , 1.5 , 2.0 , -0.75 , nav2_costmap_2d::LETHAL_OBSTACLE);
333
333
collision_tester->publishCostmap ();
334
- executor.spin_some ( );
334
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
335
335
EXPECT_FALSE (controller->isTrajectoryCollisionFree (dock_pose, true , false ));
336
336
337
337
collision_tester->deactivate ();
@@ -371,23 +371,23 @@ TEST(ControllerTests, CollisionCheckerDockBackward) {
371
371
// Publish an empty costmap
372
372
// It should not hit anything in an empty costmap
373
373
collision_tester->publishCostmap ();
374
- executor.spin_some ( );
374
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
375
375
EXPECT_TRUE (controller->isTrajectoryCollisionFree (dock_pose, true , true ));
376
376
377
377
// Set a dock in the costmap of 0.2x1.5m at 2m behind the robot
378
378
// It should hit the dock because the robot is 0.5m wide and the dock pose is at -1.75
379
379
// But it does not hit because the collision tolerance is 0.3m
380
380
collision_tester->setRectangle (0.2 , 1.5 , -2.1 , -0.75 , nav2_costmap_2d::LETHAL_OBSTACLE);
381
381
collision_tester->publishCostmap ();
382
- executor.spin_some ( );
382
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
383
383
EXPECT_TRUE (controller->isTrajectoryCollisionFree (dock_pose, true , true ));
384
384
385
385
// Set an object between the robot and the dock
386
386
// It should hit the object
387
387
collision_tester->clearCostmap ();
388
388
collision_tester->setRectangle (0.2 , 0.2 , -1.0 , 0.0 , nav2_costmap_2d::LETHAL_OBSTACLE);
389
389
collision_tester->publishCostmap ();
390
- executor.spin_some ( );
390
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
391
391
EXPECT_FALSE (controller->isTrajectoryCollisionFree (dock_pose, true , true ));
392
392
393
393
// Set the collision tolerance to 0 to ensure all obstacles in the path are detected
@@ -398,7 +398,7 @@ TEST(ControllerTests, CollisionCheckerDockBackward) {
398
398
collision_tester->clearCostmap ();
399
399
collision_tester->setRectangle (0.2 , 1.5 , -2.1 , -0.75 , nav2_costmap_2d::LETHAL_OBSTACLE);
400
400
collision_tester->publishCostmap ();
401
- executor.spin_some ( );
401
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
402
402
EXPECT_FALSE (controller->isTrajectoryCollisionFree (dock_pose, true , true ));
403
403
404
404
collision_tester->deactivate ();
@@ -438,31 +438,31 @@ TEST(ControllerTests, CollisionCheckerUndockBackward) {
438
438
// Publish an empty costmap
439
439
// It should not hit anything in an empty costmap
440
440
collision_tester->publishCostmap ();
441
- executor.spin_some ( );
441
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
442
442
EXPECT_TRUE (controller->isTrajectoryCollisionFree (staging_pose, false , true ));
443
443
444
444
// Set a dock in the costmap of 0.2x1.5m in front of the robot. The robot is docked
445
445
// It should hit the dock because the robot is 0.5m wide and the robot pose is at 1.75
446
446
// But it does not hit because the collision tolerance is 0.3m
447
447
collision_tester->setRectangle (0.2 , 1.5 , 0.25 , -0.75 , nav2_costmap_2d::LETHAL_OBSTACLE);
448
448
collision_tester->publishCostmap ();
449
- executor.spin_some ( );
449
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
450
450
EXPECT_TRUE (controller->isTrajectoryCollisionFree (staging_pose, false , true ));
451
451
452
452
// Set an object beyond the staging pose
453
453
// It should hit the object
454
454
collision_tester->clearCostmap ();
455
455
collision_tester->setRectangle (0.2 , 0.2 , -1.75 - 0.5 , -0.1 , nav2_costmap_2d::LETHAL_OBSTACLE);
456
456
collision_tester->publishCostmap ();
457
- executor.spin_some ( );
457
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
458
458
EXPECT_FALSE (controller->isTrajectoryCollisionFree (staging_pose, false , true ));
459
459
460
460
// Set an object between the robot and the staging pose
461
461
// It should hit the object
462
462
collision_tester->clearCostmap ();
463
463
collision_tester->setRectangle (0.2 , 0.2 , -1.0 , -0.1 , nav2_costmap_2d::LETHAL_OBSTACLE);
464
464
collision_tester->publishCostmap ();
465
- executor.spin_some ( );
465
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
466
466
EXPECT_FALSE (controller->isTrajectoryCollisionFree (staging_pose, false , true ));
467
467
468
468
// Set the collision tolerance to 0 to ensure all obstacles in the path are detected
@@ -473,7 +473,7 @@ TEST(ControllerTests, CollisionCheckerUndockBackward) {
473
473
collision_tester->clearCostmap ();
474
474
collision_tester->setRectangle (0.2 , 1.5 , 0.25 , -0.75 , nav2_costmap_2d::LETHAL_OBSTACLE);
475
475
collision_tester->publishCostmap ();
476
- executor.spin_some ( );
476
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
477
477
EXPECT_FALSE (controller->isTrajectoryCollisionFree (staging_pose, false , true ));
478
478
479
479
collision_tester->deactivate ();
@@ -513,30 +513,30 @@ TEST(ControllerTests, CollisionCheckerUndockForward) {
513
513
// Publish an empty costmap
514
514
// It should not hit anything in an empty costmap
515
515
collision_tester->publishCostmap ();
516
- executor.spin_some ( );
516
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
517
517
EXPECT_TRUE (controller->isTrajectoryCollisionFree (staging_pose, false , false ));
518
518
519
519
// Set a dock in the costmap of 0.2x1.5m at 0.5m behind the robot. The robot is docked
520
520
// It should not hit anything because the robot is docked and the trajectory is backward
521
521
collision_tester->setRectangle (0.2 , 1.5 , -0.35 , -0.75 , nav2_costmap_2d::LETHAL_OBSTACLE);
522
522
collision_tester->publishCostmap ();
523
- executor.spin_some ( );
523
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
524
524
EXPECT_TRUE (controller->isTrajectoryCollisionFree (staging_pose, false , false ));
525
525
526
526
// Set an object beyond the staging pose
527
527
// It should hit the object
528
528
collision_tester->clearCostmap ();
529
529
collision_tester->setRectangle (0.2 , 0.3 , 1.75 + 0.5 , 0.0 , nav2_costmap_2d::LETHAL_OBSTACLE);
530
530
collision_tester->publishCostmap ();
531
- executor.spin_some ( );
531
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
532
532
EXPECT_FALSE (controller->isTrajectoryCollisionFree (staging_pose, false , false ));
533
533
534
534
// Set an object between the robot and the staging pose
535
535
// It should hit the object
536
536
collision_tester->clearCostmap ();
537
537
collision_tester->setRectangle (0.2 , 0.2 , 1.0 , 0.0 , nav2_costmap_2d::LETHAL_OBSTACLE);
538
538
collision_tester->publishCostmap ();
539
- executor.spin_some ( );
539
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
540
540
EXPECT_FALSE (controller->isTrajectoryCollisionFree (staging_pose, false , false ));
541
541
542
542
// Set the collision tolerance to 0 to ensure all obstacles in the path are detected
@@ -547,7 +547,7 @@ TEST(ControllerTests, CollisionCheckerUndockForward) {
547
547
collision_tester->clearCostmap ();
548
548
collision_tester->setRectangle (0.2 , 1.5 , -0.35 , -0.75 , nav2_costmap_2d::LETHAL_OBSTACLE);
549
549
collision_tester->publishCostmap ();
550
- executor.spin_some ( );
550
+ executor.spin_all ( std::chrono::milliseconds ( 50 ) );
551
551
EXPECT_FALSE (controller->isTrajectoryCollisionFree (staging_pose, false , false ));
552
552
553
553
collision_tester->deactivate ();
0 commit comments