Skip to content

Commit 274b22e

Browse files
committed
improve the debug prints
1 parent 2121df0 commit 274b22e

File tree

1 file changed

+10
-10
lines changed

1 file changed

+10
-10
lines changed

controller_manager/src/controller_manager.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -2835,7 +2835,7 @@ void ControllerManager::manage_switch()
28352835
const auto chain_start_time = std::chrono::steady_clock::now();
28362836
switch_chained_mode(to_chained_mode_request_, true);
28372837
switch_chained_mode(from_chained_mode_request_, false);
2838-
RCLCPP_INFO(
2838+
RCLCPP_DEBUG(
28392839
get_logger(),
28402840
"Switching %lu controllers to chained mode and %lu controllers from chained mode",
28412841
to_chained_mode_request_.size(), from_chained_mode_request_.size());
@@ -3158,18 +3158,18 @@ void ControllerManager::write(const rclcpp::Time & time, const rclcpp::Duration
31583158
.count();
31593159
execution_time_.total_time =
31603160
execution_time_.write_time + execution_time_.update_time + execution_time_.read_time;
3161-
const bool print_log =
3162-
execution_time_.total_time > (1.e6 / static_cast<double>(get_update_rate()));
3161+
const double expected_cycle_time = 1.e6 / static_cast<double>(get_update_rate());
3162+
const bool print_log = execution_time_.total_time > expected_cycle_time;
31633163
RCLCPP_WARN_EXPRESSION(
31643164
get_logger(), print_log,
3165-
"Overrun might occur, Total time : %f us --> Read time : %f us, "
3166-
"Update time : %f us, Write time : %f us, and Switch time : %f us (Switch "
3167-
"chained mode time : %f us, perform mode change time : %f us, Activation time : %f us, "
3168-
"Deactivation time : %f us)",
3169-
execution_time_.total_time, execution_time_.read_time, execution_time_.update_time,
3170-
execution_time_.write_time, execution_time_.switch_time,
3165+
"Overrun might occur, Total time : %.3f us (Expected < %.3f us) --> Read time : %.3f us, "
3166+
"Update time : %.3f us (Switch time : %.3f us (Switch chained mode time : %.3f us, perform "
3167+
"mode change time : %.3f us, Activation time : %.3f us, Deactivation time : %.3f us)), Write "
3168+
"time : %.3f us",
3169+
execution_time_.total_time, expected_cycle_time, execution_time_.read_time,
3170+
execution_time_.update_time, execution_time_.switch_time,
31713171
execution_time_.switch_chained_mode_time, execution_time_.switch_perform_mode_time,
3172-
execution_time_.activation_time, execution_time_.deactivation_time);
3172+
execution_time_.activation_time, execution_time_.deactivation_time, execution_time_.write_time);
31733173
}
31743174

31753175
std::vector<ControllerSpec> &

0 commit comments

Comments
 (0)