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


hector_worldmodel_msgs
Author(s): Johannes Meyer
autogenerated on Mon Oct 6 2014 00:36:27