Module roslua.time
Time utility class for roslua. This module provides the Time class. It uses the local clock or the /clock topic depending whether simulation time has been initialized or not.
Copyright© Tim Niemueller, Carnegie Mellon University, Intel Research Pittsburgh
Release: Released under BSD license
Functions
Duration.__add (d1, d2) | Add the given durations d1 and d2. |
Duration.__eq (d1, d2) | Check if durations equal. |
Duration.__gt (d1, d2) | Check if d1 is greater than d2. |
Duration.__lt (d1, d2) | Check if d1 is less than d2. |
Duration.__sub (d1, d2) | Subtract d2 from d1. |
Duration.__tostring (t) | Convert duration to string. |
Duration.from_message_array (a) | Create Time from message array. |
Duration.from_sec (sec) | Create Time from seconds. |
Duration.is_instance (t) | Check if given table is an instance of Time. |
Duration:clone (time) | Clone an instance (copy constructor). |
Duration:is_zero () | Check if time is zero. |
Duration:new (sec, nsec) | Contructor. |
Duration:set (sec, nsec) | Set sec and nsec values. |
Duration:to_sec () | Convert duration to seconds. |
Time.__add (t1, t2) | Add the given times t1 and t2. |
Time.__eq (t1, t2) | Check if times equal. |
Time.__gt (t1, t2) | Check if t1 is greater than t2. |
Time.__lt (t1, t2) | Check if t1 is less than t2. |
Time.__sub (t1, t2) | Subtract t2 from t1. |
Time.__tostring (t) | Convert time to string. |
Time.from_message_array (a) | Create Time from message array. |
Time.from_sec (sec) | Create Time from seconds. |
Time.is_instance (t) | Check if given table is an instance of Time. |
Time.now () | Get current time. |
Time:clone (time) | Clone an instance (copy constructor). |
Time:format (format) | Format time as string. |
Time:is_zero () | Check if time is zero. |
Time:new (sec, nsec) | Contructor. |
Time:set (sec, nsec) | Set sec and nsec values. |
Time:stamp () | Set to current time. |
Time:to_sec () | Convert time to seconds. |
init_simtime () | Initialize simulation time. |
simtime_update (message) | Local function called on simtime updates, i.e. |
Functions
- Duration.__add (d1, d2)
-
Add the given durations d1 and d2.
Parameters
- d1: first duration to add
- d2: second duration to add
Return value:
new duration instance with the sum of d1 and d2 - Duration.__eq (d1, d2)
-
Check if durations equal.
Parameters
- d1: first duration to compare
- d2: second duration to compare
Return value:
true if d1 == d2, false otherwise - Duration.__gt (d1, d2)
-
Check if d1 is greater than d2.
Parameters
- d1: first duration to compare
- d2: second duration to compare
Return value:
true if d1 > d2, false otherwise - Duration.__lt (d1, d2)
-
Check if d1 is less than d2.
Parameters
- d1: first duration to compare
- d2: second duration to compare
Return value:
true if d1 < d2, false otherwise - Duration.__sub (d1, d2)
-
Subtract d2 from d1.
Parameters
- d1: duration to subtract from
- d2: duration to subtract
Return value:
new duration instance for the result of d1 - d2 - Duration.__tostring (t)
-
Convert duration to string.
Parameters
- t: duration to convert
Return value:
string representing this duration - Duration.from_message_array (a)
-
Create Time from message array.
Parameters
- a: array that contains two entries, index 1 must be seconds, index 2 must be nano seconds.
Return value:
new instance for the given time - Duration.from_sec (sec)
-
Create Time from seconds.
Parameters
- sec: seconds since the epoch as a floating point number, the fraction is converted internally to nanoseconds
Return value:
new instance for the given time - Duration.is_instance (t)
-
Check if given table is an instance of Time.
Parameters
- t: instance to check
Return value:
true if given object t is an instance of Time - Duration:clone (time)
-
Clone an instance (copy constructor).
Parameters
- time: Time instance to clone
Return value:
new instances for the same time as the given one - Duration:is_zero ()
-
Check if time is zero.
Return value:
true if sec and nsec fields are zero, false otherwise - Duration:new (sec, nsec)
-
Contructor.
Parameters
- sec: seconds, 0 if not supplied
- nsec: nano seconds, 0 if not supploed
Return value:
new Time instance - Duration:set (sec, nsec)
-
Set sec and nsec values.
Parameters
- sec: new seconds value
- nsec: new nano seconds value
- Duration:to_sec ()
-
Convert duration to seconds.
Return value:
floating point number in seconds. - Time.__add (t1, t2)
-
Add the given times t1 and t2.
Parameters
- t1: first time to add
- t2: second time or duration to add
Return value:
new time instance with the sum of t1 and t2 - Time.__eq (t1, t2)
-
Check if times equal.
Parameters
- t1: first time to compare
- t2: second time to compare
Return value:
true if t1 == t2, false otherwise - Time.__gt (t1, t2)
-
Check if t1 is greater than t2.
Parameters
- t1: first time to compare
- t2: second time to compare
Return value:
true if t1 > t2, false otherwise - Time.__lt (t1, t2)
-
Check if t1 is less than t2.
Parameters
- t1: first time to compare
- t2: second time to compare
Return value:
true if t1 < t2, false otherwise - Time.__sub (t1, t2)
-
Subtract t2 from t1.
Parameters
- t1: time to subtract from
- t2: time or duration to subtract
Return value:
new time instance for the result of t1 - t2 - Time.__tostring (t)
-
Convert time to string.
Parameters
- t: time to convert
Return value:
string representing this time - Time.from_message_array (a)
-
Create Time from message array.
Parameters
- a: array that contains two entries, index 1 must be seconds, index 2 must be nano seconds.
Return value:
new instance for the given time - Time.from_sec (sec)
-
Create Time from seconds.
Parameters
- sec: seconds since the epoch as a floating point number, the fraction is converted internally to nanoseconds
Return value:
new instance for the given time - Time.is_instance (t)
-
Check if given table is an instance of Time.
Parameters
- t: instance to check
Return value:
true if given object t is an instance of Time - Time.now ()
-
Get current time.
Return value:
new Time instance set to the current time - Time:clone (time)
-
Clone an instance (copy constructor).
Parameters
- time: Time instance to clone
Return value:
new instances for the same time as the given one - Time:format (format)
-
Format time as string.
Parameters
- format: format string, cf. documentation of your system's strftime
Return value:
string representation of this time given the supplied format - Time:is_zero ()
-
Check if time is zero.
Return value:
true if sec and nsec fields are zero, false otherwise - Time:new (sec, nsec)
-
Contructor.
Parameters
- sec: seconds, 0 if not supplied
- nsec: nano seconds, 0 if not supploed
Return value:
new Time instance - Time:set (sec, nsec)
-
Set sec and nsec values.
Parameters
- sec: new seconds value
- nsec: new nano seconds value
- Time:stamp ()
- Set to current time.
- Time:to_sec ()
-
Convert time to seconds.
Return value:
floating point number in seconds. - init_simtime ()
- Initialize simulation time. This initializes the simulation time by subscribing to the /clock topic. This function is called automatically from roslua.init_node() if required, so you should not call this function directly.
- simtime_update (message)
-
Local function called on simtime updates, i.e. new messages for /clock.
Parameters
- message: new Clock message