00001 """autogenerated by genmsg_py from GPSFix.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004 
00005 import clearpath_sensors.msg
00006 import std_msgs.msg
00007 
00008 class GPSFix(roslib.message.Message):
00009   _md5sum = "3db3d0a7bc53054c67c528af84710b70"
00010   _type = "clearpath_sensors/GPSFix"
00011   _has_header = True 
00012   _full_text = """# A more complete GPS fix to supplement sensor_msgs/NavSatFix.
00013 Header header
00014 
00015 GPSStatus status
00016 
00017 # Latitude (degrees). Positive is north of equator; negative is south.
00018 float64 latitude
00019 
00020 # Longitude (degrees). Positive is east of prime meridian, negative west.
00021 float64 longitude
00022 
00023 # Altitude (meters). Positive is above reference (e.g., sea level).
00024 float64 altitude
00025 
00026 # Direction (degrees from north)
00027 float64 track
00028 
00029 # Ground speed (meters/second)
00030 float64 speed
00031 
00032 # Vertical speed (meters/second)
00033 float64 climb
00034 
00035 # Device orientation (units in degrees)
00036 float64 pitch
00037 float64 roll
00038 float64 dip
00039 
00040 # GPS time
00041 float64 time
00042 
00043 ## Dilution of precision; Xdop<=0 means the value is unknown
00044 
00045 # Total (positional-temporal) dilution of precision
00046 float64 gdop
00047 
00048 # Positional (3D) dilution of precision
00049 float64 pdop
00050 
00051 # Horizontal dilution of precision
00052 float64 hdop
00053 
00054 # Vertical dilution of precision
00055 float64 vdop
00056 
00057 # Temporal dilution of precision
00058 float64 tdop
00059 
00060 ## Uncertainty of measurement, 95% confidence
00061 
00062 # Spherical position uncertainty (meters) [epe]
00063 float64 err
00064 
00065 # Horizontal position uncertainty (meters) [eph]
00066 float64 err_horz
00067 
00068 # Vertical position uncertainty (meters) [epv]
00069 float64 err_vert
00070 
00071 # Track uncertainty (degrees) [epd]
00072 float64 err_track
00073 
00074 # Ground speed uncertainty (meters/second) [eps]
00075 float64 err_speed
00076 
00077 # Vertical speed uncertainty (meters/second) [epc]
00078 float64 err_climb
00079 
00080 # Temporal uncertainty [ept]
00081 float64 err_time
00082 
00083 # Orientation uncertainty (degrees)
00084 float64 err_pitch
00085 float64 err_roll
00086 float64 err_dip
00087 
00088 # Position covariance [m^2] defined relative to a tangential plane
00089 # through the reported position. The components are East, North, and
00090 # Up (ENU), in row-major order.
00091 
00092 float64[9] position_covariance
00093 
00094 uint8 COVARIANCE_TYPE_UNKNOWN = 0
00095 uint8 COVARIANCE_TYPE_APPROXIMATED = 1
00096 uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2
00097 uint8 COVARIANCE_TYPE_KNOWN = 3
00098 
00099 uint8 position_covariance_type
00100 
00101 
00102 ================================================================================
00103 MSG: std_msgs/Header
00104 # Standard metadata for higher-level stamped data types.
00105 # This is generally used to communicate timestamped data 
00106 # in a particular coordinate frame.
00107 # 
00108 # sequence ID: consecutively increasing ID 
00109 uint32 seq
00110 #Two-integer timestamp that is expressed as:
00111 # * stamp.secs: seconds (stamp_secs) since epoch
00112 # * stamp.nsecs: nanoseconds since stamp_secs
00113 # time-handling sugar is provided by the client library
00114 time stamp
00115 #Frame this data is associated with
00116 # 0: no frame
00117 # 1: global frame
00118 string frame_id
00119 
00120 ================================================================================
00121 MSG: clearpath_sensors/GPSStatus
00122 Header header
00123 
00124 # Satellites used in solution
00125 uint16 satellites_used # Number of satellites
00126 int32[] satellite_used_prn # PRN identifiers
00127 
00128 # Satellites visible
00129 uint16 satellites_visible
00130 int32[] satellite_visible_prn # PRN identifiers
00131 int32[] satellite_visible_z # Elevation of satellites
00132 int32[] satellite_visible_azimuth # Azimuth of satellites
00133 int32[] satellite_visible_snr # Signal-to-noise ratios (dB)
00134 
00135 # Measurement status
00136 int16 STATUS_NO_FIX=-1   # Unable to fix position
00137 int16 STATUS_FIX=0       # Normal fix
00138 int16 STATUS_SBAS_FIX=1  # Fixed using a satellite-based augmentation system
00139 int16 STATUS_GBAS_FIX=2  #          or a ground-based augmentation system
00140 int16 STATUS_DGPS_FIX=18 # Fixed with DGPS
00141 int16 STATUS_WAAS_FIX=33 # Fixed with WAAS
00142 int16 status
00143 
00144 uint16 SOURCE_NONE=0 # No information is available
00145 uint16 SOURCE_GPS=1 # Using standard GPS location [only valid for position_source]
00146 uint16 SOURCE_POINTS=2 # Motion/orientation fix is derived from successive points
00147 uint16 SOURCE_DOPPLER=4 # Motion is derived using the Doppler effect
00148 uint16 SOURCE_ALTIMETER=8 # Using an altimeter
00149 uint16 SOURCE_MAGNETIC=16 # Using magnetic sensors
00150 uint16 SOURCE_GYRO=32 # Using gyroscopes
00151 uint16 SOURCE_ACCEL=64 # Using accelerometers
00152 
00153 uint16 motion_source # Source for speed, climb and track
00154 uint16 orientation_source # Source for device orientation
00155 uint16 position_source # Source for position
00156 
00157 
00158 """
00159   
00160   COVARIANCE_TYPE_UNKNOWN = 0
00161   COVARIANCE_TYPE_APPROXIMATED = 1
00162   COVARIANCE_TYPE_DIAGONAL_KNOWN = 2
00163   COVARIANCE_TYPE_KNOWN = 3
00164 
00165   __slots__ = ['header','status','latitude','longitude','altitude','track','speed','climb','pitch','roll','dip','time','gdop','pdop','hdop','vdop','tdop','err','err_horz','err_vert','err_track','err_speed','err_climb','err_time','err_pitch','err_roll','err_dip','position_covariance','position_covariance_type']
00166   _slot_types = ['Header','clearpath_sensors/GPSStatus','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64[9]','uint8']
00167 
00168   def __init__(self, *args, **kwds):
00169     """
00170     Constructor. Any message fields that are implicitly/explicitly
00171     set to None will be assigned a default value. The recommend
00172     use is keyword arguments as this is more robust to future message
00173     changes.  You cannot mix in-order arguments and keyword arguments.
00174     
00175     The available fields are:
00176        header,status,latitude,longitude,altitude,track,speed,climb,pitch,roll,dip,time,gdop,pdop,hdop,vdop,tdop,err,err_horz,err_vert,err_track,err_speed,err_climb,err_time,err_pitch,err_roll,err_dip,position_covariance,position_covariance_type
00177     
00178     @param args: complete set of field values, in .msg order
00179     @param kwds: use keyword arguments corresponding to message field names
00180     to set specific fields. 
00181     """
00182     if args or kwds:
00183       super(GPSFix, self).__init__(*args, **kwds)
00184       
00185       if self.header is None:
00186         self.header = std_msgs.msg._Header.Header()
00187       if self.status is None:
00188         self.status = clearpath_sensors.msg.GPSStatus()
00189       if self.latitude is None:
00190         self.latitude = 0.
00191       if self.longitude is None:
00192         self.longitude = 0.
00193       if self.altitude is None:
00194         self.altitude = 0.
00195       if self.track is None:
00196         self.track = 0.
00197       if self.speed is None:
00198         self.speed = 0.
00199       if self.climb is None:
00200         self.climb = 0.
00201       if self.pitch is None:
00202         self.pitch = 0.
00203       if self.roll is None:
00204         self.roll = 0.
00205       if self.dip is None:
00206         self.dip = 0.
00207       if self.time is None:
00208         self.time = 0.
00209       if self.gdop is None:
00210         self.gdop = 0.
00211       if self.pdop is None:
00212         self.pdop = 0.
00213       if self.hdop is None:
00214         self.hdop = 0.
00215       if self.vdop is None:
00216         self.vdop = 0.
00217       if self.tdop is None:
00218         self.tdop = 0.
00219       if self.err is None:
00220         self.err = 0.
00221       if self.err_horz is None:
00222         self.err_horz = 0.
00223       if self.err_vert is None:
00224         self.err_vert = 0.
00225       if self.err_track is None:
00226         self.err_track = 0.
00227       if self.err_speed is None:
00228         self.err_speed = 0.
00229       if self.err_climb is None:
00230         self.err_climb = 0.
00231       if self.err_time is None:
00232         self.err_time = 0.
00233       if self.err_pitch is None:
00234         self.err_pitch = 0.
00235       if self.err_roll is None:
00236         self.err_roll = 0.
00237       if self.err_dip is None:
00238         self.err_dip = 0.
00239       if self.position_covariance is None:
00240         self.position_covariance = [0.,0.,0.,0.,0.,0.,0.,0.,0.]
00241       if self.position_covariance_type is None:
00242         self.position_covariance_type = 0
00243     else:
00244       self.header = std_msgs.msg._Header.Header()
00245       self.status = clearpath_sensors.msg.GPSStatus()
00246       self.latitude = 0.
00247       self.longitude = 0.
00248       self.altitude = 0.
00249       self.track = 0.
00250       self.speed = 0.
00251       self.climb = 0.
00252       self.pitch = 0.
00253       self.roll = 0.
00254       self.dip = 0.
00255       self.time = 0.
00256       self.gdop = 0.
00257       self.pdop = 0.
00258       self.hdop = 0.
00259       self.vdop = 0.
00260       self.tdop = 0.
00261       self.err = 0.
00262       self.err_horz = 0.
00263       self.err_vert = 0.
00264       self.err_track = 0.
00265       self.err_speed = 0.
00266       self.err_climb = 0.
00267       self.err_time = 0.
00268       self.err_pitch = 0.
00269       self.err_roll = 0.
00270       self.err_dip = 0.
00271       self.position_covariance = [0.,0.,0.,0.,0.,0.,0.,0.,0.]
00272       self.position_covariance_type = 0
00273 
00274   def _get_types(self):
00275     """
00276     internal API method
00277     """
00278     return self._slot_types
00279 
00280   def serialize(self, buff):
00281     """
00282     serialize message into buffer
00283     @param buff: buffer
00284     @type  buff: StringIO
00285     """
00286     try:
00287       _x = self
00288       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00289       _x = self.header.frame_id
00290       length = len(_x)
00291       buff.write(struct.pack('<I%ss'%length, length, _x))
00292       _x = self
00293       buff.write(_struct_3I.pack(_x.status.header.seq, _x.status.header.stamp.secs, _x.status.header.stamp.nsecs))
00294       _x = self.status.header.frame_id
00295       length = len(_x)
00296       buff.write(struct.pack('<I%ss'%length, length, _x))
00297       buff.write(_struct_H.pack(self.status.satellites_used))
00298       length = len(self.status.satellite_used_prn)
00299       buff.write(_struct_I.pack(length))
00300       pattern = '<%si'%length
00301       buff.write(struct.pack(pattern, *self.status.satellite_used_prn))
00302       buff.write(_struct_H.pack(self.status.satellites_visible))
00303       length = len(self.status.satellite_visible_prn)
00304       buff.write(_struct_I.pack(length))
00305       pattern = '<%si'%length
00306       buff.write(struct.pack(pattern, *self.status.satellite_visible_prn))
00307       length = len(self.status.satellite_visible_z)
00308       buff.write(_struct_I.pack(length))
00309       pattern = '<%si'%length
00310       buff.write(struct.pack(pattern, *self.status.satellite_visible_z))
00311       length = len(self.status.satellite_visible_azimuth)
00312       buff.write(_struct_I.pack(length))
00313       pattern = '<%si'%length
00314       buff.write(struct.pack(pattern, *self.status.satellite_visible_azimuth))
00315       length = len(self.status.satellite_visible_snr)
00316       buff.write(_struct_I.pack(length))
00317       pattern = '<%si'%length
00318       buff.write(struct.pack(pattern, *self.status.satellite_visible_snr))
00319       _x = self
00320       buff.write(_struct_h3H25d.pack(_x.status.status, _x.status.motion_source, _x.status.orientation_source, _x.status.position_source, _x.latitude, _x.longitude, _x.altitude, _x.track, _x.speed, _x.climb, _x.pitch, _x.roll, _x.dip, _x.time, _x.gdop, _x.pdop, _x.hdop, _x.vdop, _x.tdop, _x.err, _x.err_horz, _x.err_vert, _x.err_track, _x.err_speed, _x.err_climb, _x.err_time, _x.err_pitch, _x.err_roll, _x.err_dip))
00321       buff.write(_struct_9d.pack(*self.position_covariance))
00322       buff.write(_struct_B.pack(self.position_covariance_type))
00323     except struct.error as se: self._check_types(se)
00324     except TypeError as te: self._check_types(te)
00325 
00326   def deserialize(self, str):
00327     """
00328     unpack serialized message in str into this message instance
00329     @param str: byte array of serialized message
00330     @type  str: str
00331     """
00332     try:
00333       if self.header is None:
00334         self.header = std_msgs.msg._Header.Header()
00335       if self.status is None:
00336         self.status = clearpath_sensors.msg.GPSStatus()
00337       end = 0
00338       _x = self
00339       start = end
00340       end += 12
00341       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00342       start = end
00343       end += 4
00344       (length,) = _struct_I.unpack(str[start:end])
00345       start = end
00346       end += length
00347       self.header.frame_id = str[start:end]
00348       _x = self
00349       start = end
00350       end += 12
00351       (_x.status.header.seq, _x.status.header.stamp.secs, _x.status.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00352       start = end
00353       end += 4
00354       (length,) = _struct_I.unpack(str[start:end])
00355       start = end
00356       end += length
00357       self.status.header.frame_id = str[start:end]
00358       start = end
00359       end += 2
00360       (self.status.satellites_used,) = _struct_H.unpack(str[start:end])
00361       start = end
00362       end += 4
00363       (length,) = _struct_I.unpack(str[start:end])
00364       pattern = '<%si'%length
00365       start = end
00366       end += struct.calcsize(pattern)
00367       self.status.satellite_used_prn = struct.unpack(pattern, str[start:end])
00368       start = end
00369       end += 2
00370       (self.status.satellites_visible,) = _struct_H.unpack(str[start:end])
00371       start = end
00372       end += 4
00373       (length,) = _struct_I.unpack(str[start:end])
00374       pattern = '<%si'%length
00375       start = end
00376       end += struct.calcsize(pattern)
00377       self.status.satellite_visible_prn = struct.unpack(pattern, str[start:end])
00378       start = end
00379       end += 4
00380       (length,) = _struct_I.unpack(str[start:end])
00381       pattern = '<%si'%length
00382       start = end
00383       end += struct.calcsize(pattern)
00384       self.status.satellite_visible_z = struct.unpack(pattern, str[start:end])
00385       start = end
00386       end += 4
00387       (length,) = _struct_I.unpack(str[start:end])
00388       pattern = '<%si'%length
00389       start = end
00390       end += struct.calcsize(pattern)
00391       self.status.satellite_visible_azimuth = struct.unpack(pattern, str[start:end])
00392       start = end
00393       end += 4
00394       (length,) = _struct_I.unpack(str[start:end])
00395       pattern = '<%si'%length
00396       start = end
00397       end += struct.calcsize(pattern)
00398       self.status.satellite_visible_snr = struct.unpack(pattern, str[start:end])
00399       _x = self
00400       start = end
00401       end += 208
00402       (_x.status.status, _x.status.motion_source, _x.status.orientation_source, _x.status.position_source, _x.latitude, _x.longitude, _x.altitude, _x.track, _x.speed, _x.climb, _x.pitch, _x.roll, _x.dip, _x.time, _x.gdop, _x.pdop, _x.hdop, _x.vdop, _x.tdop, _x.err, _x.err_horz, _x.err_vert, _x.err_track, _x.err_speed, _x.err_climb, _x.err_time, _x.err_pitch, _x.err_roll, _x.err_dip,) = _struct_h3H25d.unpack(str[start:end])
00403       start = end
00404       end += 72
00405       self.position_covariance = _struct_9d.unpack(str[start:end])
00406       start = end
00407       end += 1
00408       (self.position_covariance_type,) = _struct_B.unpack(str[start:end])
00409       return self
00410     except struct.error as e:
00411       raise roslib.message.DeserializationError(e) 
00412 
00413 
00414   def serialize_numpy(self, buff, numpy):
00415     """
00416     serialize message with numpy array types into buffer
00417     @param buff: buffer
00418     @type  buff: StringIO
00419     @param numpy: numpy python module
00420     @type  numpy module
00421     """
00422     try:
00423       _x = self
00424       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00425       _x = self.header.frame_id
00426       length = len(_x)
00427       buff.write(struct.pack('<I%ss'%length, length, _x))
00428       _x = self
00429       buff.write(_struct_3I.pack(_x.status.header.seq, _x.status.header.stamp.secs, _x.status.header.stamp.nsecs))
00430       _x = self.status.header.frame_id
00431       length = len(_x)
00432       buff.write(struct.pack('<I%ss'%length, length, _x))
00433       buff.write(_struct_H.pack(self.status.satellites_used))
00434       length = len(self.status.satellite_used_prn)
00435       buff.write(_struct_I.pack(length))
00436       pattern = '<%si'%length
00437       buff.write(self.status.satellite_used_prn.tostring())
00438       buff.write(_struct_H.pack(self.status.satellites_visible))
00439       length = len(self.status.satellite_visible_prn)
00440       buff.write(_struct_I.pack(length))
00441       pattern = '<%si'%length
00442       buff.write(self.status.satellite_visible_prn.tostring())
00443       length = len(self.status.satellite_visible_z)
00444       buff.write(_struct_I.pack(length))
00445       pattern = '<%si'%length
00446       buff.write(self.status.satellite_visible_z.tostring())
00447       length = len(self.status.satellite_visible_azimuth)
00448       buff.write(_struct_I.pack(length))
00449       pattern = '<%si'%length
00450       buff.write(self.status.satellite_visible_azimuth.tostring())
00451       length = len(self.status.satellite_visible_snr)
00452       buff.write(_struct_I.pack(length))
00453       pattern = '<%si'%length
00454       buff.write(self.status.satellite_visible_snr.tostring())
00455       _x = self
00456       buff.write(_struct_h3H25d.pack(_x.status.status, _x.status.motion_source, _x.status.orientation_source, _x.status.position_source, _x.latitude, _x.longitude, _x.altitude, _x.track, _x.speed, _x.climb, _x.pitch, _x.roll, _x.dip, _x.time, _x.gdop, _x.pdop, _x.hdop, _x.vdop, _x.tdop, _x.err, _x.err_horz, _x.err_vert, _x.err_track, _x.err_speed, _x.err_climb, _x.err_time, _x.err_pitch, _x.err_roll, _x.err_dip))
00457       buff.write(self.position_covariance.tostring())
00458       buff.write(_struct_B.pack(self.position_covariance_type))
00459     except struct.error as se: self._check_types(se)
00460     except TypeError as te: self._check_types(te)
00461 
00462   def deserialize_numpy(self, str, numpy):
00463     """
00464     unpack serialized message in str into this message instance using numpy for array types
00465     @param str: byte array of serialized message
00466     @type  str: str
00467     @param numpy: numpy python module
00468     @type  numpy: module
00469     """
00470     try:
00471       if self.header is None:
00472         self.header = std_msgs.msg._Header.Header()
00473       if self.status is None:
00474         self.status = clearpath_sensors.msg.GPSStatus()
00475       end = 0
00476       _x = self
00477       start = end
00478       end += 12
00479       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00480       start = end
00481       end += 4
00482       (length,) = _struct_I.unpack(str[start:end])
00483       start = end
00484       end += length
00485       self.header.frame_id = str[start:end]
00486       _x = self
00487       start = end
00488       end += 12
00489       (_x.status.header.seq, _x.status.header.stamp.secs, _x.status.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00490       start = end
00491       end += 4
00492       (length,) = _struct_I.unpack(str[start:end])
00493       start = end
00494       end += length
00495       self.status.header.frame_id = str[start:end]
00496       start = end
00497       end += 2
00498       (self.status.satellites_used,) = _struct_H.unpack(str[start:end])
00499       start = end
00500       end += 4
00501       (length,) = _struct_I.unpack(str[start:end])
00502       pattern = '<%si'%length
00503       start = end
00504       end += struct.calcsize(pattern)
00505       self.status.satellite_used_prn = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00506       start = end
00507       end += 2
00508       (self.status.satellites_visible,) = _struct_H.unpack(str[start:end])
00509       start = end
00510       end += 4
00511       (length,) = _struct_I.unpack(str[start:end])
00512       pattern = '<%si'%length
00513       start = end
00514       end += struct.calcsize(pattern)
00515       self.status.satellite_visible_prn = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00516       start = end
00517       end += 4
00518       (length,) = _struct_I.unpack(str[start:end])
00519       pattern = '<%si'%length
00520       start = end
00521       end += struct.calcsize(pattern)
00522       self.status.satellite_visible_z = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00523       start = end
00524       end += 4
00525       (length,) = _struct_I.unpack(str[start:end])
00526       pattern = '<%si'%length
00527       start = end
00528       end += struct.calcsize(pattern)
00529       self.status.satellite_visible_azimuth = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00530       start = end
00531       end += 4
00532       (length,) = _struct_I.unpack(str[start:end])
00533       pattern = '<%si'%length
00534       start = end
00535       end += struct.calcsize(pattern)
00536       self.status.satellite_visible_snr = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00537       _x = self
00538       start = end
00539       end += 208
00540       (_x.status.status, _x.status.motion_source, _x.status.orientation_source, _x.status.position_source, _x.latitude, _x.longitude, _x.altitude, _x.track, _x.speed, _x.climb, _x.pitch, _x.roll, _x.dip, _x.time, _x.gdop, _x.pdop, _x.hdop, _x.vdop, _x.tdop, _x.err, _x.err_horz, _x.err_vert, _x.err_track, _x.err_speed, _x.err_climb, _x.err_time, _x.err_pitch, _x.err_roll, _x.err_dip,) = _struct_h3H25d.unpack(str[start:end])
00541       start = end
00542       end += 72
00543       self.position_covariance = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00544       start = end
00545       end += 1
00546       (self.position_covariance_type,) = _struct_B.unpack(str[start:end])
00547       return self
00548     except struct.error as e:
00549       raise roslib.message.DeserializationError(e) 
00550 
00551 _struct_I = roslib.message.struct_I
00552 _struct_h3H25d = struct.Struct("<h3H25d")
00553 _struct_H = struct.Struct("<H")
00554 _struct_3I = struct.Struct("<3I")
00555 _struct_B = struct.Struct("<B")
00556 _struct_9d = struct.Struct("<9d")