Skip to content

Commit 8b98fbf

Browse files
authored
Don't print the overrun warnings for the simulations (#2539)
1 parent 8beae64 commit 8b98fbf

File tree

2 files changed

+30
-17
lines changed

2 files changed

+30
-17
lines changed

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -630,6 +630,7 @@ class ControllerManager : public rclcpp::Node
630630
std::function<void()> on_switch_callback_ = nullptr;
631631
};
632632

633+
bool use_sim_time_;
633634
rclcpp::Clock::SharedPtr trigger_clock_ = nullptr;
634635
std::unique_ptr<rclcpp::PreShutdownCallbackHandle> preshutdown_cb_handle_{nullptr};
635636
RTControllerListWrapper rt_controllers_wrapper_;

controller_manager/src/controller_manager.cpp

Lines changed: 29 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -595,9 +595,9 @@ void ControllerManager::initialize_parameters()
595595
this->get_node_parameters_interface(), this->get_logger());
596596
params_ = std::make_shared<controller_manager::Params>(cm_param_listener_->get_params());
597597
update_rate_ = static_cast<unsigned int>(params_->update_rate);
598-
const rclcpp::Parameter use_sim_time = this->get_parameter("use_sim_time");
598+
use_sim_time_ = this->get_parameter("use_sim_time").as_bool();
599599
trigger_clock_ =
600-
use_sim_time.as_bool() ? this->get_clock() : std::make_shared<rclcpp::Clock>(RCL_STEADY_TIME);
600+
use_sim_time_ ? this->get_clock() : std::make_shared<rclcpp::Clock>(RCL_STEADY_TIME);
601601
RCLCPP_INFO(
602602
get_logger(), "Using %s clock for triggering controller manager cycles.",
603603
trigger_clock_->get_clock_type() == RCL_STEADY_TIME ? "Steady (Monotonic)" : "ROS");
@@ -3179,19 +3179,32 @@ void ControllerManager::write(const rclcpp::Time & time, const rclcpp::Duration
31793179
execution_time_.total_time =
31803180
execution_time_.write_time + execution_time_.update_time + execution_time_.read_time;
31813181
const double expected_cycle_time = 1.e6 / static_cast<double>(get_update_rate());
3182-
if (execution_time_.total_time > expected_cycle_time)
3183-
{
3184-
RCLCPP_WARN_THROTTLE(
3185-
get_logger(), *get_clock(), 1000,
3186-
"Overrun might occur, Total time : %.3f us (Expected < %.3f us) --> Read time : %.3f us, "
3187-
"Update time : %.3f us (Switch time : %.3f us (Switch chained mode time : %.3f us, perform "
3188-
"mode change time : %.3f us, Activation time : %.3f us, Deactivation time : %.3f us)), Write "
3189-
"time : %.3f us",
3190-
execution_time_.total_time, expected_cycle_time, execution_time_.read_time,
3191-
execution_time_.update_time, execution_time_.switch_time,
3192-
execution_time_.switch_chained_mode_time, execution_time_.switch_perform_mode_time,
3193-
execution_time_.activation_time, execution_time_.deactivation_time,
3194-
execution_time_.write_time);
3182+
if (execution_time_.total_time > expected_cycle_time && !use_sim_time_)
3183+
{
3184+
if (execution_time_.switch_time > 0.0)
3185+
{
3186+
RCLCPP_WARN_THROTTLE(
3187+
get_logger(), *get_clock(), 1000,
3188+
"Overrun might occur, Total time : %.3f us (Expected < %.3f us) --> Read time : %.3f us, "
3189+
"Update time : %.3f us (Switch time : %.3f us (Switch chained mode time : %.3f us, perform "
3190+
"mode change time : %.3f us, Activation time : %.3f us, Deactivation time : %.3f us)), "
3191+
"Write "
3192+
"time : %.3f us",
3193+
execution_time_.total_time, expected_cycle_time, execution_time_.read_time,
3194+
execution_time_.update_time, execution_time_.switch_time,
3195+
execution_time_.switch_chained_mode_time, execution_time_.switch_perform_mode_time,
3196+
execution_time_.activation_time, execution_time_.deactivation_time,
3197+
execution_time_.write_time);
3198+
}
3199+
else
3200+
{
3201+
RCLCPP_WARN_THROTTLE(
3202+
get_logger(), *get_clock(), 1000,
3203+
"Overrun might occur, Total time : %.3f us (Expected < %.3f us) --> Read time : %.3f us, "
3204+
"Update time : %.3f us, Write time : %.3f us",
3205+
execution_time_.total_time, expected_cycle_time, execution_time_.read_time,
3206+
execution_time_.update_time, execution_time_.write_time);
3207+
}
31953208
}
31963209
}
31973210

@@ -4350,8 +4363,7 @@ rclcpp::NodeOptions ControllerManager::determine_controller_node_options(
43504363
}
43514364

43524365
// ensure controller's `use_sim_time` parameter matches controller_manager's
4353-
const rclcpp::Parameter use_sim_time = this->get_parameter("use_sim_time");
4354-
if (use_sim_time.as_bool())
4366+
if (use_sim_time_)
43554367
{
43564368
if (!check_for_element(node_options_arguments, RCL_ROS_ARGS_FLAG))
43574369
{

0 commit comments

Comments
 (0)