rclcpp
rclcpp copied to clipboard
EventsExecutor misses one-shot-timer and never executes it again.
Operating System:
Linux robin-zeal 6.9.3-76060903-generic #202405300957~1732141768~22.04~f2697e1~dev-Ubuntu SMP PREEMPT_DY x86_64 x86_64 x86_64 GNU/Linux
ROS version or commit hash:
jazzy
RMW implementation (if applicable):
rmw_zenoh_cpp
RMW Configuration (if applicable):
No response
Client library (if applicable):
rclcpp
'ros2 doctor --report' output
ros2 doc --report
<COPY OUTPUT HERE>
Steps to reproduce issue
Run this code
#include <chrono>
#include <memory>
#include <rclcpp/rclcpp.hpp>
using namespace std::chrono_literals;
class ExecutorBugNode : public rclcpp::Node
{
public:
ExecutorBugNode()
: Node("executor_bug_node")
{
wall_timer_ = create_wall_timer(
50ms, std::bind(&ExecutorBugNode::wall_timer_callback, this));
}
private:
void
wall_timer_callback()
{
if (counter_ < 100) {
std::this_thread::sleep_for(40ms);
counter_++;
} else {
RCLCPP_INFO(get_logger(), "Sleep stopped");
}
if (!one_shot_timer_) {
one_shot_timer_ = create_wall_timer(
0s, std::bind(&ExecutorBugNode::one_shot_timer_callback, this));
} else {
RCLCPP_INFO(get_logger(), "One-shot timer already exists. Skipping creation.");
}
}
void
one_shot_timer_callback()
{
RCLCPP_INFO(get_logger(), "--- One-shot timer callback triggered! ---");
if (one_shot_timer_) {
one_shot_timer_->cancel();
one_shot_timer_.reset();
}
}
size_t counter_ = 0;
rclcpp::TimerBase::SharedPtr wall_timer_;
rclcpp::TimerBase::SharedPtr one_shot_timer_;
};
int
main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<ExecutorBugNode>();
rclcpp::experimental::executors::EventsExecutor executor;
executor.add_node(node);
executor.spin();
executor.remove_node(node);
rclcpp::shutdown();
return 0;
}
Expected behavior
The one-shot timer callback should be called every time, or at least every time after the sleep part ends.
Actual behavior
The one-shot timer callback gets called a few times at the start, then it never gets called again even after the sleep part ends.
Additional information
The sleep is there because the event seems to be missed only when the executor takes a while handling other things. Once the event is missed, it is stuck forever. On the single-threaded executor the callback gets called every single time, it never skips creation.
[INFO] [2025-04-11 07:26:04.146] [executor_bug_node]: --- One-shot timer callback triggered! ---
[INFO] [2025-04-11 07:26:04.196] [executor_bug_node]: --- One-shot timer callback triggered! ---
[INFO] [2025-04-11 07:26:04.246] [executor_bug_node]: --- One-shot timer callback triggered! ---
[INFO] [2025-04-11 07:26:04.346] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:04.396] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:04.446] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:04.496] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:04.546] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:04.596] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:04.646] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:04.696] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:04.746] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:04.796] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:04.846] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:04.896] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:04.946] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:04.995] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.462] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.962] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.146] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.196] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.246] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.295] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.346] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.396] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.445] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.496] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.546] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.596] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.646] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.696] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.746] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.796] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.846] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.896] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.946] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:05.996] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.460] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.961] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.146] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.196] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.245] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.296] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.346] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.395] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.446] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.496] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.545] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.596] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.646] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.696] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.746] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.796] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.846] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.896] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.946] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:06.995] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.460] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.960] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.146] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.196] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.246] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.296] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.346] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.396] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.445] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.496] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.546] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.596] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.646] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.696] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.746] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.796] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.846] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.896] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.946] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:07.996] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.458] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.958] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.145] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.196] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.246] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.295] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.346] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.396] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.445] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.495] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.546] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.596] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.646] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.695] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.745] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.796] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.846] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.896] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.946] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:08.996] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.458] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.959] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.105] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.105] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.155] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.155] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.205] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.205] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.255] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.256] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.305] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.306] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.355] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.355] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.405] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.405] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.455] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.456] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.505] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.505] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.555] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.556] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.605] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.606] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.655] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.656] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.705] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.706] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.755] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.756] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.805] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.806] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.855] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.856] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.906] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.906] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:09.955] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:09.955] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:10.589] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:10.601] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:10.558] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:10.559] [executor_bug_node]: One-shot timer already exists. Skipping creation.
[INFO] [2025-04-11 07:26:10.105] [executor_bug_node]: Sleep stopped
[INFO] [2025-04-11 07:26:10.106] [executor_bug_node]: One-shot timer already exists. Skipping creation.
....