@@ -2835,7 +2835,7 @@ void ControllerManager::manage_switch()
2835
2835
const auto chain_start_time = std::chrono::steady_clock::now ();
2836
2836
switch_chained_mode (to_chained_mode_request_, true );
2837
2837
switch_chained_mode (from_chained_mode_request_, false );
2838
- RCLCPP_INFO (
2838
+ RCLCPP_DEBUG (
2839
2839
get_logger (),
2840
2840
" Switching %lu controllers to chained mode and %lu controllers from chained mode" ,
2841
2841
to_chained_mode_request_.size (), from_chained_mode_request_.size ());
@@ -3158,18 +3158,18 @@ void ControllerManager::write(const rclcpp::Time & time, const rclcpp::Duration
3158
3158
.count ();
3159
3159
execution_time_.total_time =
3160
3160
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 ;
3163
3163
RCLCPP_WARN_EXPRESSION (
3164
3164
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 ,
3171
3171
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 );
3173
3173
}
3174
3174
3175
3175
std::vector<ControllerSpec> &
0 commit comments