|
12 | 12 | // See the License for the specific language governing permissions and
|
13 | 13 | // limitations under the License.
|
14 | 14 |
|
15 |
| -#include <gtest/gtest.h> |
| 15 | +#include <gmock/gmock.h> |
16 | 16 | #include <memory>
|
17 | 17 | #include <string>
|
18 | 18 | #include <utility>
|
|
27 | 27 | using ::testing::_;
|
28 | 28 | using ::testing::Return;
|
29 | 29 |
|
30 |
| -class TestControllerManager |
| 30 | +class TestControllerManagerWithStrictness |
31 | 31 | : public ControllerManagerFixture<controller_manager::ControllerManager>,
|
32 | 32 | public testing::WithParamInterface<Strictness>
|
33 | 33 | {
|
34 | 34 | };
|
35 | 35 |
|
36 |
| -TEST_P(TestControllerManager, controller_lifecycle) |
| 36 | +TEST_P(TestControllerManagerWithStrictness, controller_lifecycle) |
37 | 37 | {
|
38 | 38 | const auto test_param = GetParam();
|
39 | 39 | auto test_controller = std::make_shared<test_controller::TestController>();
|
@@ -159,7 +159,7 @@ TEST_P(TestControllerManager, controller_lifecycle)
|
159 | 159 | controller_interface::return_type::OK,
|
160 | 160 | cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
|
161 | 161 | EXPECT_GE(test_controller->internal_counter, 1u);
|
162 |
| - auto last_internal_counter = test_controller->internal_counter; |
| 162 | + size_t last_internal_counter = test_controller->internal_counter; |
163 | 163 |
|
164 | 164 | // Stop controller, will take effect at the end of the update function
|
165 | 165 | start_controllers = {};
|
@@ -196,7 +196,7 @@ TEST_P(TestControllerManager, controller_lifecycle)
|
196 | 196 | EXPECT_EQ(1, test_controller.use_count());
|
197 | 197 | }
|
198 | 198 |
|
199 |
| -TEST_P(TestControllerManager, per_controller_update_rate) |
| 199 | +TEST_P(TestControllerManagerWithStrictness, per_controller_update_rate) |
200 | 200 | {
|
201 | 201 | auto strictness = GetParam().strictness;
|
202 | 202 | auto test_controller = std::make_shared<test_controller::TestController>();
|
@@ -254,4 +254,113 @@ TEST_P(TestControllerManager, per_controller_update_rate)
|
254 | 254 | }
|
255 | 255 |
|
256 | 256 | INSTANTIATE_TEST_SUITE_P(
|
257 |
| - test_strict_best_effort, TestControllerManager, testing::Values(strict, best_effort)); |
| 257 | + test_strict_best_effort, TestControllerManagerWithStrictness, |
| 258 | + testing::Values(strict, best_effort)); |
| 259 | + |
| 260 | +class TestControllerManagerWithUpdateRates |
| 261 | +: public ControllerManagerFixture<controller_manager::ControllerManager>, |
| 262 | + public testing::WithParamInterface<unsigned int> |
| 263 | +{ |
| 264 | +}; |
| 265 | + |
| 266 | +TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_update_rate) |
| 267 | +{ |
| 268 | + const auto strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; |
| 269 | + const unsigned int ctrl_update_rate = GetParam(); |
| 270 | + auto test_controller = std::make_shared<test_controller::TestController>(); |
| 271 | + |
| 272 | + auto last_internal_counter = 0u; |
| 273 | + RCLCPP_INFO( |
| 274 | + rclcpp::get_logger("test_controller_manager"), "Testing update rate : %u Hz", ctrl_update_rate); |
| 275 | + { |
| 276 | + ControllerManagerRunner cm_runner(this); |
| 277 | + cm_->add_controller( |
| 278 | + test_controller, test_controller::TEST_CONTROLLER_NAME, |
| 279 | + test_controller::TEST_CONTROLLER_CLASS_NAME); |
| 280 | + } |
| 281 | + EXPECT_EQ(1u, cm_->get_loaded_controllers().size()); |
| 282 | + EXPECT_EQ(2, test_controller.use_count()); |
| 283 | + EXPECT_EQ( |
| 284 | + controller_interface::return_type::OK, |
| 285 | + cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01))); |
| 286 | + EXPECT_EQ(last_internal_counter, test_controller->internal_counter) |
| 287 | + << "Update should not reach an unconfigured controller"; |
| 288 | + |
| 289 | + EXPECT_EQ( |
| 290 | + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state().id()); |
| 291 | + |
| 292 | + rclcpp::Parameter update_rate_parameter("update_rate", static_cast<int>(ctrl_update_rate)); |
| 293 | + test_controller->get_node()->set_parameter(update_rate_parameter); |
| 294 | + // configure controller |
| 295 | + cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME); |
| 296 | + EXPECT_EQ( |
| 297 | + controller_interface::return_type::OK, |
| 298 | + cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01))); |
| 299 | + EXPECT_EQ(last_internal_counter, test_controller->internal_counter) |
| 300 | + << "Controller is not started"; |
| 301 | + EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state().id()); |
| 302 | + |
| 303 | + // Start controller, will take effect at the end of the update function |
| 304 | + std::vector<std::string> start_controllers = {test_controller::TEST_CONTROLLER_NAME}; |
| 305 | + std::vector<std::string> stop_controllers = {}; |
| 306 | + auto switch_future = std::async( |
| 307 | + std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_, |
| 308 | + start_controllers, stop_controllers, strictness, true, rclcpp::Duration(0, 0)); |
| 309 | + |
| 310 | + ASSERT_EQ(std::future_status::timeout, switch_future.wait_for(std::chrono::milliseconds(100))) |
| 311 | + << "switch_controller should be blocking until next update cycle"; |
| 312 | + |
| 313 | + EXPECT_EQ( |
| 314 | + controller_interface::return_type::OK, |
| 315 | + cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01))); |
| 316 | + EXPECT_EQ(last_internal_counter, test_controller->internal_counter) |
| 317 | + << "Controller is started at the end of update"; |
| 318 | + { |
| 319 | + ControllerManagerRunner cm_runner(this); |
| 320 | + EXPECT_EQ(controller_interface::return_type::OK, switch_future.get()); |
| 321 | + } |
| 322 | + |
| 323 | + EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_state().id()); |
| 324 | + |
| 325 | + const auto pre_internal_counter = test_controller->internal_counter; |
| 326 | + rclcpp::Rate loop_rate(cm_->get_update_rate()); |
| 327 | + for (size_t i = 0; i < 2 * cm_->get_update_rate(); i++) |
| 328 | + { |
| 329 | + EXPECT_EQ( |
| 330 | + controller_interface::return_type::OK, |
| 331 | + cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01))); |
| 332 | + loop_rate.sleep(); |
| 333 | + } |
| 334 | + // if we do 2 times of the controller_manager update rate, the internal counter should be |
| 335 | + // similarly incremented |
| 336 | + EXPECT_EQ(test_controller->internal_counter, pre_internal_counter + (2 * cm_->get_update_rate())); |
| 337 | + EXPECT_EQ(test_controller->get_update_rate(), ctrl_update_rate); |
| 338 | + |
| 339 | + auto deactivate_future = std::async( |
| 340 | + std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_, |
| 341 | + stop_controllers, start_controllers, strictness, true, rclcpp::Duration(0, 0)); |
| 342 | + |
| 343 | + ASSERT_EQ(std::future_status::timeout, deactivate_future.wait_for(std::chrono::milliseconds(100))) |
| 344 | + << "switch_controller should be blocking until next update cycle"; |
| 345 | + |
| 346 | + EXPECT_EQ( |
| 347 | + controller_interface::return_type::OK, |
| 348 | + cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01))) |
| 349 | + << "Controller is stopped at the end of update, so it should have done one more update"; |
| 350 | + { |
| 351 | + ControllerManagerRunner cm_runner(this); |
| 352 | + EXPECT_EQ(controller_interface::return_type::OK, deactivate_future.get()); |
| 353 | + } |
| 354 | + auto unload_future = std::async( |
| 355 | + std::launch::async, &controller_manager::ControllerManager::unload_controller, cm_, |
| 356 | + test_controller::TEST_CONTROLLER_NAME); |
| 357 | + ASSERT_EQ(std::future_status::timeout, unload_future.wait_for(std::chrono::milliseconds(100))) |
| 358 | + << "unload_controller should be blocking until next update cycle"; |
| 359 | + ControllerManagerRunner cm_runner(this); |
| 360 | + EXPECT_EQ(controller_interface::return_type::OK, unload_future.get()); |
| 361 | + last_internal_counter = test_controller->internal_counter; |
| 362 | +} |
| 363 | + |
| 364 | +INSTANTIATE_TEST_SUITE_P( |
| 365 | + per_controller_equal_and_higher_update_rate, TestControllerManagerWithUpdateRates, |
| 366 | + testing::Values(100, 232, 400)); |
0 commit comments