EventsExecutor with an overrunning timer can lead to a burst of timer events
Hi,
I recently found an issue with the EventsExecutor relating to timers. If a timer callback is running slower than its period then it will create multiple timer events inside the EventsExecutor. This leads to 2 issues:
- Other events will not run untill all queued timers events finish
- If the timer callback starts running faster than its period, a sudden burst of timer events will run.
Example:
The code to reproduce the following is given at the end. I am running ROS2 rolling (commit: fa63fcf) on Ubuntu 24.04. The first node is running a timer at 1Hz with a callback that publishes a message before sleeping for 2 seconds. A second node listens and measures the time between messages. The sleep time can be changed via:
ros2 topic pub /sleep_time std_msgs/msg/Float32 data:\ 0.01 -1
| Timer | Listener |
|---|---|
|
|
Why does this happen?
From my understanding of the EventsExecutor, it will add a timer event after each period of the timer regardless of if the timer has finished running or if there are other timer events in the queue. This leads to a build up of timer events. This backlog is the underlying root cause for both 1 and 2. The backlog will delay other incoming events (such as messages) and lead to the burst of timer events when the running time drops.
Observed behavioral differences to other executors:
SingleThreadedExecutor The SingleThreadedExecutor does not display either of the behaviors. If you publish a new message, its callback will be executed after the current timer. If the running time suddenly changes, the timer doesn't run faster than its period.
| Timer | Listener |
|---|---|
|
|
MultiThreadedExecutor The MultiThreadedExecutor can suffer from 1 (solvable by changing the setup of the callback groups) but should not suffer from 2. The issue with 1 has already been raised by this other issue https://github.com/ros2/rclcpp/issues/2402.
| Timer | Listener |
|---|---|
|
|
Code to reproduce
Timer
#include <chrono>
#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/experimental/executors/events_executor/events_executor.hpp"
#include "std_msgs/msg/float32.hpp"
#include "std_msgs/msg/bool.hpp"
using namespace std::chrono_literals;
class Timer : public rclcpp::Node
{
public:
Timer()
: Node("timer")
{
auto callback_group = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
rclcpp::SubscriptionOptions options;
options.callback_group = callback_group;
timer_ = this->create_wall_timer(1000ms, std::bind(&Timer::timer_callback, this));
sleep_time_sub_ = this->create_subscription<std_msgs::msg::Float32>(
"sleep_time", 10, std::bind(&Timer::sleep_time_callback, this, std::placeholders::_1), options);
publisher_ = this->create_publisher<std_msgs::msg::Bool>("msg", 10);
}
private:
void timer_callback()
{
rclcpp::Rate wait_time(1.0/sleep_time_);
RCLCPP_INFO_STREAM(get_logger(), "Sleeping for " << sleep_time_ << "s");
publisher_->publish(std_msgs::msg::Bool());
wait_time.sleep();
}
void sleep_time_callback(const std_msgs::msg::Float32::SharedPtr msg)
{
sleep_time_ = msg->data;
RCLCPP_INFO_STREAM(get_logger(), "Sleep changed to " << msg->data << "s");
}
private:
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Subscription<std_msgs::msg::Float32>::SharedPtr sleep_time_sub_;
rclcpp::Publisher<std_msgs::msg::Bool>::SharedPtr publisher_;
float sleep_time_{2.0f};
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = std::make_shared<Timer>();
rclcpp::experimental::executors::EventsExecutor executor;
// rclcpp::executors::SingleThreadedExecutor executor;
// rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(node);
executor.spin();
rclcpp::shutdown();
return 0;
}
Listener
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/bool.hpp"
class Listener : public rclcpp::Node
{
public:
Listener()
: Node("listener")
{
subscription_ =
this->create_subscription<std_msgs::msg::Bool>("msg", 10, std::bind(&Listener::callback, this, std::placeholders::_1));
}
void callback(std_msgs::msg::Bool::UniquePtr msg)
{
auto current_time = std::chrono::steady_clock::now();
// Calculate the time difference between the current time and the last received time
auto duration = std::chrono::duration_cast<std::chrono::duration<float>>(current_time - last_time_);
// Print the time difference in milliseconds
RCLCPP_INFO(get_logger(), "%.2fs since last msg", duration.count());
// Update the last time to the current time
last_time_ = current_time;
}
private:
std::chrono::steady_clock::time_point last_time_;
rclcpp::Subscription<std_msgs::msg::Bool>::SharedPtr subscription_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<Listener>());
rclcpp::shutdown();
return 0;
}