1   
  2   
  3   
  4   
  5   
  6   
  7   
  8   
  9   
 10   
 11   
 12   
 13   
 14   
 15   
 16   
 17   
 18   
 19   
 20   
 21   
 22   
 23   
 24   
 25   
 26   
 27   
 28   
 29   
 30   
 31   
 32   
 33   
 34   
 35  """ 
 36  ROS time and duration representations, as well as internal routines 
 37  for managing wallclock versus a simulated clock.  The important data 
 38  classes are L{Time} and L{Duration}, which represent the ROS 'time' 
 39  and 'duration' primitives, respectively. 
 40  """ 
 41   
 42  import sys 
 43  import threading 
 44  import time 
 45  import traceback 
 46   
 47  import rospy.exceptions 
 48   
 49  import genpy 
 50   
 51   
 52   
 53   
 54  _rostime_initialized = False 
 55  _rostime_current = None 
 56  _rostime_cond = threading.Condition() 
 60      """ 
 61      Duration represents the ROS 'duration' primitive type, which 
 62      consists of two integers: seconds and nanoseconds. The Duration 
 63      class allows you to add and subtract Duration instances, including 
 64      adding and subtracting from L{Time} instances. 
 65   
 66      Usage:: 
 67        five_seconds = Duration(5) 
 68        five_nanoseconds = Duration(0, 5) 
 69   
 70        print 'Fields are', five_seconds.secs, five_seconds.nsecs 
 71   
 72        # Duration arithmetic 
 73        ten_seconds = five_seconds + five_seconds 
 74        five_secs_ago = rospy.Time.now() - five_seconds # Time minus Duration is a Time 
 75   
 76        true_val = ten_second > five_seconds 
 77      """ 
 78      __slots__ = [] 
 79   
 81          """ 
 82          Create new Duration instance. secs and nsecs are integers and 
 83          correspond to the ROS 'duration' primitive type. 
 84   
 85          @param secs: seconds 
 86          @type  secs: int 
 87          @param nsecs: nanoseconds 
 88          @type  nsecs: int 
 89          """ 
 90          genpy.Duration.__init__(self, secs, nsecs) 
   91   
 92 -class Time(genpy.Time): 
  93      """ 
 94      Time represents the ROS 'time' primitive type, which consists of two 
 95      integers: seconds since epoch and nanoseconds since seconds. Time 
 96      instances are mutable. 
 97   
 98      The L{Time.now()} factory method can initialize Time to the 
 99      current ROS time and L{from_sec()} can be used to create a 
100      Time instance from the Python's time.time() float seconds 
101      representation. 
102   
103      The Time class allows you to subtract Time instances to compute 
104      Durations, as well as add Durations to Time to create new Time 
105      instances. 
106   
107      Usage:: 
108        now = rospy.Time.now() 
109        zero_time = rospy.Time() 
110   
111        print 'Fields are', now.secs, now.nsecs 
112   
113        # Time arithmetic 
114        five_secs_ago = now - rospy.Duration(5) # Time minus Duration is a Time 
115        five_seconds  = now - five_secs_ago  # Time minus Time is a Duration 
116        true_val = now > five_secs_ago 
117   
118        # NOTE: in general, you will want to avoid using time.time() in ROS code 
119        import time 
120        py_time = rospy.Time.from_sec(time.time()) 
121      """ 
122      __slots__ = []     
123   
125          """ 
126          Constructor: secs and nsecs are integers and correspond to the 
127          ROS 'time' primitive type. You may prefer to use the static 
128          L{from_sec()} and L{now()} factory methods instead. 
129           
130          @param secs: seconds since epoch 
131          @type  secs: int 
132          @param nsecs: nanoseconds since seconds (since epoch) 
133          @type  nsecs: int 
134          """ 
135          genpy.Time.__init__(self, secs, nsecs) 
 136           
137      @staticmethod 
139          """ 
140          Create new L{Time} instance representing current time. This 
141          can either be wall-clock time or a simulated clock. It is 
142          strongly recommended that you use the now() factory to create 
143          current time representations instead of reading wall-clock 
144          time and create Time instances from it. 
145           
146          @return: L{Time} instance for current time 
147          @rtype: L{Time} 
148          """ 
149          return get_rostime() 
 150   
151       
152       
154          """ 
155          Use Time.from_sec() instead. Retained for backwards compatibility. 
156           
157          @param float_secs: time value in time.time() format 
158          @type  float_secs: float 
159          @return: Time instance for specified time 
160          @rtype: L{Time} 
161          """ 
162          return Time.from_sec(float_secs) 
 163       
164      from_seconds = staticmethod(from_seconds) 
165   
167          """ 
168          Create new Time instance from a float seconds representation 
169          (e.g. time.time()). 
170           
171          @param float_secs: time value in time.time() format 
172          @type  float_secs: float 
173          @return: Time instance for specified time 
174          @rtype: L{Time} 
175          """ 
176          secs = int(float_secs) 
177          nsecs = int((float_secs - secs) * 1000000000) 
178          return Time(secs, nsecs) 
 179       
180      from_sec = staticmethod(from_sec) 
 181       
195       
197      """ 
198      Get the current time as a L{Time} object     
199      @return: current time as a L{rospy.Time} object 
200      @rtype: L{Time} 
201      """ 
202      if not _rostime_initialized: 
203          raise rospy.exceptions.ROSInitException("time is not initialized. Have you called init_node()?") 
204      if _rostime_current is not None: 
205           
206          return _rostime_current 
207      else: 
208           
209          float_secs = time.time() 
210          secs = int(float_secs) 
211          nsecs = int((float_secs - secs) * 1000000000) 
212          return Time(secs, nsecs) 
 213   
215      """ 
216      Get the current time as float secs (time.time() format) 
217      @return: time in secs (time.time() format)     
218      @rtype: float 
219      """ 
220      return Time.now().to_sec() 
 221   
223      """ 
224      Internal use. 
225      Mark rostime as initialized. This flag enables other routines to 
226      throw exceptions if rostime is being used before the underlying 
227      system is initialized. 
228      @param val: value for initialization state 
229      @type  val: bool 
230      """ 
231      global _rostime_initialized 
232      _rostime_initialized = val 
 233   
235      """ 
236      Internal use. 
237      @return: True if rostime has been initialized 
238      @rtype: bool 
239      """ 
240      return _rostime_initialized     
 241   
243      """ 
244      internal API for helper routines that need to wait on time updates 
245      @return: rostime conditional var 
246      @rtype: threading.Cond 
247      """ 
248      return _rostime_cond 
 249   
251      """ 
252      Internal use for ROS-time routines. 
253      @return: True if ROS is currently using wallclock time 
254      @rtype: bool 
255      """ 
256      return _rostime_current == None 
 257       
270   
272      """ 
273      Internal use. 
274      Windows interrupts time.sleep with an IOError exception 
275      when a signal is caught. Even when the signal is handled 
276      by a callback, it will then proceed to throw IOError when 
277      the handling has completed.  
278   
279      Refer to https://code.ros.org/trac/ros/ticket/3421. 
280   
281      So we create a platform dependant wrapper to handle this 
282      here. 
283      """ 
284      if sys.platform in ['win32']:  
285          try: 
286              time.sleep(duration) 
287          except IOError: 
288              pass 
289      else: 
290          time.sleep(duration) 
 291