Skip to content

Commit

Permalink
Fix const overload call
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jan 7, 2025
1 parent 08de669 commit 4ae7e79
Showing 1 changed file with 3 additions and 2 deletions.
5 changes: 3 additions & 2 deletions controller_interface/test/test_controller_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,10 +36,11 @@ TEST(TestableControllerInterface, init)
rclcpp::init(argc, argv);

TestableControllerInterface controller;
const TestableControllerInterface & const_controller = controller;

// try to get node when not initialized
ASSERT_THROW(controller.get_node(), std::runtime_error);
ASSERT_THROW(const auto node = controller.get_node(), std::runtime_error);
ASSERT_THROW(const_controller.get_node(), std::runtime_error);
ASSERT_THROW(controller.get_lifecycle_state(), std::runtime_error);

// initialize, create node
Expand All @@ -48,7 +49,7 @@ TEST(TestableControllerInterface, init)
controller.init(TEST_CONTROLLER_NAME, "", 10.0, "", node_options),
controller_interface::return_type::OK);
ASSERT_NO_THROW(controller.get_node());
ASSERT_NO_THROW(const auto node = controller.get_node());
ASSERT_NO_THROW(const_controller.get_node());
ASSERT_NO_THROW(controller.get_lifecycle_state());

// update_rate is set to controller_manager's rate
Expand Down

0 comments on commit 4ae7e79

Please sign in to comment.