$search
00001 """autogenerated by genmsg_py from GPSStatus.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import std_msgs.msg 00006 00007 class GPSStatus(roslib.message.Message): 00008 _md5sum = "313baa8951fdd056c78bf61b1b07d249" 00009 _type = "gps_common/GPSStatus" 00010 _has_header = True #flag to mark the presence of a Header object 00011 _full_text = """Header header 00012 00013 # Satellites used in solution 00014 uint16 satellites_used # Number of satellites 00015 int32[] satellite_used_prn # PRN identifiers 00016 00017 # Satellites visible 00018 uint16 satellites_visible 00019 int32[] satellite_visible_prn # PRN identifiers 00020 int32[] satellite_visible_z # Elevation of satellites 00021 int32[] satellite_visible_azimuth # Azimuth of satellites 00022 int32[] satellite_visible_snr # Signal-to-noise ratios (dB) 00023 00024 # Measurement status 00025 int16 STATUS_NO_FIX=-1 # Unable to fix position 00026 int16 STATUS_FIX=0 # Normal fix 00027 int16 STATUS_SBAS_FIX=1 # Fixed using a satellite-based augmentation system 00028 int16 STATUS_GBAS_FIX=2 # or a ground-based augmentation system 00029 int16 STATUS_DGPS_FIX=18 # Fixed with DGPS 00030 int16 STATUS_WAAS_FIX=33 # Fixed with WAAS 00031 int16 status 00032 00033 uint16 SOURCE_NONE=0 # No information is available 00034 uint16 SOURCE_GPS=1 # Using standard GPS location [only valid for position_source] 00035 uint16 SOURCE_POINTS=2 # Motion/orientation fix is derived from successive points 00036 uint16 SOURCE_DOPPLER=4 # Motion is derived using the Doppler effect 00037 uint16 SOURCE_ALTIMETER=8 # Using an altimeter 00038 uint16 SOURCE_MAGNETIC=16 # Using magnetic sensors 00039 uint16 SOURCE_GYRO=32 # Using gyroscopes 00040 uint16 SOURCE_ACCEL=64 # Using accelerometers 00041 00042 uint16 motion_source # Source for speed, climb and track 00043 uint16 orientation_source # Source for device orientation 00044 uint16 position_source # Source for position 00045 00046 00047 ================================================================================ 00048 MSG: std_msgs/Header 00049 # Standard metadata for higher-level stamped data types. 00050 # This is generally used to communicate timestamped data 00051 # in a particular coordinate frame. 00052 # 00053 # sequence ID: consecutively increasing ID 00054 uint32 seq 00055 #Two-integer timestamp that is expressed as: 00056 # * stamp.secs: seconds (stamp_secs) since epoch 00057 # * stamp.nsecs: nanoseconds since stamp_secs 00058 # time-handling sugar is provided by the client library 00059 time stamp 00060 #Frame this data is associated with 00061 # 0: no frame 00062 # 1: global frame 00063 string frame_id 00064 00065 """ 00066 # Pseudo-constants 00067 STATUS_NO_FIX = -1 00068 STATUS_FIX = 0 00069 STATUS_SBAS_FIX = 1 00070 STATUS_GBAS_FIX = 2 00071 STATUS_DGPS_FIX = 18 00072 STATUS_WAAS_FIX = 33 00073 SOURCE_NONE = 0 00074 SOURCE_GPS = 1 00075 SOURCE_POINTS = 2 00076 SOURCE_DOPPLER = 4 00077 SOURCE_ALTIMETER = 8 00078 SOURCE_MAGNETIC = 16 00079 SOURCE_GYRO = 32 00080 SOURCE_ACCEL = 64 00081 00082 __slots__ = ['header','satellites_used','satellite_used_prn','satellites_visible','satellite_visible_prn','satellite_visible_z','satellite_visible_azimuth','satellite_visible_snr','status','motion_source','orientation_source','position_source'] 00083 _slot_types = ['Header','uint16','int32[]','uint16','int32[]','int32[]','int32[]','int32[]','int16','uint16','uint16','uint16'] 00084 00085 def __init__(self, *args, **kwds): 00086 """ 00087 Constructor. Any message fields that are implicitly/explicitly 00088 set to None will be assigned a default value. The recommend 00089 use is keyword arguments as this is more robust to future message 00090 changes. You cannot mix in-order arguments and keyword arguments. 00091 00092 The available fields are: 00093 header,satellites_used,satellite_used_prn,satellites_visible,satellite_visible_prn,satellite_visible_z,satellite_visible_azimuth,satellite_visible_snr,status,motion_source,orientation_source,position_source 00094 00095 @param args: complete set of field values, in .msg order 00096 @param kwds: use keyword arguments corresponding to message field names 00097 to set specific fields. 00098 """ 00099 if args or kwds: 00100 super(GPSStatus, self).__init__(*args, **kwds) 00101 #message fields cannot be None, assign default values for those that are 00102 if self.header is None: 00103 self.header = std_msgs.msg._Header.Header() 00104 if self.satellites_used is None: 00105 self.satellites_used = 0 00106 if self.satellite_used_prn is None: 00107 self.satellite_used_prn = [] 00108 if self.satellites_visible is None: 00109 self.satellites_visible = 0 00110 if self.satellite_visible_prn is None: 00111 self.satellite_visible_prn = [] 00112 if self.satellite_visible_z is None: 00113 self.satellite_visible_z = [] 00114 if self.satellite_visible_azimuth is None: 00115 self.satellite_visible_azimuth = [] 00116 if self.satellite_visible_snr is None: 00117 self.satellite_visible_snr = [] 00118 if self.status is None: 00119 self.status = 0 00120 if self.motion_source is None: 00121 self.motion_source = 0 00122 if self.orientation_source is None: 00123 self.orientation_source = 0 00124 if self.position_source is None: 00125 self.position_source = 0 00126 else: 00127 self.header = std_msgs.msg._Header.Header() 00128 self.satellites_used = 0 00129 self.satellite_used_prn = [] 00130 self.satellites_visible = 0 00131 self.satellite_visible_prn = [] 00132 self.satellite_visible_z = [] 00133 self.satellite_visible_azimuth = [] 00134 self.satellite_visible_snr = [] 00135 self.status = 0 00136 self.motion_source = 0 00137 self.orientation_source = 0 00138 self.position_source = 0 00139 00140 def _get_types(self): 00141 """ 00142 internal API method 00143 """ 00144 return self._slot_types 00145 00146 def serialize(self, buff): 00147 """ 00148 serialize message into buffer 00149 @param buff: buffer 00150 @type buff: StringIO 00151 """ 00152 try: 00153 _x = self 00154 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00155 _x = self.header.frame_id 00156 length = len(_x) 00157 buff.write(struct.pack('<I%ss'%length, length, _x)) 00158 buff.write(_struct_H.pack(self.satellites_used)) 00159 length = len(self.satellite_used_prn) 00160 buff.write(_struct_I.pack(length)) 00161 pattern = '<%si'%length 00162 buff.write(struct.pack(pattern, *self.satellite_used_prn)) 00163 buff.write(_struct_H.pack(self.satellites_visible)) 00164 length = len(self.satellite_visible_prn) 00165 buff.write(_struct_I.pack(length)) 00166 pattern = '<%si'%length 00167 buff.write(struct.pack(pattern, *self.satellite_visible_prn)) 00168 length = len(self.satellite_visible_z) 00169 buff.write(_struct_I.pack(length)) 00170 pattern = '<%si'%length 00171 buff.write(struct.pack(pattern, *self.satellite_visible_z)) 00172 length = len(self.satellite_visible_azimuth) 00173 buff.write(_struct_I.pack(length)) 00174 pattern = '<%si'%length 00175 buff.write(struct.pack(pattern, *self.satellite_visible_azimuth)) 00176 length = len(self.satellite_visible_snr) 00177 buff.write(_struct_I.pack(length)) 00178 pattern = '<%si'%length 00179 buff.write(struct.pack(pattern, *self.satellite_visible_snr)) 00180 _x = self 00181 buff.write(_struct_h3H.pack(_x.status, _x.motion_source, _x.orientation_source, _x.position_source)) 00182 except struct.error as se: self._check_types(se) 00183 except TypeError as te: self._check_types(te) 00184 00185 def deserialize(self, str): 00186 """ 00187 unpack serialized message in str into this message instance 00188 @param str: byte array of serialized message 00189 @type str: str 00190 """ 00191 try: 00192 if self.header is None: 00193 self.header = std_msgs.msg._Header.Header() 00194 end = 0 00195 _x = self 00196 start = end 00197 end += 12 00198 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00199 start = end 00200 end += 4 00201 (length,) = _struct_I.unpack(str[start:end]) 00202 start = end 00203 end += length 00204 self.header.frame_id = str[start:end] 00205 start = end 00206 end += 2 00207 (self.satellites_used,) = _struct_H.unpack(str[start:end]) 00208 start = end 00209 end += 4 00210 (length,) = _struct_I.unpack(str[start:end]) 00211 pattern = '<%si'%length 00212 start = end 00213 end += struct.calcsize(pattern) 00214 self.satellite_used_prn = struct.unpack(pattern, str[start:end]) 00215 start = end 00216 end += 2 00217 (self.satellites_visible,) = _struct_H.unpack(str[start:end]) 00218 start = end 00219 end += 4 00220 (length,) = _struct_I.unpack(str[start:end]) 00221 pattern = '<%si'%length 00222 start = end 00223 end += struct.calcsize(pattern) 00224 self.satellite_visible_prn = struct.unpack(pattern, str[start:end]) 00225 start = end 00226 end += 4 00227 (length,) = _struct_I.unpack(str[start:end]) 00228 pattern = '<%si'%length 00229 start = end 00230 end += struct.calcsize(pattern) 00231 self.satellite_visible_z = struct.unpack(pattern, str[start:end]) 00232 start = end 00233 end += 4 00234 (length,) = _struct_I.unpack(str[start:end]) 00235 pattern = '<%si'%length 00236 start = end 00237 end += struct.calcsize(pattern) 00238 self.satellite_visible_azimuth = struct.unpack(pattern, str[start:end]) 00239 start = end 00240 end += 4 00241 (length,) = _struct_I.unpack(str[start:end]) 00242 pattern = '<%si'%length 00243 start = end 00244 end += struct.calcsize(pattern) 00245 self.satellite_visible_snr = struct.unpack(pattern, str[start:end]) 00246 _x = self 00247 start = end 00248 end += 8 00249 (_x.status, _x.motion_source, _x.orientation_source, _x.position_source,) = _struct_h3H.unpack(str[start:end]) 00250 return self 00251 except struct.error as e: 00252 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00253 00254 00255 def serialize_numpy(self, buff, numpy): 00256 """ 00257 serialize message with numpy array types into buffer 00258 @param buff: buffer 00259 @type buff: StringIO 00260 @param numpy: numpy python module 00261 @type numpy module 00262 """ 00263 try: 00264 _x = self 00265 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00266 _x = self.header.frame_id 00267 length = len(_x) 00268 buff.write(struct.pack('<I%ss'%length, length, _x)) 00269 buff.write(_struct_H.pack(self.satellites_used)) 00270 length = len(self.satellite_used_prn) 00271 buff.write(_struct_I.pack(length)) 00272 pattern = '<%si'%length 00273 buff.write(self.satellite_used_prn.tostring()) 00274 buff.write(_struct_H.pack(self.satellites_visible)) 00275 length = len(self.satellite_visible_prn) 00276 buff.write(_struct_I.pack(length)) 00277 pattern = '<%si'%length 00278 buff.write(self.satellite_visible_prn.tostring()) 00279 length = len(self.satellite_visible_z) 00280 buff.write(_struct_I.pack(length)) 00281 pattern = '<%si'%length 00282 buff.write(self.satellite_visible_z.tostring()) 00283 length = len(self.satellite_visible_azimuth) 00284 buff.write(_struct_I.pack(length)) 00285 pattern = '<%si'%length 00286 buff.write(self.satellite_visible_azimuth.tostring()) 00287 length = len(self.satellite_visible_snr) 00288 buff.write(_struct_I.pack(length)) 00289 pattern = '<%si'%length 00290 buff.write(self.satellite_visible_snr.tostring()) 00291 _x = self 00292 buff.write(_struct_h3H.pack(_x.status, _x.motion_source, _x.orientation_source, _x.position_source)) 00293 except struct.error as se: self._check_types(se) 00294 except TypeError as te: self._check_types(te) 00295 00296 def deserialize_numpy(self, str, numpy): 00297 """ 00298 unpack serialized message in str into this message instance using numpy for array types 00299 @param str: byte array of serialized message 00300 @type str: str 00301 @param numpy: numpy python module 00302 @type numpy: module 00303 """ 00304 try: 00305 if self.header is None: 00306 self.header = std_msgs.msg._Header.Header() 00307 end = 0 00308 _x = self 00309 start = end 00310 end += 12 00311 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00312 start = end 00313 end += 4 00314 (length,) = _struct_I.unpack(str[start:end]) 00315 start = end 00316 end += length 00317 self.header.frame_id = str[start:end] 00318 start = end 00319 end += 2 00320 (self.satellites_used,) = _struct_H.unpack(str[start:end]) 00321 start = end 00322 end += 4 00323 (length,) = _struct_I.unpack(str[start:end]) 00324 pattern = '<%si'%length 00325 start = end 00326 end += struct.calcsize(pattern) 00327 self.satellite_used_prn = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length) 00328 start = end 00329 end += 2 00330 (self.satellites_visible,) = _struct_H.unpack(str[start:end]) 00331 start = end 00332 end += 4 00333 (length,) = _struct_I.unpack(str[start:end]) 00334 pattern = '<%si'%length 00335 start = end 00336 end += struct.calcsize(pattern) 00337 self.satellite_visible_prn = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length) 00338 start = end 00339 end += 4 00340 (length,) = _struct_I.unpack(str[start:end]) 00341 pattern = '<%si'%length 00342 start = end 00343 end += struct.calcsize(pattern) 00344 self.satellite_visible_z = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length) 00345 start = end 00346 end += 4 00347 (length,) = _struct_I.unpack(str[start:end]) 00348 pattern = '<%si'%length 00349 start = end 00350 end += struct.calcsize(pattern) 00351 self.satellite_visible_azimuth = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length) 00352 start = end 00353 end += 4 00354 (length,) = _struct_I.unpack(str[start:end]) 00355 pattern = '<%si'%length 00356 start = end 00357 end += struct.calcsize(pattern) 00358 self.satellite_visible_snr = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length) 00359 _x = self 00360 start = end 00361 end += 8 00362 (_x.status, _x.motion_source, _x.orientation_source, _x.position_source,) = _struct_h3H.unpack(str[start:end]) 00363 return self 00364 except struct.error as e: 00365 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00366 00367 _struct_I = roslib.message.struct_I 00368 _struct_H = struct.Struct("<H") 00369 _struct_3I = struct.Struct("<3I") 00370 _struct_h3H = struct.Struct("<h3H")