Note: This tutorial assumes that you have completed the previous tutorials: roscpp tutorials.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Understanding Timers

Description: This tutorial explains roscpp Timers, which allow you to schedule a callback to happen periodically.

Tutorial Level: INTERMEDIATE

What are Timers?

Timers let you schedule a callback to happen at a specified rate. They are a more flexible and useful form of the ros::Rate used in the Writing a Simple Publisher and Subscriber tutorial.

Note that Timers are not a realtime thread/kernel replacement, and make no guarantees about how accurate they are, which can vary wildly because of system load/capabilities.

See also: roscpp Timers overview

Using Timers

Creating a Timer works very similar to creating a Subscriber.

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

Timer callbacks take the form:

   1 void timerCallback(const ros::TimerEvent& e);

A full example

Now that you've seen the basics, let's go through a larger example, with multiple Timers.

The code

  28 #include "ros/ros.h"
  29 
  30 /**
  31  * This tutorial demonstrates the use of timer callbacks.
  32  */
  33 
  34 void callback1(const ros::TimerEvent&)
  35 {
  36   ROS_INFO("Callback 1 triggered");
  37 }
  38 
  39 void callback2(const ros::TimerEvent&)
  40 {
  41   ROS_INFO("Callback 2 triggered");
  42 }
  43 
  44 int main(int argc, char **argv)
  45 {
  46   ros::init(argc, argv, "talker");
  47   ros::NodeHandle n;
  48 
  49   /**
  50    * Timers allow you to get a callback at a specified rate.  Here we create
  51    * two timers at different rates as a demonstration.
  52    */
  53   ros::Timer timer1 = n.createTimer(ros::Duration(0.1), callback1);
  54   ros::Timer timer2 = n.createTimer(ros::Duration(1.0), callback2);
  55 
  56   ros::spin();
  57 
  58   return 0;
  59 }

The code explained

I'll ignore parts that have been explained in previous tutorials, which really just leaves two lines:

  53   ros::Timer timer1 = n.createTimer(ros::Duration(0.1), callback1);
  54   ros::Timer timer2 = n.createTimer(ros::Duration(1.0), callback2);

Here we create two timers, one which fires every 100 milliseconds, and one which fires every second. If you run this program, it should output something like the following:

[ INFO] 1251854032.362376000: Callback 1 triggered
[ INFO] 1251854032.462840000: Callback 1 triggered
[ INFO] 1251854032.562464000: Callback 1 triggered
[ INFO] 1251854032.662169000: Callback 1 triggered
[ INFO] 1251854032.762649000: Callback 1 triggered
[ INFO] 1251854032.862853000: Callback 1 triggered
[ INFO] 1251854032.962642000: Callback 1 triggered
[ INFO] 1251854033.063118000: Callback 1 triggered
[ INFO] 1251854033.162221000: Callback 1 triggered
[ INFO] 1251854033.262749000: Callback 1 triggered
[ INFO] 1251854033.262864000: Callback 2 triggered
[ INFO] 1251854033.362643000: Callback 1 triggered
[ INFO] 1251854033.463158000: Callback 1 triggered
...

The TimerEvent Structure

The ros::TimerEvent structure provides you information about the timing of the current timer. Here is its definition:

   1 struct TimerEvent
   2 {
   3   Time last_expected;                     ///< In a perfect world, this is when the last callback should have happened
   4   Time last_real;                         ///< When the last callback actually happened
   5 
   6   Time current_expected;                  ///< In a perfect world, this is when the current callback should be happening
   7   Time current_real;                      ///< This is when the current callback was actually called (Time::now() as of the beginning of the callback)
   8 
   9   struct
  10   {
  11     WallDuration last_duration;           ///< How long the last callback ran for, always in wall-clock time
  12   } profile;
  13 };

Wiki: roscpp_tutorials/Tutorials/Timers (last edited 2018-05-08 08:22:12 by AndreaPonza)