roscpp overview: Initialization and Shutdown | Basics | Advanced: Traits [ROS C Turtle] | Advanced: Custom Allocators [ROS C Turtle] | Advanced: Serialization and Adapting Types [ROS C Turtle] | Publishers and Subscribers | Services | Parameter Server | Timers (Periodic Callbacks) | NodeHandles | Callbacks and Spinning | Logging | Names and Node Information | Time | Exceptions | Compilation Options | Advanced: Internals | tf/Overview | tf/Tutorials | C++ Style Guide

See also: roscpp Timers Tutorial

roscpp's Timers let you schedule a callback to happen at a specific rate through the same callback queue mechanism used by subscription, service, etc. callbacks.

Timers are not a realtime thread/kernel replacement, rather they are useful for things that do not have hard realtime requirements.

Creating a Timer

Creating a Timer is done through the ros::NodeHandle::createTimer() method:

   1 ros::Timer timer = nh.createTimer(ros::Duration(0.1), timerCallback);

There are a number of different forms of createTimer() which allow you to specify a few different options, as well as a number of different callback types. The general signature is:

   1 ros::Timer ros::NodeHandle::createTimer(ros::Duration period, <callback>, bool oneshot = false);
  • period

    • This is the period between calls to the timer callback. For example, if this is ros::Duration(0.1), the callback will be scheduled for every 1/10th of a second

    <callback>

    • This is the callback to be called -- it may be a function, class method or functor object. These are explained below.

    oneshot

    • Specifies whether or not the timer is a one-shot timer. If so, it will only fire once. Otherwise it will be re-scheduled continuously until it is stopped.

      If a one-shot timer has fired it can be reused by calling stop() along with setPeriod(ros::Duration) and start() to be re-scheduled once again.

Callback Signature

The signature for the timer callback is:

   1 void callback(const ros::TimerEvent&);

The ros::TimerEvent structure passed in provides you timing information that can be useful when debugging or profiling.

ros::TimerEvent

  • ros::Time last_expected

    • In a perfect world, this is when the previous callback should have happened

    ros::Time last_real

    • This is when the last callback actually happened

    ros::Time current_expected

    • In a perfect world, this is when the current callback should have been called

    ros::Time current_real

    • When the current callback is actually being called (ros::Time::now() as of immediately before calling the callback)

    ros::WallTime profile.last_duration

    • Contains the duration of the last callback (end time minus start time). Note that this is always in wall-clock time.

Callback Types

roscpp supports any callback supported by boost::bind:

  1. functions
  2. class methods
  3. functor objects (including boost::function)

Functions

   1 void callback(const ros::TimerEvent& event)
   2 {
   3 ...
   4 }
   5 
   6 ...
   7 ros::Timer timer = nh.createTimer(ros::Duration(0.1), callback);

Class Methods

   1 class Foo
   2 {
   3 public:
   4   void Foo::callback(const ros::TimerEvent& event)
   5   {
   6   ...
   7   }
   8 
   9   ros::Timer timer;
  10 };
  11 
  12 ...
  13 // then, during initialization, etc
  14 timer = nh.createTimer(ros::Duration(0.1), &Foo::callback, &foo_object);
  15 
  16 ...
  17 Foo foo_object;

Note that, in this example, the timer object must be a member of the class for callbacks to fire.

Functor Objects

   1 class Foo
   2 {
   3 public:
   4   void operator()(const ros::TimerEvent& event)
   5   {
   6     ...
   7   }
   8 };
   9 
  10 ...
  11 ros::Timer timer = nh.createTimer(ros::Duration(0.1), Foo());

A functor passed to createTimer() must be copyable.

Wall-clock Timers

ros::Timer uses the ROS Clock when available (usually when running in simulation). If you'd like a timer that always uses wall-clock time there is a ros::WallTimer that works exactly the same except replace Timer with WallTimer in all uses, e.g.:

   1 void callback(const ros::WallTimerEvent& event)
   2 {
   3   ...
   4 }
   5 
   6 ...
   7 ros::WallTimer timer = nh.createWallTimer(ros::WallDuration(0.1), callback);

Wiki: roscpp/Overview/Timers (last edited 2022-09-14 19:58:13 by NicolasVaras)