Skip to content

Commit

Permalink
Use Clock instead of Rate for backward compatibility of rolling (#1864)
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Nov 8, 2024
1 parent dffba96 commit 302baee
Showing 1 changed file with 2 additions and 3 deletions.
5 changes: 2 additions & 3 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@ int main(int argc, char ** argv)
auto cm = std::make_shared<controller_manager::ControllerManager>(executor, manager_node_name);

const bool use_sim_time = cm->get_parameter_or("use_sim_time", false);
rclcpp::Rate rate(cm->get_update_rate());

const int cpu_affinity = cm->get_parameter_or<int>("cpu_affinity", -1);
if (cpu_affinity >= 0)
Expand All @@ -71,7 +70,7 @@ int main(int argc, char ** argv)
thread_priority);

std::thread cm_thread(
[cm, thread_priority, use_sim_time, &rate]()
[cm, thread_priority, use_sim_time]()
{
if (realtime_tools::has_realtime_kernel())
{
Expand Down Expand Up @@ -125,7 +124,7 @@ int main(int argc, char ** argv)
next_iteration_time += period;
if (use_sim_time)
{
rate.sleep();
cm->get_clock()->sleep_until(current_time + period);
}
else
{
Expand Down

0 comments on commit 302baee

Please sign in to comment.