Skip to content

Commit 1fcf10f

Browse files
authored
Added parameters to handle the overruns behaviour and prints (#2546)
1 parent 6077af4 commit 1fcf10f

File tree

5 files changed

+31
-4
lines changed

5 files changed

+31
-4
lines changed

controller_manager/doc/userdoc.rst

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -383,6 +383,12 @@ thread_priority (optional; int; default: 50)
383383
use_sim_time (optional; bool; default: false)
384384
Enables the use of simulation time in the ``controller_manager`` node.
385385

386+
overruns.manage (optional; bool; default: true)
387+
Enables or disables the handling of overruns in the real-time loop of the ``controller_manager`` node.
388+
If set to true, the controller manager will detect overruns caused by system time changes or longer execution times of the controllers and hardware components.
389+
If an overrun is detected, the controller manager will print a warning message to the console.
390+
When used with ``use_sim_time`` set to true, this parameter is ignored and the overrun handling is disabled.
391+
386392
Concepts
387393
-----------
388394

controller_manager/src/controller_manager.cpp

Lines changed: 14 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -583,11 +583,23 @@ void ControllerManager::initialize_parameters()
583583
// Initialize parameters
584584
try
585585
{
586+
use_sim_time_ = this->get_parameter("use_sim_time").as_bool();
587+
588+
if (!this->has_parameter("overruns.print_warnings"))
589+
{
590+
rcl_interfaces::msg::ParameterDescriptor descriptor;
591+
descriptor.description =
592+
"If true, the controller manager will print a warning message to the console if an overrun "
593+
"is detected in its real-time loop (read, update and write). By default, it is set to "
594+
"true, except when used with use_sim_time parameter set to true.";
595+
descriptor.read_only = false;
596+
auto parameter = rclcpp::ParameterValue(!use_sim_time_);
597+
this->declare_parameter("overruns.print_warnings", parameter, descriptor);
598+
}
586599
cm_param_listener_ = std::make_shared<controller_manager::ParamListener>(
587600
this->get_node_parameters_interface(), this->get_logger());
588601
params_ = std::make_shared<controller_manager::Params>(cm_param_listener_->get_params());
589602
update_rate_ = static_cast<unsigned int>(params_->update_rate);
590-
use_sim_time_ = this->get_parameter("use_sim_time").as_bool();
591603
trigger_clock_ =
592604
use_sim_time_ ? this->get_clock() : std::make_shared<rclcpp::Clock>(RCL_STEADY_TIME);
593605
RCLCPP_INFO(
@@ -3187,7 +3199,7 @@ void ControllerManager::write(const rclcpp::Time & time, const rclcpp::Duration
31873199
execution_time_.total_time =
31883200
execution_time_.write_time + execution_time_.update_time + execution_time_.read_time;
31893201
const double expected_cycle_time = 1.e6 / static_cast<double>(get_update_rate());
3190-
if (execution_time_.total_time > expected_cycle_time && !use_sim_time_)
3202+
if (params_->overruns.print_warnings && execution_time_.total_time > expected_cycle_time)
31913203
{
31923204
if (execution_time_.switch_time > 0.0)
31933205
{

controller_manager/src/controller_manager_parameters.yaml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -251,3 +251,8 @@ controller_manager:
251251
gt<>: 0.0,
252252
}
253253
}
254+
overruns:
255+
print_warnings: {
256+
type: bool,
257+
description: "If true, the controller manager will print a warning message to the console if an overrun is detected in its real-time loop (``read``, ``update`` and ``write``). By default, it is set to true, except when used with ``use_sim_time`` parameter set to true.",
258+
}

controller_manager/src/ros2_control_node.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -75,13 +75,16 @@ int main(int argc, char ** argv)
7575
cm->get_clock()->sleep_for(rclcpp::Duration::from_seconds(1.0 / cm->get_update_rate()));
7676

7777
RCLCPP_INFO(cm->get_logger(), "update rate is %d Hz", cm->get_update_rate());
78+
const bool manage_overruns = cm->get_parameter_or<bool>("overruns.manage", true);
79+
RCLCPP_INFO(
80+
cm->get_logger(), "Overruns handling is : %s", manage_overruns ? "enabled" : "disabled");
7881
const int thread_priority = cm->get_parameter_or<int>("thread_priority", kSchedPriority);
7982
RCLCPP_INFO(
8083
cm->get_logger(), "Spawning %s RT thread with scheduler priority: %d", cm->get_name(),
8184
thread_priority);
8285

8386
std::thread cm_thread(
84-
[cm, thread_priority, use_sim_time]()
87+
[cm, thread_priority, use_sim_time, manage_overruns]()
8588
{
8689
rclcpp::Parameter cpu_affinity_param;
8790
if (cm->get_parameter("cpu_affinity", cpu_affinity_param))
@@ -153,7 +156,7 @@ int main(int argc, char ** argv)
153156
{
154157
next_iteration_time += period;
155158
const auto time_now = std::chrono::steady_clock::now();
156-
if (next_iteration_time < time_now)
159+
if (manage_overruns && next_iteration_time < time_now)
157160
{
158161
const double time_diff =
159162
static_cast<double>(

doc/release_notes.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@ controller_manager
1010
* The default strictness of the ``switch_controllers`` can now we be chosen using ROS 2 parameters. The default behaviour is still left to ``BEST_EFFORT`` (`#2168 <https://github.com/ros-controls/ros2_control/pull/2168>`_).
1111
* Parameter ``shutdown_on_initial_state_failure`` was added to avoid shutting down on hardware initial state failure (`#2230 <https://github.com/ros-controls/ros2_control/pull/2230>`_).
1212
* The controller manager now publishes ``~/statistics/names`` and ``~/statistics/values`` topics to introspect the execution time and periodicity of the different entities running in the realtime loop (`#2449 <https://github.com/ros-controls/ros2_control/pull/2449>`_).
13+
* New parameters ``overruns.manage`` and ``overruns.print_warnings`` were added to control the behavior of the controller manager/ros2_control_node when overruns occur (`#2546 <https://github.com/ros-controls/ros2_control/pull/2546/files>`_).
1314

1415
hardware_interface
1516
******************

0 commit comments

Comments
 (0)