00001 """autogenerated by genpy from hector_worldmodel_msgs/VerifyPerceptRequest.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 geometry_msgs.msg
00008 import hector_worldmodel_msgs.msg
00009 import std_msgs.msg
00010
00011 class VerifyPerceptRequest(genpy.Message):
00012 _md5sum = "9bd63c0c584500367d789d059094e625"
00013 _type = "hector_worldmodel_msgs/VerifyPerceptRequest"
00014 _has_header = False
00015 _full_text = """
00016
00017
00018 PosePercept percept
00019
00020 ================================================================================
00021 MSG: hector_worldmodel_msgs/PosePercept
00022 # hector_worldmodel_msgs/PosePercept
00023 # This message represents an observation of an object in a single image.
00024
00025 # The header should equal the header of the corresponding image.
00026 Header header
00027
00028 # The estimated pose of the object with its covariance
00029 geometry_msgs/PoseWithCovariance pose
00030
00031 # Additional information about the percept
00032 PerceptInfo info
00033
00034 ================================================================================
00035 MSG: std_msgs/Header
00036 # Standard metadata for higher-level stamped data types.
00037 # This is generally used to communicate timestamped data
00038 # in a particular coordinate frame.
00039 #
00040 # sequence ID: consecutively increasing ID
00041 uint32 seq
00042 #Two-integer timestamp that is expressed as:
00043 # * stamp.secs: seconds (stamp_secs) since epoch
00044 # * stamp.nsecs: nanoseconds since stamp_secs
00045 # time-handling sugar is provided by the client library
00046 time stamp
00047 #Frame this data is associated with
00048 # 0: no frame
00049 # 1: global frame
00050 string frame_id
00051
00052 ================================================================================
00053 MSG: geometry_msgs/PoseWithCovariance
00054 # This represents a pose in free space with uncertainty.
00055
00056 Pose pose
00057
00058 # Row-major representation of the 6x6 covariance matrix
00059 # The orientation parameters use a fixed-axis representation.
00060 # In order, the parameters are:
00061 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
00062 float64[36] covariance
00063
00064 ================================================================================
00065 MSG: geometry_msgs/Pose
00066 # A representation of pose in free space, composed of postion and orientation.
00067 Point position
00068 Quaternion orientation
00069
00070 ================================================================================
00071 MSG: geometry_msgs/Point
00072 # This contains the position of a point in free space
00073 float64 x
00074 float64 y
00075 float64 z
00076
00077 ================================================================================
00078 MSG: geometry_msgs/Quaternion
00079 # This represents an orientation in free space in quaternion form.
00080
00081 float64 x
00082 float64 y
00083 float64 z
00084 float64 w
00085
00086 ================================================================================
00087 MSG: hector_worldmodel_msgs/PerceptInfo
00088 # hector_worldmodel_msgs/PerceptInfo
00089 # This message contains information about the estimated class and object identity
00090
00091 # A string identifying the object's class (all objects of a class look the same)
00092 string class_id
00093
00094 # The class association support of the observation
00095 # The support is the log odd likelihood ratio given by log(p(y/observation y belongs to object of class class_id) / p(y/observation y is a false positive))
00096 float32 class_support
00097
00098 # A string identifying a specific object
00099 string object_id
00100
00101 # The object association support of the observation
00102 # The support is the log odd likelihood ratio given by log(p(observation belongs to object object_id) / p(observation is false positive or belongs to another object))
00103 float32 object_support
00104
00105 # A string that contains the name or a description of the specific object
00106 string name
00107
00108 """
00109 __slots__ = ['percept']
00110 _slot_types = ['hector_worldmodel_msgs/PosePercept']
00111
00112 def __init__(self, *args, **kwds):
00113 """
00114 Constructor. Any message fields that are implicitly/explicitly
00115 set to None will be assigned a default value. The recommend
00116 use is keyword arguments as this is more robust to future message
00117 changes. You cannot mix in-order arguments and keyword arguments.
00118
00119 The available fields are:
00120 percept
00121
00122 :param args: complete set of field values, in .msg order
00123 :param kwds: use keyword arguments corresponding to message field names
00124 to set specific fields.
00125 """
00126 if args or kwds:
00127 super(VerifyPerceptRequest, self).__init__(*args, **kwds)
00128
00129 if self.percept is None:
00130 self.percept = hector_worldmodel_msgs.msg.PosePercept()
00131 else:
00132 self.percept = hector_worldmodel_msgs.msg.PosePercept()
00133
00134 def _get_types(self):
00135 """
00136 internal API method
00137 """
00138 return self._slot_types
00139
00140 def serialize(self, buff):
00141 """
00142 serialize message into buffer
00143 :param buff: buffer, ``StringIO``
00144 """
00145 try:
00146 _x = self
00147 buff.write(_struct_3I.pack(_x.percept.header.seq, _x.percept.header.stamp.secs, _x.percept.header.stamp.nsecs))
00148 _x = self.percept.header.frame_id
00149 length = len(_x)
00150 if python3 or type(_x) == unicode:
00151 _x = _x.encode('utf-8')
00152 length = len(_x)
00153 buff.write(struct.pack('<I%ss'%length, length, _x))
00154 _x = self
00155 buff.write(_struct_7d.pack(_x.percept.pose.pose.position.x, _x.percept.pose.pose.position.y, _x.percept.pose.pose.position.z, _x.percept.pose.pose.orientation.x, _x.percept.pose.pose.orientation.y, _x.percept.pose.pose.orientation.z, _x.percept.pose.pose.orientation.w))
00156 buff.write(_struct_36d.pack(*self.percept.pose.covariance))
00157 _x = self.percept.info.class_id
00158 length = len(_x)
00159 if python3 or type(_x) == unicode:
00160 _x = _x.encode('utf-8')
00161 length = len(_x)
00162 buff.write(struct.pack('<I%ss'%length, length, _x))
00163 buff.write(_struct_f.pack(self.percept.info.class_support))
00164 _x = self.percept.info.object_id
00165 length = len(_x)
00166 if python3 or type(_x) == unicode:
00167 _x = _x.encode('utf-8')
00168 length = len(_x)
00169 buff.write(struct.pack('<I%ss'%length, length, _x))
00170 buff.write(_struct_f.pack(self.percept.info.object_support))
00171 _x = self.percept.info.name
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 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00178 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00179
00180 def deserialize(self, str):
00181 """
00182 unpack serialized message in str into this message instance
00183 :param str: byte array of serialized message, ``str``
00184 """
00185 try:
00186 if self.percept is None:
00187 self.percept = hector_worldmodel_msgs.msg.PosePercept()
00188 end = 0
00189 _x = self
00190 start = end
00191 end += 12
00192 (_x.percept.header.seq, _x.percept.header.stamp.secs, _x.percept.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00193 start = end
00194 end += 4
00195 (length,) = _struct_I.unpack(str[start:end])
00196 start = end
00197 end += length
00198 if python3:
00199 self.percept.header.frame_id = str[start:end].decode('utf-8')
00200 else:
00201 self.percept.header.frame_id = str[start:end]
00202 _x = self
00203 start = end
00204 end += 56
00205 (_x.percept.pose.pose.position.x, _x.percept.pose.pose.position.y, _x.percept.pose.pose.position.z, _x.percept.pose.pose.orientation.x, _x.percept.pose.pose.orientation.y, _x.percept.pose.pose.orientation.z, _x.percept.pose.pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00206 start = end
00207 end += 288
00208 self.percept.pose.covariance = _struct_36d.unpack(str[start:end])
00209 start = end
00210 end += 4
00211 (length,) = _struct_I.unpack(str[start:end])
00212 start = end
00213 end += length
00214 if python3:
00215 self.percept.info.class_id = str[start:end].decode('utf-8')
00216 else:
00217 self.percept.info.class_id = str[start:end]
00218 start = end
00219 end += 4
00220 (self.percept.info.class_support,) = _struct_f.unpack(str[start:end])
00221 start = end
00222 end += 4
00223 (length,) = _struct_I.unpack(str[start:end])
00224 start = end
00225 end += length
00226 if python3:
00227 self.percept.info.object_id = str[start:end].decode('utf-8')
00228 else:
00229 self.percept.info.object_id = str[start:end]
00230 start = end
00231 end += 4
00232 (self.percept.info.object_support,) = _struct_f.unpack(str[start:end])
00233 start = end
00234 end += 4
00235 (length,) = _struct_I.unpack(str[start:end])
00236 start = end
00237 end += length
00238 if python3:
00239 self.percept.info.name = str[start:end].decode('utf-8')
00240 else:
00241 self.percept.info.name = str[start:end]
00242 return self
00243 except struct.error as e:
00244 raise genpy.DeserializationError(e)
00245
00246
00247 def serialize_numpy(self, buff, numpy):
00248 """
00249 serialize message with numpy array types into buffer
00250 :param buff: buffer, ``StringIO``
00251 :param numpy: numpy python module
00252 """
00253 try:
00254 _x = self
00255 buff.write(_struct_3I.pack(_x.percept.header.seq, _x.percept.header.stamp.secs, _x.percept.header.stamp.nsecs))
00256 _x = self.percept.header.frame_id
00257 length = len(_x)
00258 if python3 or type(_x) == unicode:
00259 _x = _x.encode('utf-8')
00260 length = len(_x)
00261 buff.write(struct.pack('<I%ss'%length, length, _x))
00262 _x = self
00263 buff.write(_struct_7d.pack(_x.percept.pose.pose.position.x, _x.percept.pose.pose.position.y, _x.percept.pose.pose.position.z, _x.percept.pose.pose.orientation.x, _x.percept.pose.pose.orientation.y, _x.percept.pose.pose.orientation.z, _x.percept.pose.pose.orientation.w))
00264 buff.write(self.percept.pose.covariance.tostring())
00265 _x = self.percept.info.class_id
00266 length = len(_x)
00267 if python3 or type(_x) == unicode:
00268 _x = _x.encode('utf-8')
00269 length = len(_x)
00270 buff.write(struct.pack('<I%ss'%length, length, _x))
00271 buff.write(_struct_f.pack(self.percept.info.class_support))
00272 _x = self.percept.info.object_id
00273 length = len(_x)
00274 if python3 or type(_x) == unicode:
00275 _x = _x.encode('utf-8')
00276 length = len(_x)
00277 buff.write(struct.pack('<I%ss'%length, length, _x))
00278 buff.write(_struct_f.pack(self.percept.info.object_support))
00279 _x = self.percept.info.name
00280 length = len(_x)
00281 if python3 or type(_x) == unicode:
00282 _x = _x.encode('utf-8')
00283 length = len(_x)
00284 buff.write(struct.pack('<I%ss'%length, length, _x))
00285 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00286 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00287
00288 def deserialize_numpy(self, str, numpy):
00289 """
00290 unpack serialized message in str into this message instance using numpy for array types
00291 :param str: byte array of serialized message, ``str``
00292 :param numpy: numpy python module
00293 """
00294 try:
00295 if self.percept is None:
00296 self.percept = hector_worldmodel_msgs.msg.PosePercept()
00297 end = 0
00298 _x = self
00299 start = end
00300 end += 12
00301 (_x.percept.header.seq, _x.percept.header.stamp.secs, _x.percept.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00302 start = end
00303 end += 4
00304 (length,) = _struct_I.unpack(str[start:end])
00305 start = end
00306 end += length
00307 if python3:
00308 self.percept.header.frame_id = str[start:end].decode('utf-8')
00309 else:
00310 self.percept.header.frame_id = str[start:end]
00311 _x = self
00312 start = end
00313 end += 56
00314 (_x.percept.pose.pose.position.x, _x.percept.pose.pose.position.y, _x.percept.pose.pose.position.z, _x.percept.pose.pose.orientation.x, _x.percept.pose.pose.orientation.y, _x.percept.pose.pose.orientation.z, _x.percept.pose.pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00315 start = end
00316 end += 288
00317 self.percept.pose.covariance = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=36)
00318 start = end
00319 end += 4
00320 (length,) = _struct_I.unpack(str[start:end])
00321 start = end
00322 end += length
00323 if python3:
00324 self.percept.info.class_id = str[start:end].decode('utf-8')
00325 else:
00326 self.percept.info.class_id = str[start:end]
00327 start = end
00328 end += 4
00329 (self.percept.info.class_support,) = _struct_f.unpack(str[start:end])
00330 start = end
00331 end += 4
00332 (length,) = _struct_I.unpack(str[start:end])
00333 start = end
00334 end += length
00335 if python3:
00336 self.percept.info.object_id = str[start:end].decode('utf-8')
00337 else:
00338 self.percept.info.object_id = str[start:end]
00339 start = end
00340 end += 4
00341 (self.percept.info.object_support,) = _struct_f.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 if python3:
00348 self.percept.info.name = str[start:end].decode('utf-8')
00349 else:
00350 self.percept.info.name = str[start:end]
00351 return self
00352 except struct.error as e:
00353 raise genpy.DeserializationError(e)
00354
00355 _struct_I = genpy.struct_I
00356 _struct_3I = struct.Struct("<3I")
00357 _struct_7d = struct.Struct("<7d")
00358 _struct_36d = struct.Struct("<36d")
00359 _struct_f = struct.Struct("<f")
00360 """autogenerated by genpy from hector_worldmodel_msgs/VerifyPerceptResponse.msg. Do not edit."""
00361 import sys
00362 python3 = True if sys.hexversion > 0x03000000 else False
00363 import genpy
00364 import struct
00365
00366
00367 class VerifyPerceptResponse(genpy.Message):
00368 _md5sum = "a4e2509e523147799a63deb6a40a0721"
00369 _type = "hector_worldmodel_msgs/VerifyPerceptResponse"
00370 _has_header = False
00371 _full_text = """
00372 uint8 response
00373 uint8 UNKNOWN = 0
00374 uint8 DISCARD = 1
00375 uint8 CONFIRM = 2
00376
00377
00378 """
00379
00380 UNKNOWN = 0
00381 DISCARD = 1
00382 CONFIRM = 2
00383
00384 __slots__ = ['response']
00385 _slot_types = ['uint8']
00386
00387 def __init__(self, *args, **kwds):
00388 """
00389 Constructor. Any message fields that are implicitly/explicitly
00390 set to None will be assigned a default value. The recommend
00391 use is keyword arguments as this is more robust to future message
00392 changes. You cannot mix in-order arguments and keyword arguments.
00393
00394 The available fields are:
00395 response
00396
00397 :param args: complete set of field values, in .msg order
00398 :param kwds: use keyword arguments corresponding to message field names
00399 to set specific fields.
00400 """
00401 if args or kwds:
00402 super(VerifyPerceptResponse, self).__init__(*args, **kwds)
00403
00404 if self.response is None:
00405 self.response = 0
00406 else:
00407 self.response = 0
00408
00409 def _get_types(self):
00410 """
00411 internal API method
00412 """
00413 return self._slot_types
00414
00415 def serialize(self, buff):
00416 """
00417 serialize message into buffer
00418 :param buff: buffer, ``StringIO``
00419 """
00420 try:
00421 buff.write(_struct_B.pack(self.response))
00422 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00423 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00424
00425 def deserialize(self, str):
00426 """
00427 unpack serialized message in str into this message instance
00428 :param str: byte array of serialized message, ``str``
00429 """
00430 try:
00431 end = 0
00432 start = end
00433 end += 1
00434 (self.response,) = _struct_B.unpack(str[start:end])
00435 return self
00436 except struct.error as e:
00437 raise genpy.DeserializationError(e)
00438
00439
00440 def serialize_numpy(self, buff, numpy):
00441 """
00442 serialize message with numpy array types into buffer
00443 :param buff: buffer, ``StringIO``
00444 :param numpy: numpy python module
00445 """
00446 try:
00447 buff.write(_struct_B.pack(self.response))
00448 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00449 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00450
00451 def deserialize_numpy(self, str, numpy):
00452 """
00453 unpack serialized message in str into this message instance using numpy for array types
00454 :param str: byte array of serialized message, ``str``
00455 :param numpy: numpy python module
00456 """
00457 try:
00458 end = 0
00459 start = end
00460 end += 1
00461 (self.response,) = _struct_B.unpack(str[start:end])
00462 return self
00463 except struct.error as e:
00464 raise genpy.DeserializationError(e)
00465
00466 _struct_I = genpy.struct_I
00467 _struct_B = struct.Struct("<B")
00468 class VerifyPercept(object):
00469 _type = 'hector_worldmodel_msgs/VerifyPercept'
00470 _md5sum = '4274b9c0812a5a8c107aa29835bb1b45'
00471 _request_class = VerifyPerceptRequest
00472 _response_class = VerifyPerceptResponse