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


worldmodel_msgs
Author(s): Johannes Meyer
autogenerated on Mon Jul 15 2013 16:50:40