diff --git a/nav2_controller/src/nav2_controller.cpp b/nav2_controller/src/nav2_controller.cpp index bb53e3c6d42..7af5e660cf2 100644 --- a/nav2_controller/src/nav2_controller.cpp +++ b/nav2_controller/src/nav2_controller.cpp @@ -283,7 +283,7 @@ void ControllerServer::computeControl() setPlannerPath(action_server_->get_current_goal()->path); progress_checker_->reset(); - rclcpp::Rate loop_rate(controller_frequency_); + rclcpp::WallRate loop_rate(controller_frequency_); while (rclcpp::ok()) { if (action_server_ == nullptr || !action_server_->is_server_active()) { RCLCPP_DEBUG(get_logger(), "Action server unavailable or inactive. Stopping."); diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index f70d2ac6b37..7b7b3ea4be5 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -382,7 +382,7 @@ Costmap2DROS::mapUpdateLoop(double frequency) RCLCPP_DEBUG(get_logger(), "Entering loop"); - rclcpp::Rate r(frequency); // 200ms by default + rclcpp::WallRate r(frequency); // 200ms by default while (rclcpp::ok() && !map_update_thread_shutdown_) { nav2_util::ExecutionTimer timer; diff --git a/nav2_recoveries/include/nav2_recoveries/recovery.hpp b/nav2_recoveries/include/nav2_recoveries/recovery.hpp index b52d944884e..829fc44385a 100644 --- a/nav2_recoveries/include/nav2_recoveries/recovery.hpp +++ b/nav2_recoveries/include/nav2_recoveries/recovery.hpp @@ -197,7 +197,7 @@ class Recovery : public nav2_core::Recovery // Initialize the ActionT result auto result = std::make_shared(); - rclcpp::Rate loop_rate(cycle_frequency_); + rclcpp::WallRate loop_rate(cycle_frequency_); while (rclcpp::ok()) { if (action_server_->is_cancel_requested()) { diff --git a/nav2_waypoint_follower/src/waypoint_follower.cpp b/nav2_waypoint_follower/src/waypoint_follower.cpp index a923098de69..a6d3b55e361 100644 --- a/nav2_waypoint_follower/src/waypoint_follower.cpp +++ b/nav2_waypoint_follower/src/waypoint_follower.cpp @@ -132,7 +132,7 @@ WaypointFollower::followWaypoints() return; } - rclcpp::Rate r(loop_rate_); + rclcpp::WallRate r(loop_rate_); uint32_t goal_index = 0; bool new_goal = true;