Skip to content

Commit

Permalink
nav2_controller: add loop rate log (ros-navigation#4171)
Browse files Browse the repository at this point in the history
* update smac_planner README

Signed-off-by: ARK3r <[email protected]>

* added current controller loop rate logging

Signed-off-by: ARK3r <[email protected]>

* linting

Signed-off-by: ARK3r <[email protected]>

* uncrustify lint

Signed-off-by: ARK3r <[email protected]>

* Update nav2_controller/src/controller_server.cpp

Signed-off-by: Steve Macenski <[email protected]>

* Update nav2_controller/src/controller_server.cpp

Signed-off-by: Steve Macenski <[email protected]>

* Update nav2_controller/src/controller_server.cpp

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: ARK3r <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>
  • Loading branch information
ARK3r and SteveMacenski authored Mar 8, 2024
1 parent c9d9b5c commit 4737462
Showing 1 changed file with 5 additions and 2 deletions.
7 changes: 5 additions & 2 deletions nav2_controller/src/controller_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -419,6 +419,7 @@ void ControllerServer::computeControl()
{
std::lock_guard<std::mutex> lock(dynamic_params_lock_);

auto start_time = this->now();
RCLCPP_INFO(get_logger(), "Received a goal, begin computing control effort.");

try {
Expand Down Expand Up @@ -479,10 +480,12 @@ void ControllerServer::computeControl()
break;
}

auto cycle_duration = this->now() - start_time;
if (!loop_rate.sleep()) {
RCLCPP_WARN(
get_logger(), "Control loop missed its desired rate of %.4fHz",
controller_frequency_);
get_logger(),
"Control loop missed its desired rate of %.4f Hz. Current loop rate is %.4f Hz.",
controller_frequency_, 1 / cycle_duration.seconds());
}
}
} catch (nav2_core::InvalidController & e) {
Expand Down

0 comments on commit 4737462

Please sign in to comment.