diff --git a/controller_interface/include/controller_interface/controller_interface_base.hpp b/controller_interface/include/controller_interface/controller_interface_base.hpp index 44268dbe6d..bbc45c8583 100644 --- a/controller_interface/include/controller_interface/controller_interface_base.hpp +++ b/controller_interface/include/controller_interface/controller_interface_base.hpp @@ -153,9 +153,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy CONTROLLER_INTERFACE_PUBLIC unsigned int get_update_rate() const; - CONTROLLER_INTERFACE_PUBLIC - unsigned int get_cm_update_rate() const; - CONTROLLER_INTERFACE_PUBLIC bool is_async() const; @@ -229,7 +226,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy std::vector command_interfaces_; std::vector state_interfaces_; unsigned int update_rate_ = 0; - unsigned int cm_update_rate_ = 0; bool is_async_ = false; std::string urdf_ = ""; diff --git a/controller_interface/src/controller_interface_base.cpp b/controller_interface/src/controller_interface_base.cpp index f9347d454d..4594e7ac07 100644 --- a/controller_interface/src/controller_interface_base.cpp +++ b/controller_interface/src/controller_interface_base.cpp @@ -31,7 +31,6 @@ return_type ControllerInterfaceBase::init( node_ = std::make_shared( controller_name, namespace_, node_options, false); // disable LifecycleNode service interfaces urdf_ = urdf; - cm_update_rate_ = cm_update_rate; try { @@ -134,8 +133,6 @@ unsigned int ControllerInterfaceBase::get_update_rate() const { return update_ra bool ControllerInterfaceBase::is_async() const { return is_async_; } -unsigned int ControllerInterfaceBase::get_cm_update_rate() const { return cm_update_rate_; } - const std::string & ControllerInterfaceBase::get_robot_description() const { return urdf_; } } // namespace controller_interface diff --git a/controller_manager/test/test_controller_manager.cpp b/controller_manager/test/test_controller_manager.cpp index f6e8013299..8769a24749 100644 --- a/controller_manager/test/test_controller_manager.cpp +++ b/controller_manager/test/test_controller_manager.cpp @@ -376,7 +376,6 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd // similarly incremented EXPECT_EQ(test_controller->internal_counter, pre_internal_counter + (2 * cm_->get_update_rate())); EXPECT_EQ(test_controller->get_update_rate(), ctrl_update_rate); - EXPECT_EQ(test_controller->get_cm_update_rate(), cm_->get_update_rate()); auto deactivate_future = std::async( std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,