$search
00001 """autogenerated by genmsg_py from NavSatFix.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import sensor_msgs.msg 00006 import std_msgs.msg 00007 00008 class NavSatFix(roslib.message.Message): 00009 _md5sum = "2d3a8cd499b9b4a0249fb98fd05cfa48" 00010 _type = "sensor_msgs/NavSatFix" 00011 _has_header = True #flag to mark the presence of a Header object 00012 _full_text = """# Navigation Satellite fix for any Global Navigation Satellite System 00013 # 00014 # Specified using the WGS 84 reference ellipsoid 00015 00016 # Header specifies ROS time and frame of reference for this fix. 00017 Header header 00018 00019 # satellite fix status information 00020 sensor_msgs/NavSatStatus status 00021 00022 # Latitude [degrees]. Positive is north of equator; negative is south. 00023 float64 latitude 00024 00025 # Longitude [degrees]. Positive is east of prime meridian; negative is west. 00026 float64 longitude 00027 00028 # Altitude [m]. Positive is above the WGS 84 ellipsoid. 00029 float64 altitude 00030 00031 # Position covariance [m^2] defined relative to a tangential plane 00032 # through the reported position. The components are East, North, and 00033 # Up (ENU), in row-major order. 00034 # 00035 # Beware: this coordinate system exhibits singularities at the poles. 00036 00037 float64[9] position_covariance 00038 00039 # If the covariance of the fix is known, fill it in completely. If the 00040 # GPS receiver provides the variance of each measurement, put them 00041 # along the diagonal. If only Dilution of Precision is available, 00042 # estimate an approximate covariance from that. 00043 00044 uint8 COVARIANCE_TYPE_UNKNOWN = 0 00045 uint8 COVARIANCE_TYPE_APPROXIMATED = 1 00046 uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 00047 uint8 COVARIANCE_TYPE_KNOWN = 3 00048 00049 uint8 position_covariance_type 00050 00051 ================================================================================ 00052 MSG: std_msgs/Header 00053 # Standard metadata for higher-level stamped data types. 00054 # This is generally used to communicate timestamped data 00055 # in a particular coordinate frame. 00056 # 00057 # sequence ID: consecutively increasing ID 00058 uint32 seq 00059 #Two-integer timestamp that is expressed as: 00060 # * stamp.secs: seconds (stamp_secs) since epoch 00061 # * stamp.nsecs: nanoseconds since stamp_secs 00062 # time-handling sugar is provided by the client library 00063 time stamp 00064 #Frame this data is associated with 00065 # 0: no frame 00066 # 1: global frame 00067 string frame_id 00068 00069 ================================================================================ 00070 MSG: sensor_msgs/NavSatStatus 00071 # Navigation Satellite fix status for any Global Navigation Satellite System 00072 00073 # Whether to output an augmented fix is determined by both the fix 00074 # type and the last time differential corrections were received. A 00075 # fix is valid when status >= STATUS_FIX. 00076 00077 int8 STATUS_NO_FIX = -1 # unable to fix position 00078 int8 STATUS_FIX = 0 # unaugmented fix 00079 int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation 00080 int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation 00081 00082 int8 status 00083 00084 # Bits defining which Global Navigation Satellite System signals were 00085 # used by the receiver. 00086 00087 uint16 SERVICE_GPS = 1 00088 uint16 SERVICE_GLONASS = 2 00089 uint16 SERVICE_COMPASS = 4 # includes BeiDou. 00090 uint16 SERVICE_GALILEO = 8 00091 00092 uint16 service 00093 00094 """ 00095 # Pseudo-constants 00096 COVARIANCE_TYPE_UNKNOWN = 0 00097 COVARIANCE_TYPE_APPROXIMATED = 1 00098 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 00099 COVARIANCE_TYPE_KNOWN = 3 00100 00101 __slots__ = ['header','status','latitude','longitude','altitude','position_covariance','position_covariance_type'] 00102 _slot_types = ['Header','sensor_msgs/NavSatStatus','float64','float64','float64','float64[9]','uint8'] 00103 00104 def __init__(self, *args, **kwds): 00105 """ 00106 Constructor. Any message fields that are implicitly/explicitly 00107 set to None will be assigned a default value. The recommend 00108 use is keyword arguments as this is more robust to future message 00109 changes. You cannot mix in-order arguments and keyword arguments. 00110 00111 The available fields are: 00112 header,status,latitude,longitude,altitude,position_covariance,position_covariance_type 00113 00114 @param args: complete set of field values, in .msg order 00115 @param kwds: use keyword arguments corresponding to message field names 00116 to set specific fields. 00117 """ 00118 if args or kwds: 00119 super(NavSatFix, self).__init__(*args, **kwds) 00120 #message fields cannot be None, assign default values for those that are 00121 if self.header is None: 00122 self.header = std_msgs.msg._Header.Header() 00123 if self.status is None: 00124 self.status = sensor_msgs.msg.NavSatStatus() 00125 if self.latitude is None: 00126 self.latitude = 0. 00127 if self.longitude is None: 00128 self.longitude = 0. 00129 if self.altitude is None: 00130 self.altitude = 0. 00131 if self.position_covariance is None: 00132 self.position_covariance = [0.,0.,0.,0.,0.,0.,0.,0.,0.] 00133 if self.position_covariance_type is None: 00134 self.position_covariance_type = 0 00135 else: 00136 self.header = std_msgs.msg._Header.Header() 00137 self.status = sensor_msgs.msg.NavSatStatus() 00138 self.latitude = 0. 00139 self.longitude = 0. 00140 self.altitude = 0. 00141 self.position_covariance = [0.,0.,0.,0.,0.,0.,0.,0.,0.] 00142 self.position_covariance_type = 0 00143 00144 def _get_types(self): 00145 """ 00146 internal API method 00147 """ 00148 return self._slot_types 00149 00150 def serialize(self, buff): 00151 """ 00152 serialize message into buffer 00153 @param buff: buffer 00154 @type buff: StringIO 00155 """ 00156 try: 00157 _x = self 00158 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00159 _x = self.header.frame_id 00160 length = len(_x) 00161 buff.write(struct.pack('<I%ss'%length, length, _x)) 00162 _x = self 00163 buff.write(_struct_bH3d.pack(_x.status.status, _x.status.service, _x.latitude, _x.longitude, _x.altitude)) 00164 buff.write(_struct_9d.pack(*self.position_covariance)) 00165 buff.write(_struct_B.pack(self.position_covariance_type)) 00166 except struct.error as se: self._check_types(se) 00167 except TypeError as te: self._check_types(te) 00168 00169 def deserialize(self, str): 00170 """ 00171 unpack serialized message in str into this message instance 00172 @param str: byte array of serialized message 00173 @type str: str 00174 """ 00175 try: 00176 if self.header is None: 00177 self.header = std_msgs.msg._Header.Header() 00178 if self.status is None: 00179 self.status = sensor_msgs.msg.NavSatStatus() 00180 end = 0 00181 _x = self 00182 start = end 00183 end += 12 00184 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00185 start = end 00186 end += 4 00187 (length,) = _struct_I.unpack(str[start:end]) 00188 start = end 00189 end += length 00190 self.header.frame_id = str[start:end] 00191 _x = self 00192 start = end 00193 end += 27 00194 (_x.status.status, _x.status.service, _x.latitude, _x.longitude, _x.altitude,) = _struct_bH3d.unpack(str[start:end]) 00195 start = end 00196 end += 72 00197 self.position_covariance = _struct_9d.unpack(str[start:end]) 00198 start = end 00199 end += 1 00200 (self.position_covariance_type,) = _struct_B.unpack(str[start:end]) 00201 return self 00202 except struct.error as e: 00203 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00204 00205 00206 def serialize_numpy(self, buff, numpy): 00207 """ 00208 serialize message with numpy array types into buffer 00209 @param buff: buffer 00210 @type buff: StringIO 00211 @param numpy: numpy python module 00212 @type numpy module 00213 """ 00214 try: 00215 _x = self 00216 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00217 _x = self.header.frame_id 00218 length = len(_x) 00219 buff.write(struct.pack('<I%ss'%length, length, _x)) 00220 _x = self 00221 buff.write(_struct_bH3d.pack(_x.status.status, _x.status.service, _x.latitude, _x.longitude, _x.altitude)) 00222 buff.write(self.position_covariance.tostring()) 00223 buff.write(_struct_B.pack(self.position_covariance_type)) 00224 except struct.error as se: self._check_types(se) 00225 except TypeError as te: self._check_types(te) 00226 00227 def deserialize_numpy(self, str, numpy): 00228 """ 00229 unpack serialized message in str into this message instance using numpy for array types 00230 @param str: byte array of serialized message 00231 @type str: str 00232 @param numpy: numpy python module 00233 @type numpy: module 00234 """ 00235 try: 00236 if self.header is None: 00237 self.header = std_msgs.msg._Header.Header() 00238 if self.status is None: 00239 self.status = sensor_msgs.msg.NavSatStatus() 00240 end = 0 00241 _x = self 00242 start = end 00243 end += 12 00244 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00245 start = end 00246 end += 4 00247 (length,) = _struct_I.unpack(str[start:end]) 00248 start = end 00249 end += length 00250 self.header.frame_id = str[start:end] 00251 _x = self 00252 start = end 00253 end += 27 00254 (_x.status.status, _x.status.service, _x.latitude, _x.longitude, _x.altitude,) = _struct_bH3d.unpack(str[start:end]) 00255 start = end 00256 end += 72 00257 self.position_covariance = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9) 00258 start = end 00259 end += 1 00260 (self.position_covariance_type,) = _struct_B.unpack(str[start:end]) 00261 return self 00262 except struct.error as e: 00263 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00264 00265 _struct_I = roslib.message.struct_I 00266 _struct_3I = struct.Struct("<3I") 00267 _struct_bH3d = struct.Struct("<bH3d") 00268 _struct_9d = struct.Struct("<9d") 00269 _struct_B = struct.Struct("<B")