rostime.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2008, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 
00033 """
00034 ROS Time representation, including Duration
00035 """
00036 
00037 import sys
00038 
00039 if sys.version > '3': 
00040     long = int
00041 
00042 def _canon(secs, nsecs):
00043     #canonical form: nsecs is always positive, nsecs < 1 second
00044     while nsecs >= 1000000000:
00045         secs += 1
00046         nsecs -= 1000000000
00047     while nsecs < 0:
00048         secs -= 1
00049         nsecs += 1000000000
00050     return secs,nsecs
00051 
00052 class TVal(object):
00053     """
00054     Base class of :class:`Time` and :class:`Duration` representations. Representation
00055     is secs+nanoseconds since epoch.
00056     """
00057 
00058     __slots__ = ['secs', 'nsecs']
00059 
00060     # mimic same API as messages when being introspected
00061     _slot_types = ['int32', 'int32']
00062 
00063     def __init__(self, secs=0, nsecs=0):
00064         """
00065         :param secs: seconds. If secs is a float, then nsecs must not be set or 0,
00066           larger seconds will be of type long on 32-bit systems, ``int/long/float``
00067         :param nsecs: nanoseconds, ``int``
00068         """
00069         if type(secs) != int and type(secs) != long:
00070             # float secs constructor
00071             if nsecs != 0:
00072                 raise ValueError("if secs is a float, nsecs cannot be set")
00073             float_secs = secs
00074             secs = int(float_secs)
00075             nsecs = int((float_secs - secs) * 1000000000)
00076 
00077         self.secs, self.nsecs = _canon(secs, nsecs)
00078 
00079     def is_zero(self):
00080         """
00081         :returns: ``True`` if time is zero (secs and nsecs are zero), ``bool``
00082         """
00083         return self.secs == 0 and self.nsecs == 0
00084     
00085     def set(self, secs, nsecs):
00086         """
00087         Set time using separate secs and nsecs values
00088         
00089         :param secs: seconds since epoch, ``int``
00090         :param nsecs: nanoseconds since seconds, ``int``
00091         """
00092         self.secs = secs
00093         self.nsecs = nsecs
00094 
00095     def canon(self):
00096         """
00097         Canonicalize the field representation in this instance.  should
00098         only be used when manually setting secs/nsecs slot values, as
00099         in deserialization.
00100         """
00101         self.secs, self.nsecs = _canon(self.secs, self.nsecs)
00102         
00103     def to_sec(self):
00104         """
00105         :returns: time as float seconds (same as time.time() representation), ``float``
00106         """
00107         return float(self.secs) + float(self.nsecs) / 1e9
00108 
00109     def to_nsec(self):
00110         """
00111         :returns: time as nanoseconds, ``long``
00112         """
00113         return self.secs * long(1e9) + self.nsecs
00114         
00115     def __hash__(self):
00116         """
00117         Time values are hashable. Time values with identical fields have the same hash.
00118         """
00119         return ("%s.%s"%(self.secs, self.nsecs)) .__hash__()
00120 
00121     def __str__(self):
00122         return str(self.to_nsec())
00123 
00124     def __repr__(self):
00125         return "genpy.TVal[%d]"%self.to_nsec()
00126 
00127     def __bool__(self):
00128         """
00129         Return if time value is not zero
00130         """
00131         return self.secs != 0 or self.nsecs != 0
00132 
00133     def __nonzero__(self):
00134         """
00135         Check if time value is not zero
00136         """
00137         return self.secs or self.nsecs
00138 
00139     def __lt__(self, other):
00140         """
00141         < test for time values
00142         """
00143         try:
00144             return self.__cmp__(other) < 0
00145         except TypeError:
00146             return NotImplemented
00147     def __le__(self, other):
00148         """
00149         <= test for time values
00150         """
00151         try:
00152             return self.__cmp__(other) <= 0
00153         except TypeError:
00154             return NotImplemented
00155     def __gt__(self, other):
00156         """
00157         > test for time values
00158         """
00159         try:
00160             return self.__cmp__(other) > 0
00161         except TypeError:
00162             return NotImplemented
00163     def __ge__(self, other):
00164         """
00165         >= test for time values
00166         """
00167         try:
00168             return self.__cmp__(other) >= 0
00169         except TypeError:
00170             return NotImplemented
00171     def __ne__(self, other):
00172         return not self.__eq__(other)
00173     def __cmp__(self, other):
00174         if not isinstance(other, TVal):
00175             raise TypeError("Cannot compare to non-TVal")
00176         nanos = self.to_nsec() - other.to_nsec()
00177         if nanos > 0:
00178             return 1
00179         if nanos == 0:
00180             return 0
00181         return -1
00182     def __eq__(self, other):
00183         if not isinstance(other, TVal):
00184             return False
00185         return self.to_nsec() == other.to_nsec()
00186 
00187 class Time(TVal):
00188     """
00189     Time contains the ROS-wide 'time' primitive representation, which
00190     consists of two integers: seconds since epoch and nanoseconds since
00191     seconds. Time instances are mutable.
00192     """
00193     __slots__ = ['secs', 'nsecs']
00194     def __init__(self, secs=0, nsecs=0):
00195         """
00196         Constructor: secs and nsecs are integers. You may prefer to use the static L{from_sec()} factory
00197         method instead.
00198         
00199         :param secs: seconds since epoch, ``int``
00200         :param nsecs: nanoseconds since seconds (since epoch), ``int``
00201         """
00202         super(Time, self).__init__(secs, nsecs)
00203         if self.secs < 0:
00204             raise TypeError("time values must be positive")
00205 
00206     def __getstate__(self):
00207         """
00208         support for Python pickling
00209         """
00210         return [self.secs, self.nsecs]
00211 
00212     def __setstate__(self, state):
00213         """
00214         support for Python pickling
00215         """
00216         self.secs, self.nsecs = state
00217 
00218     def from_sec(float_secs):
00219         """
00220         Create new Time instance using time.time() value (float
00221         seconds)
00222         
00223         :param float_secs: time value in time.time() format, ``float``
00224         :returns: :class:`Time` instance for specified time
00225         """
00226         secs = int(float_secs)
00227         nsecs = int((float_secs - secs) * 1000000000)
00228         return Time(secs, nsecs)
00229     
00230     from_sec = staticmethod(from_sec)    
00231 
00232     def to_time(self):
00233         """
00234         Get Time in time.time() format. alias of L{to_sec()}
00235         
00236         :returns: time in floating point secs (time.time() format), ``float``
00237         """
00238         return self.to_sec()
00239 
00240     def __repr__(self):
00241         return "genpy.Time[%d]"%self.to_nsec()
00242 
00243     def __add__(self, other):
00244         """
00245         Add duration to this time
00246         
00247         :param other: :class:`Duration`
00248         """
00249         if not isinstance(other, Duration):
00250             return NotImplemented
00251         return Time(self.secs + other.secs, self.nsecs + other.nsecs)
00252 
00253     def __sub__(self, other):
00254         """
00255         Subtract time or duration from this time
00256         :param other: :class:`Duration`/:class:`Time`
00257         :returns: :class:`Duration` if other is a :class:`Time`, :class:`Time` if other is a :class:`Duration`
00258         """
00259         if isinstance(other, Time):
00260             return Duration(self.secs - other.secs, self.nsecs - other.nsecs)
00261         elif isinstance(other, Duration):
00262             return Time(self.secs - other.secs, self.nsecs - other.nsecs)
00263         else:
00264             return NotImplemented
00265 
00266     def __cmp__(self, other):
00267         """
00268         Compare to another time
00269         :param other: :class:`Time`
00270         """
00271         if not isinstance(other, Time):
00272             raise TypeError("cannot compare to non-Time")
00273         nanos = self.to_nsec() - other.to_nsec()
00274         if nanos > 0:
00275             return 1
00276         if nanos == 0:
00277             return 0
00278         return -1
00279 
00280     def __eq__(self, other):
00281         """
00282         Equals test for Time. Comparison assumes that both time
00283         instances are in canonical representation; only compares fields.
00284         
00285         :param other: :class:`Time`
00286         """
00287         if not isinstance(other, Time):
00288             return False
00289         return self.secs == other.secs and self.nsecs == other.nsecs
00290 
00291     def __hash__(self):
00292         return super(Time, self).__hash__()
00293 
00294 class Duration(TVal):
00295     """
00296     Duration represents the ROS 'duration' primitive, which consists
00297     of two integers: seconds and nanoseconds. The Duration class
00298     allows you to add and subtract Duration instances, including
00299     adding and subtracting from :class:`Time` instances.
00300     """
00301     __slots__ = ['secs', 'nsecs']
00302     def __init__(self, secs=0, nsecs=0):
00303         """
00304         Create new Duration instance. secs and nsecs are integers and correspond to the ROS 'duration' primitive.
00305 
00306         :param secs: seconds, ``int``
00307         :param nsecs: nanoseconds, ``int``
00308         """
00309         super(Duration, self).__init__(secs, nsecs)
00310 
00311     def __getstate__(self):
00312         """
00313         support for Python pickling
00314         """
00315         return [self.secs, self.nsecs]
00316 
00317     def __setstate__(self, state):
00318         """
00319         support for Python pickling
00320         """
00321         self.secs, self.nsecs = state
00322 
00323     def __repr__(self):
00324         return "genpy.Duration[%d]"%self.to_nsec()
00325 
00326     def from_sec(float_seconds):
00327         """
00328         Create new Duration instance from float seconds format.
00329         
00330         :param float_seconds: time value in specified as float seconds, ``float``
00331         :returns: :class:`Duration` instance for specified float_seconds
00332         """
00333         secs = int(float_seconds)
00334         nsecs = int((float_seconds - secs) * 1000000000)
00335         return Duration(secs, nsecs)
00336     
00337     from_sec = staticmethod(from_sec)    
00338 
00339     def __neg__(self):
00340         """
00341         :returns: Negative value of this :class:`Duration`
00342         """
00343         return Duration(-self.secs, -self.nsecs)
00344     def __abs__(self):
00345         """
00346         Absolute value of this duration
00347         :returns: positive :class:`Duration`
00348         """
00349         if self.secs > 0:
00350             return self
00351         return self.__neg__()
00352 
00353     def __add__(self, other):
00354         """
00355         Add duration to this duration, or this duration to a time, creating a new time value as a result.
00356         :param other: duration or time, ``Duration``/``Time``
00357         :returns: :class:`Duration` if other is a :class:`Duration`
00358           instance, :class:`Time` if other is a :class:`Time`
00359         """
00360         if isinstance(other, Time):
00361             return other.__add__(self)
00362         elif isinstance(other, Duration):
00363             return Duration(self.secs+other.secs, self.nsecs+other.nsecs)
00364         else:
00365             return NotImplemented
00366     def __sub__(self, other):
00367         """
00368         Subtract duration from this duration, returning a new duration
00369         :param other: duration
00370         :returns: :class:`Duration`
00371         """
00372         if not isinstance(other, Duration):
00373             return NotImplemented
00374         return Duration(self.secs-other.secs, self.nsecs-other.nsecs)        
00375 
00376     def __mul__(self, val):
00377         """
00378         Multiply this duration by an integer or float
00379         :param val: multiplication factor, ``int/float``
00380         :returns: :class:`Duration` multiplied by val
00381         """
00382         t = type(val)
00383         if t in (int, long):
00384             return Duration(self.secs * val, self.nsecs * val)
00385         elif t == float:
00386             return Duration.from_sec(self.to_sec() * val)
00387         else:
00388             return NotImplemented
00389 
00390     def __floordiv__(self, val):
00391         """
00392         Floor divide this duration by an integer or float
00393         :param val: division factor, ``int/float``
00394         :returns: :class:`Duration` divided by val
00395         """
00396         t = type(val)
00397         if t in (int, long):
00398             return Duration(self.secs // val, self.nsecs // val)
00399         elif t == float:
00400             return Duration.from_sec(self.to_sec() // val)
00401         else:
00402             return NotImplemented
00403 
00404     def __div__(self, val):
00405         """
00406         Divide this duration by an integer or float
00407         :param val: division factor, ``int/float``
00408         :returns: :class:`Duration` divided by val
00409         """
00410         # unlike __floordiv__, this uses true div for float arg.
00411         # PEP 238
00412         t = type(val)
00413         if t in (int, long):
00414             return Duration(self.secs // val, self.nsecs // val)
00415         elif t == float:
00416             return Duration.from_sec(self.to_sec() / val)
00417         else:
00418             return NotImplemented
00419 
00420     def __truediv__(self, val):
00421         """
00422         Divide this duration by an integer or float
00423         :param val: division factor, ``int/float``
00424         :returns: :class:`Duration` multiplied by val
00425         """
00426         if type(val) in (int, long, float):
00427             return Duration.from_sec(self.to_sec() / val)
00428         else:
00429             return NotImplemented
00430 
00431     def __cmp__(self, other):
00432         if not isinstance(other, Duration):
00433             raise TypeError("Cannot compare to non-Duration")
00434         nanos = self.to_nsec() - other.to_nsec()
00435         if nanos > 0:
00436             return 1
00437         if nanos == 0:
00438             return 0
00439         return -1
00440 
00441     def __eq__(self, other):
00442         if not isinstance(other, Duration):
00443             return False
00444         return self.secs == other.secs and self.nsecs == other.nsecs
00445 
00446     def __hash__(self):
00447         return super(Duration, self).__hash__()


firos
Author(s): IƱigo Gonzalez, igonzalez@ikergune.com
autogenerated on Thu Jun 6 2019 17:51:04