<> <> == Time and Duration == See also: [[http://docs.ros.org/latest/api/rostime/html/classros_1_1TimeBase.html|ros::TimeBase API docs]], [[http://docs.ros.org/latest/api/rostime/html/classros_1_1DurationBase.html|ros::DurationBase API docs]] ROS has builtin `time` and `duration` primitive types, which [[roslib]] provides as the `ros::Time` and `ros::Duration` classes, respectively. A `Time` is a specific moment (e.g. "today at 5pm") whereas a `Duration` is a period of time (e.g. "5 hours"). Durations can be negative. Times and durations have identical representations: {{{ int32 sec int32 nsec }}} Time cannot be negative, while durations can hold both positive and negative values (represented by negative `sec`; `nsec` is always non-negative). Beware that negative durations interpret `sec` and `nsec` so that `float_time = sec + nsec * 10e-9`, so e.g. a duration instance with `sec = -1, nsec = 5e8` represents a duration of `-0.5 seconds` and not `-1.5 seconds`. ROS has the ability to setup a simulated [[Clock]] for nodes. Instead of using platform time routines, you should use roscpp's time routines for accessing the current time, which will work seamlessly with simulated [[Clock]] time as well as wall-clock time. === Getting the Current Time === `ros::Time::now()` Get the current time as a `ros::Time` instance: {{{ #!cplusplus ros::Time begin = ros::Time::now(); }}} ==== Time zero ==== When using simulated [[Clock]] time, `now()` returns time `0` until first message has been received on `/clock`, so `0` means essentially that the client does not know clock time yet. A value of `0` should therefore be treated differently, such as looping over `now()` until non-zero is returned. === Creating Time and Duration Instances === You can create a `Time` or `Duration` to a specific value as well, either floating-point seconds: {{{ #!cplusplus ros::Time a_little_after_the_beginning(0.001); ros::Duration five_seconds(5.0); }}} or through the two-integer constructor: {{{ #!cplusplus ros::Time a_little_after_the_beginning(0, 1000000); ros::Duration five_seconds(5, 0); }}} === Converting Time and Duration Instances === `Time` and `Duration` objects can also be turned into floating point seconds: {{{ #!cplusplus double secs =ros::Time::now().toSec(); ros::Duration d(0.5); secs = d.toSec(); }}} === Time and Duration Arithmetic === Like other primitive types, you can perform arithmetic operations on `Time`s and `Duration`s. People are often initially confused on what arithmetic with these instances is like, so it's good to run through some examples: 1 hour + 1 hour = 2 hours (''duration + duration = duration'') 2 hours - 1 hour = 1 hour (''duration - duration = duration'') Today + 1 day = tomorrow (''time + duration = time'') Today - tomorrow = -1 day (''time - time = duration'') Today + tomorrow = ''error'' (''time + time is undefined'') Arithmetic with `Time` and `Duration` instances is similar to the above examples: {{{#!cplusplus ros::Duration two_hours = ros::Duration(60*60) + ros::Duration(60*60); ros::Duration one_hour = ros::Duration(2*60*60) - ros::Duration(60*60); ros::Time tomorrow = ros::Time::now() + ros::Duration(24*60*60); ros::Duration negative_one_day = ros::Time::now() - tomorrow; }}} == Sleeping and Rates == `bool ros::Duration::sleep()` Sleep for the amount of time specified by the duration: {{{#!cplusplus ros::Duration(0.5).sleep(); // sleep for half a second }}} `ros::Rate` roslib provides a `ros::Rate` convenience class which makes a best effort at maintaining a particular rate for a loop. For example: {{{ ros::Rate r(10); // 10 hz while (ros::ok()) { ... do some work ... r.sleep(); } }}} In the above example, the `Rate` instance will attempt to keep the loop at 10hz by accounting for the time used by the work done during the loop. '''Note:''' It is generally recommended to use `Timer`s instead of `Rate`. See the [[roscpp_tutorials/Tutorials/Timers|Timers Tutorial]] for details. == Wall Time == For cases where you want access to the actual wall-clock time even if running inside simulation, roslib provides `Wall` versions of all its time constructs, i.e. `ros::WallTime`, `ros::WallDuration`, and `ros::WallRate` which have identical interfaces to `ros::Time`, `ros::Duration`, and `ros::Rate` respectively.