From ecf095533456fd02ff7fd451c8517a3224c17fc9 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Mon, 10 Feb 2025 22:14:52 +0100 Subject: [PATCH] Use monotonic clock on realtime kernels --- controller_manager/src/controller_manager.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 99ab12bb47..8f01c2c0b2 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -402,9 +402,9 @@ void ControllerManager::initialize_parameters() this->get_node_parameters_interface(), this->get_logger()); params_ = std::make_shared(cm_param_listener_->get_params()); update_rate_ = static_cast(params_->update_rate); - const rclcpp::Parameter use_sim_time = this->get_parameter("use_sim_time"); - trigger_clock_ = - use_sim_time.as_bool() ? this->get_clock() : std::make_shared(RCL_STEADY_TIME); + trigger_clock_ = realtime_tools::has_realtime_kernel() + ? this->get_clock() + : std::make_shared(RCL_STEADY_TIME); RCLCPP_INFO( get_logger(), "Using %s clock for triggering controller manager cycles.", trigger_clock_->get_clock_type() == RCL_STEADY_TIME ? "Steady (Monotonic)" : "ROS");