_GpsInfo.py
Go to the documentation of this file.
00001 """autogenerated by genpy from art_msgs/GpsInfo.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006 
00007 import std_msgs.msg
00008 
00009 class GpsInfo(genpy.Message):
00010   _md5sum = "4f5e197f8744c1a11f1c94dc6e9a77a6"
00011   _type = "art_msgs/GpsInfo"
00012   _has_header = True #flag to mark the presence of a Header object
00013   _full_text = """# GPS position message
00014 #
00015 # Probably to be replaced by a standard ROS message for Diamondback.
00016 
00017 # $Id: GpsInfo.msg 604 2010-09-22 15:50:16Z jack.oquin $
00018 
00019 # standard ROS header, includes time stamp
00020 Header header
00021 
00022 # Latitude in degrees.  Positive is north of equator, negative is
00023 # south of equator.
00024 float64 latitude
00025 
00026 # Longitude in degrees.  Positive is east of prime meridian, negative
00027 # is west of prime meridian.
00028 float64 longitude
00029 
00030 # Altitude, in meters.  Positive is above reference (e.g., sea-level),
00031 # and negative is below.
00032 float64 altitude
00033 
00034 # UTM WGS84 coordinates, easting [m]
00035 float64 utm_e
00036 
00037 # UTM WGS84 coordinates, northing [m]
00038 float64 utm_n
00039 
00040 # UTM zone
00041 string zone
00042 
00043 # Horizontal dilution of position (HDOP)
00044 float64 hdop
00045 
00046 # Vertical dilution of position (VDOP)
00047 float64 vdop
00048 
00049 # Horizonal error [m]
00050 float64 err_horz
00051 
00052 # Vertical error [m]
00053 float64 err_vert
00054 
00055 # Quality of fix 0 = invalid, 1 = GPS fix, 2 = Differential GPS fix
00056 uint16 INVALID_FIX = 0
00057 uint16 GPS_FIX = 1
00058 uint16 DGPS_FIX = 2
00059 uint16 quality
00060 
00061 # Number of satellites in view.
00062 uint16 num_sats
00063 
00064 ================================================================================
00065 MSG: std_msgs/Header
00066 # Standard metadata for higher-level stamped data types.
00067 # This is generally used to communicate timestamped data 
00068 # in a particular coordinate frame.
00069 # 
00070 # sequence ID: consecutively increasing ID 
00071 uint32 seq
00072 #Two-integer timestamp that is expressed as:
00073 # * stamp.secs: seconds (stamp_secs) since epoch
00074 # * stamp.nsecs: nanoseconds since stamp_secs
00075 # time-handling sugar is provided by the client library
00076 time stamp
00077 #Frame this data is associated with
00078 # 0: no frame
00079 # 1: global frame
00080 string frame_id
00081 
00082 """
00083   # Pseudo-constants
00084   INVALID_FIX = 0
00085   GPS_FIX = 1
00086   DGPS_FIX = 2
00087 
00088   __slots__ = ['header','latitude','longitude','altitude','utm_e','utm_n','zone','hdop','vdop','err_horz','err_vert','quality','num_sats']
00089   _slot_types = ['std_msgs/Header','float64','float64','float64','float64','float64','string','float64','float64','float64','float64','uint16','uint16']
00090 
00091   def __init__(self, *args, **kwds):
00092     """
00093     Constructor. Any message fields that are implicitly/explicitly
00094     set to None will be assigned a default value. The recommend
00095     use is keyword arguments as this is more robust to future message
00096     changes.  You cannot mix in-order arguments and keyword arguments.
00097 
00098     The available fields are:
00099        header,latitude,longitude,altitude,utm_e,utm_n,zone,hdop,vdop,err_horz,err_vert,quality,num_sats
00100 
00101     :param args: complete set of field values, in .msg order
00102     :param kwds: use keyword arguments corresponding to message field names
00103     to set specific fields.
00104     """
00105     if args or kwds:
00106       super(GpsInfo, self).__init__(*args, **kwds)
00107       #message fields cannot be None, assign default values for those that are
00108       if self.header is None:
00109         self.header = std_msgs.msg.Header()
00110       if self.latitude is None:
00111         self.latitude = 0.
00112       if self.longitude is None:
00113         self.longitude = 0.
00114       if self.altitude is None:
00115         self.altitude = 0.
00116       if self.utm_e is None:
00117         self.utm_e = 0.
00118       if self.utm_n is None:
00119         self.utm_n = 0.
00120       if self.zone is None:
00121         self.zone = ''
00122       if self.hdop is None:
00123         self.hdop = 0.
00124       if self.vdop is None:
00125         self.vdop = 0.
00126       if self.err_horz is None:
00127         self.err_horz = 0.
00128       if self.err_vert is None:
00129         self.err_vert = 0.
00130       if self.quality is None:
00131         self.quality = 0
00132       if self.num_sats is None:
00133         self.num_sats = 0
00134     else:
00135       self.header = std_msgs.msg.Header()
00136       self.latitude = 0.
00137       self.longitude = 0.
00138       self.altitude = 0.
00139       self.utm_e = 0.
00140       self.utm_n = 0.
00141       self.zone = ''
00142       self.hdop = 0.
00143       self.vdop = 0.
00144       self.err_horz = 0.
00145       self.err_vert = 0.
00146       self.quality = 0
00147       self.num_sats = 0
00148 
00149   def _get_types(self):
00150     """
00151     internal API method
00152     """
00153     return self._slot_types
00154 
00155   def serialize(self, buff):
00156     """
00157     serialize message into buffer
00158     :param buff: buffer, ``StringIO``
00159     """
00160     try:
00161       _x = self
00162       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00163       _x = self.header.frame_id
00164       length = len(_x)
00165       if python3 or type(_x) == unicode:
00166         _x = _x.encode('utf-8')
00167         length = len(_x)
00168       buff.write(struct.pack('<I%ss'%length, length, _x))
00169       _x = self
00170       buff.write(_struct_5d.pack(_x.latitude, _x.longitude, _x.altitude, _x.utm_e, _x.utm_n))
00171       _x = self.zone
00172       length = len(_x)
00173       if python3 or type(_x) == unicode:
00174         _x = _x.encode('utf-8')
00175         length = len(_x)
00176       buff.write(struct.pack('<I%ss'%length, length, _x))
00177       _x = self
00178       buff.write(_struct_4d2H.pack(_x.hdop, _x.vdop, _x.err_horz, _x.err_vert, _x.quality, _x.num_sats))
00179     except struct.error as se: self._check_types(se)
00180     except TypeError as te: self._check_types(te)
00181 
00182   def deserialize(self, str):
00183     """
00184     unpack serialized message in str into this message instance
00185     :param str: byte array of serialized message, ``str``
00186     """
00187     try:
00188       if self.header is None:
00189         self.header = std_msgs.msg.Header()
00190       end = 0
00191       _x = self
00192       start = end
00193       end += 12
00194       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00195       start = end
00196       end += 4
00197       (length,) = _struct_I.unpack(str[start:end])
00198       start = end
00199       end += length
00200       if python3:
00201         self.header.frame_id = str[start:end].decode('utf-8')
00202       else:
00203         self.header.frame_id = str[start:end]
00204       _x = self
00205       start = end
00206       end += 40
00207       (_x.latitude, _x.longitude, _x.altitude, _x.utm_e, _x.utm_n,) = _struct_5d.unpack(str[start:end])
00208       start = end
00209       end += 4
00210       (length,) = _struct_I.unpack(str[start:end])
00211       start = end
00212       end += length
00213       if python3:
00214         self.zone = str[start:end].decode('utf-8')
00215       else:
00216         self.zone = str[start:end]
00217       _x = self
00218       start = end
00219       end += 36
00220       (_x.hdop, _x.vdop, _x.err_horz, _x.err_vert, _x.quality, _x.num_sats,) = _struct_4d2H.unpack(str[start:end])
00221       return self
00222     except struct.error as e:
00223       raise genpy.DeserializationError(e) #most likely buffer underfill
00224 
00225 
00226   def serialize_numpy(self, buff, numpy):
00227     """
00228     serialize message with numpy array types into buffer
00229     :param buff: buffer, ``StringIO``
00230     :param numpy: numpy python module
00231     """
00232     try:
00233       _x = self
00234       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00235       _x = self.header.frame_id
00236       length = len(_x)
00237       if python3 or type(_x) == unicode:
00238         _x = _x.encode('utf-8')
00239         length = len(_x)
00240       buff.write(struct.pack('<I%ss'%length, length, _x))
00241       _x = self
00242       buff.write(_struct_5d.pack(_x.latitude, _x.longitude, _x.altitude, _x.utm_e, _x.utm_n))
00243       _x = self.zone
00244       length = len(_x)
00245       if python3 or type(_x) == unicode:
00246         _x = _x.encode('utf-8')
00247         length = len(_x)
00248       buff.write(struct.pack('<I%ss'%length, length, _x))
00249       _x = self
00250       buff.write(_struct_4d2H.pack(_x.hdop, _x.vdop, _x.err_horz, _x.err_vert, _x.quality, _x.num_sats))
00251     except struct.error as se: self._check_types(se)
00252     except TypeError as te: self._check_types(te)
00253 
00254   def deserialize_numpy(self, str, numpy):
00255     """
00256     unpack serialized message in str into this message instance using numpy for array types
00257     :param str: byte array of serialized message, ``str``
00258     :param numpy: numpy python module
00259     """
00260     try:
00261       if self.header is None:
00262         self.header = std_msgs.msg.Header()
00263       end = 0
00264       _x = self
00265       start = end
00266       end += 12
00267       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00268       start = end
00269       end += 4
00270       (length,) = _struct_I.unpack(str[start:end])
00271       start = end
00272       end += length
00273       if python3:
00274         self.header.frame_id = str[start:end].decode('utf-8')
00275       else:
00276         self.header.frame_id = str[start:end]
00277       _x = self
00278       start = end
00279       end += 40
00280       (_x.latitude, _x.longitude, _x.altitude, _x.utm_e, _x.utm_n,) = _struct_5d.unpack(str[start:end])
00281       start = end
00282       end += 4
00283       (length,) = _struct_I.unpack(str[start:end])
00284       start = end
00285       end += length
00286       if python3:
00287         self.zone = str[start:end].decode('utf-8')
00288       else:
00289         self.zone = str[start:end]
00290       _x = self
00291       start = end
00292       end += 36
00293       (_x.hdop, _x.vdop, _x.err_horz, _x.err_vert, _x.quality, _x.num_sats,) = _struct_4d2H.unpack(str[start:end])
00294       return self
00295     except struct.error as e:
00296       raise genpy.DeserializationError(e) #most likely buffer underfill
00297 
00298 _struct_I = genpy.struct_I
00299 _struct_5d = struct.Struct("<5d")
00300 _struct_3I = struct.Struct("<3I")
00301 _struct_4d2H = struct.Struct("<4d2H")
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


art_msgs
Author(s): Jack O'Quin
autogenerated on Tue Sep 24 2013 10:40:45