Skip to content

Commit

Permalink
fix the condition of the clock
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Feb 10, 2025
1 parent 2182de8 commit 79bd7a3
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -403,8 +403,8 @@ void ControllerManager::initialize_parameters()
params_ = std::make_shared<controller_manager::Params>(cm_param_listener_->get_params());
update_rate_ = static_cast<unsigned int>(params_->update_rate);
trigger_clock_ = realtime_tools::has_realtime_kernel()
? this->get_clock()
: std::make_shared<rclcpp::Clock>(RCL_STEADY_TIME);
? std::make_shared<rclcpp::Clock>(RCL_STEADY_TIME)
: this->get_clock();
RCLCPP_INFO(
get_logger(), "Using %s clock for triggering controller manager cycles.",
trigger_clock_->get_clock_type() == RCL_STEADY_TIME ? "Steady (Monotonic)" : "ROS");
Expand Down

0 comments on commit 79bd7a3

Please sign in to comment.