From 0970d016ce5d72c3c68cd4c50b2e745ccd324173 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Denis=20=C5=A0togl?= Date: Thu, 25 Aug 2022 19:36:48 +0200 Subject: [PATCH] Do some more variable renaming to the new nomenclature. --- controller_manager/src/controller_manager.cpp | 6 +++--- hardware_interface/test/test_components/test_actuator.cpp | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index ddc775ffee1..441efe4bece 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -837,7 +837,7 @@ controller_interface::return_type ControllerManager::switch_controller( // outdated. Keeping it up to date is not easy because of stopping controllers from multiple // threads maybe we should not at all cache this but always search for the related controllers // to a hardware when error in hardware happens - if (in_start_list) + if (in_activate_list) { std::vector interface_names = {}; @@ -1718,7 +1718,7 @@ void ControllerManager::read(const rclcpp::Time & time, const rclcpp::Duration & std::vector & rt_controller_list = rt_controllers_wrapper_.update_and_get_used_by_rt_list(); - stop_controllers(rt_controller_list, stop_request); + deactivate_controllers(rt_controller_list, stop_request); // TODO(destogl): do auto-start of broadcasters } } @@ -1788,7 +1788,7 @@ void ControllerManager::write(const rclcpp::Time & time, const rclcpp::Duration std::vector & rt_controller_list = rt_controllers_wrapper_.update_and_get_used_by_rt_list(); - stop_controllers(rt_controller_list, stop_request); + deactivate_controllers(rt_controller_list, stop_request); // TODO(destogl): do auto-start of broadcasters } } diff --git a/hardware_interface/test/test_components/test_actuator.cpp b/hardware_interface/test/test_components/test_actuator.cpp index 4165e79047f..99337664320 100644 --- a/hardware_interface/test/test_components/test_actuator.cpp +++ b/hardware_interface/test/test_components/test_actuator.cpp @@ -81,7 +81,7 @@ class TestActuator : public ActuatorInterface if (velocity_command_ == 28282828.0) { // reset value to get out from error on the next call - simplifies CM tests - position_command_ = 0.0; + velocity_command_ = 0.0; return return_type::ERROR; } // The next line is for the testing purposes. We need value to be changed to be sure that @@ -98,7 +98,7 @@ class TestActuator : public ActuatorInterface if (velocity_command_ == 23232323.0) { // reset value to get out from error on the next call - simplifies CM tests - position_command_ = 0.0; + velocity_command_ = 0.0; return return_type::ERROR; } return return_type::OK;