ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

How to NOT auto-start timer in ROS2?

asked 2021-09-26 12:33:01 -0600

jn42 gravatar image

updated 2021-09-26 12:33:39 -0600

In the ROS2 docs for create_timer(), I don't see any arguments for NOT auto-starting the timer upon creation (unlike the createTimer() function in ROS1)

Am I just not seeing the way to do this in ROS2? Are there any workarounds?

edit retag flag offensive close merge delete

Comments

I have a workaround where I have a std::shared_ptr member variable for the timer and only call createTimer() when I actually want to start the timer. And to stop the timer from hitting it's callbacks, I simply call .reset() on the std::shared_ptr member variable

jn42 gravatar image jn42  ( 2021-09-27 13:07:38 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2023-06-20 05:33:11 -0600

jrtg gravatar image

Turns out it is fairly simple:

In your constructor:

// Create the timer  
timer_ = this->create_wall_timer(  
   timer_duration,
   std::bind(&MyClass::timer_callback, this));  

// Instantly stop the timer  
timer_->cancel();

And then define e.g. a service callback to start/stop the timer:

if (start_) {
  timer_->reset();  // starts the timer
} else {
  timer_->cancel();  // stops the timer
}

It's OK to call cancel() on an already stopped timer.

edit flag offensive delete link more

Comments

So technically, the answer would be: you can't.

But this seems like a good work-around though.

gvdhoorn gravatar image gvdhoorn  ( 2023-06-20 06:16:28 -0600 )edit

Well, technically, my answer answers at least one of the questions, whereas you can't is neither an answer to Am I just not seeing the way to do this in ROS2? nor to Are there any workarounds?. ;-)

Re. the proposed workaround: one possible flaw is that the constructor could be preempted between the creation and the cancelling of the timer, so that the timer might fire at least once if the preemption is long enough and the timer period small enough. But I assume this has a neglible probability for the typical use case.

jrtg gravatar image jrtg  ( 2023-06-20 06:39:15 -0600 )edit

The main question appears to be "How to NOT auto-start timer in ROS2?" (at least, that's the title of the post). The answer to that would be "it's not supported".

Note btw I wasn't trying to imply your answer is wrong. I even upvoted it.

Just pointing out something which seems like it should be documented somewhere.

gvdhoorn gravatar image gvdhoorn  ( 2023-06-20 06:41:32 -0600 )edit

Heh, that's correct. :-) No worries, it was intended in a funny way, hence the smiley. In an ideal world, someone would write a patch to add the functionality...

jrtg gravatar image jrtg  ( 2023-06-20 06:57:08 -0600 )edit

Recently this functionality has been added rolling: https://github.com/ros2/rclcpp/pull/2005

jrtg gravatar image jrtg  ( 2023-08-07 16:44:49 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2021-09-26 12:33:01 -0600

Seen: 1,943 times

Last updated: Jun 20 '23