diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 583ab3cee0..b6ab481282 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -1230,8 +1230,6 @@ controller_interface::return_type ControllerManager::update( for (auto loaded_controller : rt_controller_list) { - // TODO(v-lopez) we could cache this information - // https://github.com/ros-controls/ros2_control/issues/153 if (is_controller_active(*loaded_controller.c)) { auto controller_update_rate = loaded_controller.c->get_update_rate(); diff --git a/controller_manager/src/ros2_control_node.cpp b/controller_manager/src/ros2_control_node.cpp index 2885f5f70d..4e7aa8238b 100644 --- a/controller_manager/src/ros2_control_node.cpp +++ b/controller_manager/src/ros2_control_node.cpp @@ -41,17 +41,19 @@ int main(int argc, char ** argv) RCLCPP_INFO(cm->get_logger(), "update rate is %d Hz", cm->get_update_rate()); rclcpp::Time begin = cm->now(); + rclcpp::Time begin_last = begin; + rclcpp::Time end = begin; // Use nanoseconds to avoid chrono's rounding std::this_thread::sleep_for(std::chrono::nanoseconds(1000000000 / cm->get_update_rate())); while (rclcpp::ok()) { - rclcpp::Time begin_last = begin; begin = cm->now(); cm->read(); cm->update(begin, begin - begin_last); + begin_last = begin; cm->write(); - rclcpp::Time end = cm->now(); + end = cm->now(); std::this_thread::sleep_for(std::max( std::chrono::nanoseconds(0), std::chrono::nanoseconds(1000000000 / cm->get_update_rate()) -