@@ -203,25 +203,28 @@ class TestDiffDriveController : public ::testing::Test
203
203
return controller_->init (controller_name, urdf_, 0 , ns, node_options);
204
204
}
205
205
206
- void expect_configure_succeeded (
207
- std::unique_ptr<TestableDiffDriveController> & controller, bool succeeded)
206
+ bool is_configure_succeeded (const std::unique_ptr<TestableDiffDriveController> & controller)
208
207
{
209
208
auto state = controller->configure ();
209
+ return State::PRIMARY_STATE_INACTIVE == state.id ();
210
+ }
210
211
211
- if (succeeded)
212
- ASSERT_EQ (State::PRIMARY_STATE_INACTIVE, state.id ());
213
- else
214
- ASSERT_EQ (State::PRIMARY_STATE_UNCONFIGURED, state.id ());
212
+ bool is_configure_failed (const std::unique_ptr<TestableDiffDriveController> & controller)
213
+ {
214
+ auto state = controller->configure ();
215
+ return State::PRIMARY_STATE_UNCONFIGURED == state.id ();
216
+ }
217
+
218
+ bool is_activate_succeeded (const std::unique_ptr<TestableDiffDriveController> & controller)
219
+ {
220
+ auto state = controller->get_node ()->activate ();
221
+ return State::PRIMARY_STATE_ACTIVE == state.id ();
215
222
}
216
223
217
- void expect_activate_succeeded (
218
- std::unique_ptr<TestableDiffDriveController> & controller, bool succeeded)
224
+ bool is_activate_failed (const std::unique_ptr<TestableDiffDriveController> & controller)
219
225
{
220
226
auto state = controller->get_node ()->activate ();
221
- if (succeeded)
222
- ASSERT_EQ (State::PRIMARY_STATE_ACTIVE, state.id ());
223
- else
224
- ASSERT_EQ (State::PRIMARY_STATE_UNCONFIGURED, state.id ());
227
+ return State::PRIMARY_STATE_UNCONFIGURED == state.id ();
225
228
}
226
229
227
230
std::string controller_name;
@@ -269,7 +272,7 @@ TEST_F(TestDiffDriveController, configure_fails_with_mismatching_wheel_side_size
269
272
InitController (left_wheel_names, {right_wheel_names[0 ], " extra_wheel" }),
270
273
controller_interface::return_type::OK);
271
274
272
- expect_configure_succeeded ( controller_, false );
275
+ ASSERT_TRUE ( is_configure_failed ( controller_) );
273
276
}
274
277
275
278
TEST_F (
@@ -278,7 +281,7 @@ TEST_F(
278
281
{
279
282
ASSERT_EQ (InitController (), controller_interface::return_type::OK);
280
283
281
- expect_configure_succeeded ( controller_, true );
284
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
282
285
283
286
auto state_if_conf = controller_->state_interface_configuration ();
284
287
ASSERT_THAT (state_if_conf.names , SizeIs (left_wheel_names.size () + right_wheel_names.size ()));
@@ -323,7 +326,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_false_no_names
323
326
rclcpp::Parameter (" base_frame_id" , rclcpp::ParameterValue (base_link_id))}),
324
327
controller_interface::return_type::OK);
325
328
326
- expect_configure_succeeded ( controller_, true );
329
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
327
330
328
331
auto odometry_message = controller_->get_rt_odom_publisher ()->msg_ ;
329
332
std::string test_odom_frame_id = odometry_message.header .frame_id ;
@@ -348,7 +351,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_true_no_namesp
348
351
rclcpp::Parameter (" base_frame_id" , rclcpp::ParameterValue (base_link_id))}),
349
352
controller_interface::return_type::OK);
350
353
351
- expect_configure_succeeded ( controller_, true );
354
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
352
355
353
356
auto odometry_message = controller_->get_rt_odom_publisher ()->msg_ ;
354
357
std::string test_odom_frame_id = odometry_message.header .frame_id ;
@@ -375,7 +378,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_blank_prefix_true_no_names
375
378
rclcpp::Parameter (" base_frame_id" , rclcpp::ParameterValue (base_link_id))}),
376
379
controller_interface::return_type::OK);
377
380
378
- expect_configure_succeeded ( controller_, true );
381
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
379
382
380
383
auto odometry_message = controller_->get_rt_odom_publisher ()->msg_ ;
381
384
std::string test_odom_frame_id = odometry_message.header .frame_id ;
@@ -404,7 +407,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_false_set_name
404
407
test_namespace),
405
408
controller_interface::return_type::OK);
406
409
407
- expect_configure_succeeded ( controller_, true );
410
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
408
411
409
412
auto odometry_message = controller_->get_rt_odom_publisher ()->msg_ ;
410
413
std::string test_odom_frame_id = odometry_message.header .frame_id ;
@@ -432,7 +435,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_true_set_names
432
435
test_namespace),
433
436
controller_interface::return_type::OK);
434
437
435
- expect_configure_succeeded ( controller_, true );
438
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
436
439
437
440
auto odometry_message = controller_->get_rt_odom_publisher ()->msg_ ;
438
441
std::string test_odom_frame_id = odometry_message.header .frame_id ;
@@ -461,7 +464,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_blank_prefix_true_set_name
461
464
test_namespace),
462
465
controller_interface::return_type::OK);
463
466
464
- expect_configure_succeeded ( controller_, true );
467
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
465
468
466
469
auto odometry_message = controller_->get_rt_odom_publisher ()->msg_ ;
467
470
std::string test_odom_frame_id = odometry_message.header .frame_id ;
@@ -477,21 +480,21 @@ TEST_F(TestDiffDriveController, activate_fails_without_resources_assigned)
477
480
{
478
481
ASSERT_EQ (InitController (), controller_interface::return_type::OK);
479
482
480
- expect_configure_succeeded ( controller_, true );
483
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
481
484
482
- expect_activate_succeeded ( controller_, false );
485
+ ASSERT_TRUE ( is_activate_failed ( controller_) );
483
486
}
484
487
485
488
TEST_F (TestDiffDriveController, activate_succeeds_with_pos_resources_assigned)
486
489
{
487
490
ASSERT_EQ (InitController (), controller_interface::return_type::OK);
488
491
489
492
// We implicitly test that by default position feedback is required
490
- expect_configure_succeeded ( controller_, true );
493
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
491
494
492
495
assignResourcesPosFeedback ();
493
496
494
- expect_activate_succeeded ( controller_, true );
497
+ ASSERT_TRUE ( is_activate_succeeded ( controller_) );
495
498
}
496
499
497
500
TEST_F (TestDiffDriveController, activate_succeeds_with_vel_resources_assigned)
@@ -502,11 +505,11 @@ TEST_F(TestDiffDriveController, activate_succeeds_with_vel_resources_assigned)
502
505
{rclcpp::Parameter (" position_feedback" , rclcpp::ParameterValue (false ))}),
503
506
controller_interface::return_type::OK);
504
507
505
- expect_configure_succeeded ( controller_, true );
508
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
506
509
507
510
assignResourcesVelFeedback ();
508
511
509
- expect_activate_succeeded ( controller_, true );
512
+ ASSERT_TRUE ( is_activate_succeeded ( controller_) );
510
513
}
511
514
512
515
TEST_F (TestDiffDriveController, activate_succeeds_with_open_loop_assigned)
@@ -552,11 +555,11 @@ TEST_F(TestDiffDriveController, test_speed_limiter)
552
555
rclcpp::executors::SingleThreadedExecutor executor;
553
556
executor.add_node (controller_->get_node ()->get_node_base_interface ());
554
557
555
- expect_configure_succeeded ( controller_, true );
558
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
556
559
557
560
assignResourcesPosFeedback ();
558
561
559
- expect_activate_succeeded ( controller_, true );
562
+ ASSERT_TRUE ( is_activate_succeeded ( controller_) );
560
563
561
564
waitForSetup ();
562
565
@@ -736,11 +739,11 @@ TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_1)
736
739
{rclcpp::Parameter (" position_feedback" , rclcpp::ParameterValue (false ))}),
737
740
controller_interface::return_type::OK);
738
741
739
- expect_configure_succeeded ( controller_, true );
742
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
740
743
741
744
assignResourcesPosFeedback ();
742
745
743
- expect_activate_succeeded ( controller_, false );
746
+ ASSERT_TRUE ( is_activate_failed ( controller_) );
744
747
}
745
748
746
749
TEST_F (TestDiffDriveController, activate_fails_with_wrong_resources_assigned_2)
@@ -751,11 +754,11 @@ TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_2)
751
754
{rclcpp::Parameter (" position_feedback" , rclcpp::ParameterValue (true ))}),
752
755
controller_interface::return_type::OK);
753
756
754
- expect_configure_succeeded ( controller_, true );
757
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
755
758
756
759
assignResourcesVelFeedback ();
757
760
758
- expect_activate_succeeded ( controller_, false );
761
+ ASSERT_TRUE ( is_activate_failed ( controller_) );
759
762
}
760
763
761
764
TEST_F (TestDiffDriveController, activate_silently_ignores_with_unnecessary_resources_assigned_1)
@@ -797,11 +800,11 @@ TEST_F(TestDiffDriveController, cleanup)
797
800
rclcpp::executors::SingleThreadedExecutor executor;
798
801
executor.add_node (controller_->get_node ()->get_node_base_interface ());
799
802
800
- expect_configure_succeeded ( controller_, true );
803
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
801
804
802
805
assignResourcesPosFeedback ();
803
806
804
- expect_activate_succeeded ( controller_, true );
807
+ ASSERT_TRUE ( is_activate_succeeded ( controller_) );
805
808
806
809
waitForSetup ();
807
810
@@ -849,14 +852,14 @@ TEST_F(TestDiffDriveController, correct_initialization_using_parameters)
849
852
rclcpp::executors::SingleThreadedExecutor executor;
850
853
executor.add_node (controller_->get_node ()->get_node_base_interface ());
851
854
852
- expect_configure_succeeded ( controller_, true );
855
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
853
856
854
857
assignResourcesPosFeedback ();
855
858
856
859
EXPECT_EQ (0.01 , left_wheel_vel_cmd_.get_optional ().value ());
857
860
EXPECT_EQ (0.02 , right_wheel_vel_cmd_.get_optional ().value ());
858
861
859
- expect_activate_succeeded ( controller_, true );
862
+ ASSERT_TRUE ( is_activate_succeeded ( controller_) );
860
863
861
864
// send msg
862
865
const double linear = 1.0 ;
@@ -890,7 +893,7 @@ TEST_F(TestDiffDriveController, correct_initialization_using_parameters)
890
893
EXPECT_EQ (0.0 , left_wheel_vel_cmd_.get_optional ().value ());
891
894
EXPECT_EQ (0.0 , right_wheel_vel_cmd_.get_optional ().value ());
892
895
893
- expect_configure_succeeded ( controller_, true );
896
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
894
897
895
898
executor.cancel ();
896
899
}
@@ -916,11 +919,11 @@ TEST_F(TestDiffDriveController, chainable_controller_unchained_mode)
916
919
ASSERT_TRUE (controller_->set_chained_mode (false ));
917
920
ASSERT_FALSE (controller_->is_in_chained_mode ());
918
921
919
- expect_configure_succeeded ( controller_, true );
922
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
920
923
921
924
assignResourcesPosFeedback ();
922
925
923
- expect_activate_succeeded ( controller_, true );
926
+ ASSERT_TRUE ( is_activate_succeeded ( controller_) );
924
927
925
928
waitForSetup ();
926
929
@@ -986,7 +989,7 @@ TEST_F(TestDiffDriveController, chainable_controller_unchained_mode)
986
989
EXPECT_EQ (0.0 , right_wheel_vel_cmd_.get_optional ().value ())
987
990
<< " Wheels should be halted on cleanup()" ;
988
991
989
- expect_configure_succeeded ( controller_, true );
992
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
990
993
991
994
executor.cancel ();
992
995
}
@@ -1011,11 +1014,11 @@ TEST_F(TestDiffDriveController, chainable_controller_chained_mode)
1011
1014
ASSERT_TRUE (controller_->set_chained_mode (true ));
1012
1015
ASSERT_TRUE (controller_->is_in_chained_mode ());
1013
1016
1014
- expect_configure_succeeded ( controller_, true );
1017
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
1015
1018
1016
1019
assignResourcesPosFeedback ();
1017
1020
1018
- expect_activate_succeeded ( controller_, true );
1021
+ ASSERT_TRUE ( is_activate_succeeded ( controller_) );
1019
1022
1020
1023
waitForSetup ();
1021
1024
@@ -1064,7 +1067,7 @@ TEST_F(TestDiffDriveController, chainable_controller_chained_mode)
1064
1067
EXPECT_EQ (0.0 , right_wheel_vel_cmd_.get_optional ().value ())
1065
1068
<< " Wheels should be halted on cleanup()" ;
1066
1069
1067
- expect_configure_succeeded ( controller_, true );
1070
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
1068
1071
1069
1072
executor.cancel ();
1070
1073
}
@@ -1074,7 +1077,7 @@ TEST_F(TestDiffDriveController, reference_interfaces_are_properly_exported)
1074
1077
ASSERT_EQ (
1075
1078
InitController (left_wheel_names, right_wheel_names), controller_interface::return_type::OK);
1076
1079
1077
- expect_configure_succeeded ( controller_, true );
1080
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
1078
1081
1079
1082
auto reference_interfaces = controller_->export_reference_interfaces ();
1080
1083
ASSERT_EQ (reference_interfaces.size (), 2 )
@@ -1114,11 +1117,11 @@ TEST_F(TestDiffDriveController, deactivate_then_activate)
1114
1117
1115
1118
ASSERT_TRUE (controller_->set_chained_mode (false ));
1116
1119
1117
- expect_configure_succeeded ( controller_, true );
1120
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
1118
1121
1119
1122
assignResourcesPosFeedback ();
1120
1123
1121
- expect_activate_succeeded ( controller_, true );
1124
+ ASSERT_TRUE ( is_activate_succeeded ( controller_) );
1122
1125
1123
1126
waitForSetup ();
1124
1127
@@ -1161,7 +1164,7 @@ TEST_F(TestDiffDriveController, deactivate_then_activate)
1161
1164
<< " Wheels should be halted on deactivate()" ;
1162
1165
1163
1166
// Activate again
1164
- expect_activate_succeeded ( controller_, true );
1167
+ ASSERT_TRUE ( is_activate_succeeded ( controller_) );
1165
1168
1166
1169
waitForSetup ();
1167
1170
@@ -1210,11 +1213,11 @@ TEST_F(TestDiffDriveController, command_with_zero_timestamp_is_accepted_with_war
1210
1213
1211
1214
ASSERT_TRUE (controller_->set_chained_mode (false ));
1212
1215
1213
- expect_configure_succeeded ( controller_, true );
1216
+ ASSERT_TRUE ( is_configure_succeeded ( controller_) );
1214
1217
1215
1218
assignResourcesPosFeedback ();
1216
1219
1217
- expect_activate_succeeded ( controller_, true );
1220
+ ASSERT_TRUE ( is_activate_succeeded ( controller_) );
1218
1221
1219
1222
waitForSetup ();
1220
1223
0 commit comments