Skip to content

interrupt_guard_condition_ causes executor "spurious" awakes #1021

@alsora

Description

@alsora

Bug report

Required Info:

  • Operating System:
    • Ubuntu 18.04
  • Installation type:
    • source

Steps to reproduce issue

Run a ROS 2 system made of a single node with only a timer. No publishers/subscriptions or anything else.

#include <chrono>
#include <memory>
#include "rclcpp/rclcpp.hpp"

using namespace std::chrono_literals;

class MinimalTimer : public rclcpp::Node
{
public:
  MinimalTimer()
  : Node("minimal_timer")
  {
    timer_ = this->create_wall_timer(
      5s, std::bind(&MinimalTimer::timer_callback, this));
  }

private:
  void timer_callback()
  {
    RCLCPP_WARN(this->get_logger(), "Timer executed!");
  }
  rclcpp::TimerBase::SharedPtr timer_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<MinimalTimer>());
  rclcpp::shutdown();
  return 0;
}

Expected behavior

The timer has a 5 seconds period, so the executor should wake up once every 5 seconds.

Actual behavior

After every real awakes, the executor wakes up a second time for no apparent reason.

  • Executor waits for 5 seconds
  • Executor wakes up to execute the timer callback
  • Executor goes back to wait
  • Executor wakes up IMMEDIATELY
  • There is no work to do, so executor goes back to wait
  • Executor waits for 5 seconds

This pattern keeps going on forever.
This applies also to more complex systems, with the same frequency.

Some logs that I added:

[INFO] [1583844157.135606428] [single_thread_exec_cpp]: LINE:34 Spin: While loop iteration
[INFO] [1583844157.135620489] [executor_cpp]: LINE:598 get_next_ready_executable 1st call: Nothing 
[INFO] [1583844162.135118217] [executor_cpp]: LINE:602 wait_for_work completed
[INFO] [1583844162.135281008] [executor_cpp]: LINE:540 found ready timer
[INFO] [1583844162.135315670] [executor_cpp]: LINE:607 get_next_ready_executable 2nd call: Success 
[WARN] [1583844162.135348415] [minimal_timer]: Timer executed!
[INFO] [1583844162.135504465] [single_thread_exec_cpp]: LINE:34 Spin: While loop iteration
[INFO] [1583844162.135538023] [executor_cpp]: LINE:598 get_next_ready_executable 1st call: Nothing 
[INFO] [1583844162.135712743] [executor_cpp]: LINE:602 wait_for_work completed
[INFO] [1583844162.135738309] [executor_cpp]: LINE:607 get_next_ready_executable 2nd call: Nothing 
[INFO] [1583844162.135759814] [single_thread_exec_cpp]: LINE:34 Spin: While loop iteration
[INFO] [1583844162.135781694] [executor_cpp]: LINE:598 get_next_ready_executable 1st call: Nothing 
[INFO] [1583844167.134761867] [executor_cpp]: LINE:602 wait_for_work completed
[INFO] [1583844167.134906444] [executor_cpp]: LINE:540 found ready timer
[INFO] [1583844167.134943200] [executor_cpp]: LINE:607 get_next_ready_executable 2nd call: Success 
[WARN] [1583844167.134976433] [minimal_timer]: Timer executed!

Additional information

I saw that the wait implementation in the DDS library is effectively called every time, so it's not the rcl layer or something that does not even go to sleep.

The culprit looks to be

memory_strategy_->add_guard_condition(&interrupt_guard_condition_);

If I remove this line, I see the correct number of awakes

See source code here

Metadata

Metadata

Assignees

Labels

bugSomething isn't workinghelp wantedExtra attention is needed

Type

No type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions