@@ -854,9 +854,11 @@ TEST_F(TestControllerManagerSrvs, list_sorted_chained_controllers)
854
854
};
855
855
856
856
// Activate the whole chain by activating the top level controller
857
- ASSERT_EQ (controller_interface::return_type::OK, cm_->switch_controller (
858
- {" test_controller_name" }, {}, controller_manager_msgs::srv::SwitchController::Request::AUTO,
859
- true , rclcpp::Duration (0 , 0 )));
857
+ ASSERT_EQ (
858
+ controller_interface::return_type::OK,
859
+ cm_->switch_controller (
860
+ {" test_controller_name" }, {}, controller_manager_msgs::srv::SwitchController::Request::AUTO,
861
+ true , rclcpp::Duration (0 , 0 )));
860
862
check_lifecycle_state (
861
863
{lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
862
864
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
@@ -866,9 +868,11 @@ TEST_F(TestControllerManagerSrvs, list_sorted_chained_controllers)
866
868
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE});
867
869
868
870
// redoing the switch should be a no-op and not change the states and it should be successful
869
- ASSERT_EQ (controller_interface::return_type::OK, cm_->switch_controller (
870
- {" test_controller_name" }, {}, controller_manager_msgs::srv::SwitchController::Request::AUTO,
871
- true , rclcpp::Duration (0 , 0 )));
871
+ ASSERT_EQ (
872
+ controller_interface::return_type::OK,
873
+ cm_->switch_controller (
874
+ {" test_controller_name" }, {}, controller_manager_msgs::srv::SwitchController::Request::AUTO,
875
+ true , rclcpp::Duration (0 , 0 )));
872
876
check_lifecycle_state (
873
877
{lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
874
878
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
@@ -878,9 +882,11 @@ TEST_F(TestControllerManagerSrvs, list_sorted_chained_controllers)
878
882
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE});
879
883
880
884
// Now, deactivate the last controller in the chain and see that all controllers are deactivated
881
- ASSERT_EQ (controller_interface::return_type::OK, cm_->switch_controller (
882
- {}, {TEST_CHAINED_CONTROLLER_1}, controller_manager_msgs::srv::SwitchController::Request::AUTO,
883
- true , rclcpp::Duration (0 , 0 )));
885
+ ASSERT_EQ (
886
+ controller_interface::return_type::OK,
887
+ cm_->switch_controller (
888
+ {}, {TEST_CHAINED_CONTROLLER_1},
889
+ controller_manager_msgs::srv::SwitchController::Request::AUTO, true , rclcpp::Duration (0 , 0 )));
884
890
check_lifecycle_state (
885
891
{lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
886
892
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
@@ -891,9 +897,11 @@ TEST_F(TestControllerManagerSrvs, list_sorted_chained_controllers)
891
897
892
898
// Now activate the middle controller in the chain and see that all controllers below it are
893
899
// activated
894
- ASSERT_EQ (controller_interface::return_type::OK, cm_->switch_controller (
895
- {TEST_CHAINED_CONTROLLER_4}, {}, controller_manager_msgs::srv::SwitchController::Request::AUTO,
896
- true , rclcpp::Duration (0 , 0 )));
900
+ ASSERT_EQ (
901
+ controller_interface::return_type::OK,
902
+ cm_->switch_controller (
903
+ {TEST_CHAINED_CONTROLLER_4}, {},
904
+ controller_manager_msgs::srv::SwitchController::Request::AUTO, true , rclcpp::Duration (0 , 0 )));
897
905
check_lifecycle_state (
898
906
{lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
899
907
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
@@ -903,9 +911,11 @@ TEST_F(TestControllerManagerSrvs, list_sorted_chained_controllers)
903
911
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE});
904
912
905
913
// Now, deactivate 3, and see that 3 and 4 are deactivated
906
- ASSERT_EQ (controller_interface::return_type::OK, cm_->switch_controller (
907
- {}, {TEST_CHAINED_CONTROLLER_3}, controller_manager_msgs::srv::SwitchController::Request::AUTO,
908
- true , rclcpp::Duration (0 , 0 )));
914
+ ASSERT_EQ (
915
+ controller_interface::return_type::OK,
916
+ cm_->switch_controller (
917
+ {}, {TEST_CHAINED_CONTROLLER_3},
918
+ controller_manager_msgs::srv::SwitchController::Request::AUTO, true , rclcpp::Duration (0 , 0 )));
909
919
check_lifecycle_state (
910
920
{lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
911
921
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
@@ -915,9 +925,11 @@ TEST_F(TestControllerManagerSrvs, list_sorted_chained_controllers)
915
925
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE});
916
926
917
927
// Redoing it should be a no-op and not change the states and it should be successful
918
- ASSERT_EQ (controller_interface::return_type::OK, cm_->switch_controller (
919
- {}, {TEST_CHAINED_CONTROLLER_3}, controller_manager_msgs::srv::SwitchController::Request::AUTO,
920
- true , rclcpp::Duration (0 , 0 )));
928
+ ASSERT_EQ (
929
+ controller_interface::return_type::OK,
930
+ cm_->switch_controller (
931
+ {}, {TEST_CHAINED_CONTROLLER_3},
932
+ controller_manager_msgs::srv::SwitchController::Request::AUTO, true , rclcpp::Duration (0 , 0 )));
921
933
check_lifecycle_state (
922
934
{lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
923
935
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
@@ -926,9 +938,11 @@ TEST_F(TestControllerManagerSrvs, list_sorted_chained_controllers)
926
938
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
927
939
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE});
928
940
929
- ASSERT_EQ (controller_interface::return_type::OK, cm_->switch_controller (
930
- {TEST_CHAINED_CONTROLLER_4}, {}, controller_manager_msgs::srv::SwitchController::Request::AUTO,
931
- true , rclcpp::Duration (0 , 0 )));
941
+ ASSERT_EQ (
942
+ controller_interface::return_type::OK,
943
+ cm_->switch_controller (
944
+ {TEST_CHAINED_CONTROLLER_4}, {},
945
+ controller_manager_msgs::srv::SwitchController::Request::AUTO, true , rclcpp::Duration (0 , 0 )));
932
946
check_lifecycle_state (
933
947
{lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
934
948
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
@@ -937,9 +951,11 @@ TEST_F(TestControllerManagerSrvs, list_sorted_chained_controllers)
937
951
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
938
952
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE});
939
953
940
- ASSERT_EQ (controller_interface::return_type::OK, cm_->switch_controller (
941
- {" test_controller_name" }, {}, controller_manager_msgs::srv::SwitchController::Request::AUTO,
942
- true , rclcpp::Duration (0 , 0 )));
954
+ ASSERT_EQ (
955
+ controller_interface::return_type::OK,
956
+ cm_->switch_controller (
957
+ {" test_controller_name" }, {}, controller_manager_msgs::srv::SwitchController::Request::AUTO,
958
+ true , rclcpp::Duration (0 , 0 )));
943
959
check_lifecycle_state (
944
960
{lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
945
961
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
@@ -1130,62 +1146,201 @@ TEST_F(TestControllerManagerSrvs, list_sorted_complex_chained_controllers)
1130
1146
ASSERT_GT (ctrl_4_pos, ctrl_5_pos);
1131
1147
ASSERT_GT (ctrl_3_pos, ctrl_4_pos);
1132
1148
1149
+ auto check_lifecycle_state = [&](const std::vector<uint8_t > & expected_states)
1150
+ {
1151
+ ASSERT_EQ (expected_states[0 ], test_controller->get_lifecycle_state ().id ())
1152
+ << " Unexpected state for controller: " << test_controller->get_name ();
1153
+ ASSERT_EQ (expected_states[1 ], test_chained_controller_7->get_lifecycle_state ().id ())
1154
+ << " Unexpected state for controller: " << test_chained_controller_7->get_name ();
1155
+ ASSERT_EQ (expected_states[2 ], test_chained_controller_6->get_lifecycle_state ().id ())
1156
+ << " Unexpected state for controller: " << test_chained_controller_6->get_name ();
1157
+ ASSERT_EQ (expected_states[3 ], test_chained_controller_5->get_lifecycle_state ().id ())
1158
+ << " Unexpected state for controller: " << test_chained_controller_5->get_name ();
1159
+ ASSERT_EQ (expected_states[4 ], test_chained_controller_4->get_lifecycle_state ().id ())
1160
+ << " Unexpected state for controller: " << test_chained_controller_4->get_name ();
1161
+ ASSERT_EQ (expected_states[5 ], test_chained_controller_3->get_lifecycle_state ().id ())
1162
+ << " Unexpected state for controller: " << test_chained_controller_3->get_name ();
1163
+ ASSERT_EQ (expected_states[6 ], test_chained_controller_2->get_lifecycle_state ().id ())
1164
+ << " Unexpected state for controller: " << test_chained_controller_2->get_name ();
1165
+ ASSERT_EQ (expected_states[7 ], test_chained_controller_1->get_lifecycle_state ().id ())
1166
+ << " Unexpected state for controller: " << test_chained_controller_1->get_name ();
1167
+ };
1168
+
1133
1169
// Now let's activate the top level controller and see if the whole chain is activated
1134
- cm_->switch_controller (
1135
- {" test_controller_name" }, {}, controller_manager_msgs::srv::SwitchController::Request::AUTO,
1136
- true , rclcpp::Duration (0 , 0 ));
1137
1170
ASSERT_EQ (
1138
- lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller-> get_lifecycle_state (). id ());
1139
- ASSERT_EQ (
1140
- lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE ,
1141
- test_chained_controller_7-> get_lifecycle_state (). id ( ));
1142
- ASSERT_EQ (
1143
- lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1144
- test_chained_controller_6-> get_lifecycle_state (). id ());
1145
- ASSERT_EQ (
1146
- lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1147
- test_chained_controller_5-> get_lifecycle_state (). id ());
1148
- ASSERT_EQ (
1149
- lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1150
- test_chained_controller_4-> get_lifecycle_state (). id ());
1151
- ASSERT_EQ (
1152
- lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1153
- test_chained_controller_3-> get_lifecycle_state (). id ());
1171
+ controller_interface::return_type::OK,
1172
+ cm_-> switch_controller (
1173
+ { " test_controller_name " }, {}, controller_manager_msgs::srv::SwitchController::Request::AUTO ,
1174
+ true , rclcpp::Duration ( 0 , 0 ) ));
1175
+
1176
+ check_lifecycle_state (
1177
+ {lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1178
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1179
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1180
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1181
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1182
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1183
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1184
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE});
1185
+
1186
+ // Now deactivate the chained_controller_1 and everything should deactivate
1154
1187
ASSERT_EQ (
1155
- lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1156
- test_chained_controller_2->get_lifecycle_state ().id ());
1188
+ controller_interface::return_type::OK,
1189
+ cm_->switch_controller (
1190
+ {}, {TEST_CHAINED_CONTROLLER_1},
1191
+ controller_manager_msgs::srv::SwitchController::Request::AUTO, true , rclcpp::Duration (0 , 0 )));
1192
+
1193
+ check_lifecycle_state (
1194
+ {lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1195
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1196
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1197
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1198
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1199
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1200
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1201
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE});
1202
+
1157
1203
ASSERT_EQ (
1158
- lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1159
- test_chained_controller_1->get_lifecycle_state ().id ());
1204
+ controller_interface::return_type::OK,
1205
+ cm_->switch_controller (
1206
+ {TEST_CHAINED_CONTROLLER_6}, {},
1207
+ controller_manager_msgs::srv::SwitchController::Request::AUTO, true , rclcpp::Duration (0 , 0 )));
1208
+ check_lifecycle_state (
1209
+ {lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1210
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1211
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1212
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1213
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1214
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1215
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1216
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE});
1160
1217
1161
- // Now deactivate the chained_controller_1 and everything should deactivate
1162
- cm_->switch_controller (
1163
- {}, {TEST_CHAINED_CONTROLLER_1}, controller_manager_msgs::srv::SwitchController::Request::AUTO,
1164
- true , rclcpp::Duration (0 , 0 ));
1218
+ // Now deactivate the chained_controller_1 and 3 and everything should deactivate
1165
1219
ASSERT_EQ (
1166
- lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1167
- test_controller->get_lifecycle_state ().id ());
1220
+ controller_interface::return_type::OK,
1221
+ cm_->switch_controller (
1222
+ {}, {TEST_CHAINED_CONTROLLER_1, TEST_CHAINED_CONTROLLER_3},
1223
+ controller_manager_msgs::srv::SwitchController::Request::AUTO, true , rclcpp::Duration (0 , 0 )));
1224
+
1225
+ check_lifecycle_state (
1226
+ {lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1227
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1228
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1229
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1230
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1231
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1232
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1233
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE});
1234
+
1168
1235
ASSERT_EQ (
1169
- lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1170
- test_chained_controller_7->get_lifecycle_state ().id ());
1236
+ controller_interface::return_type::OK,
1237
+ cm_->switch_controller (
1238
+ {TEST_CHAINED_CONTROLLER_2}, {},
1239
+ controller_manager_msgs::srv::SwitchController::Request::AUTO, true , rclcpp::Duration (0 , 0 )));
1240
+
1241
+ check_lifecycle_state (
1242
+ {lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1243
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1244
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1245
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1246
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1247
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1248
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1249
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE});
1250
+
1171
1251
ASSERT_EQ (
1172
- lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1173
- test_chained_controller_6->get_lifecycle_state ().id ());
1252
+ controller_interface::return_type::OK,
1253
+ cm_->switch_controller (
1254
+ {TEST_CHAINED_CONTROLLER_5}, {},
1255
+ controller_manager_msgs::srv::SwitchController::Request::AUTO, true , rclcpp::Duration (0 , 0 )));
1256
+ check_lifecycle_state (
1257
+ {lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1258
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1259
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1260
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1261
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1262
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1263
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1264
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE});
1265
+
1174
1266
ASSERT_EQ (
1175
- lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1176
- test_chained_controller_5->get_lifecycle_state ().id ());
1267
+ controller_interface::return_type::OK,
1268
+ cm_->switch_controller (
1269
+ {TEST_CHAINED_CONTROLLER_7}, {},
1270
+ controller_manager_msgs::srv::SwitchController::Request::AUTO, true , rclcpp::Duration (0 , 0 )));
1271
+ check_lifecycle_state (
1272
+ {lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1273
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1274
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1275
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1276
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1277
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1278
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1279
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE});
1280
+
1281
+ // repeating the last should also result in same state and succeed
1282
+
1177
1283
ASSERT_EQ (
1178
- lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1179
- test_chained_controller_4->get_lifecycle_state ().id ());
1284
+ controller_interface::return_type::OK,
1285
+ cm_->switch_controller (
1286
+ {TEST_CHAINED_CONTROLLER_7}, {},
1287
+ controller_manager_msgs::srv::SwitchController::Request::AUTO, true , rclcpp::Duration (0 , 0 )));
1288
+ check_lifecycle_state (
1289
+ {lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1290
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1291
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1292
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1293
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1294
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1295
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1296
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE});
1297
+
1180
1298
ASSERT_EQ (
1181
- lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1182
- test_chained_controller_3->get_lifecycle_state ().id ());
1299
+ controller_interface::return_type::OK,
1300
+ cm_->switch_controller (
1301
+ {TEST_CHAINED_CONTROLLER_5, TEST_CHAINED_CONTROLLER_2}, {},
1302
+ controller_manager_msgs::srv::SwitchController::Request::AUTO, true , rclcpp::Duration (0 , 0 )));
1303
+ check_lifecycle_state (
1304
+ {lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1305
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1306
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1307
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1308
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1309
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1310
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1311
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE});
1312
+
1313
+ // Deactivate the whole chain by deactivating 1 and 3
1183
1314
ASSERT_EQ (
1184
- lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1185
- test_chained_controller_2->get_lifecycle_state ().id ());
1315
+ controller_interface::return_type::OK,
1316
+ cm_->switch_controller (
1317
+ {}, {TEST_CHAINED_CONTROLLER_1, TEST_CHAINED_CONTROLLER_3},
1318
+ controller_manager_msgs::srv::SwitchController::Request::AUTO, true , rclcpp::Duration (0 , 0 )));
1319
+
1320
+ check_lifecycle_state (
1321
+ {lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1322
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1323
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1324
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1325
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1326
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1327
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1328
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE});
1329
+
1186
1330
ASSERT_EQ (
1187
- lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1188
- test_chained_controller_1->get_lifecycle_state ().id ());
1331
+ controller_interface::return_type::OK,
1332
+ cm_->switch_controller (
1333
+ {TEST_CHAINED_CONTROLLER_2, TEST_CHAINED_CONTROLLER_5}, {},
1334
+ controller_manager_msgs::srv::SwitchController::Request::AUTO, true , rclcpp::Duration (0 , 0 )));
1335
+ check_lifecycle_state (
1336
+ {lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1337
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1338
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
1339
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1340
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1341
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1342
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
1343
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE});
1189
1344
}
1190
1345
1191
1346
TEST_F (TestControllerManagerSrvs, list_sorted_independent_chained_controllers)
0 commit comments