00001 """autogenerated by genpy from worldmodel_msgs/Object.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 Object(genpy.Message):
00012 _md5sum = "02dea96e80640703553490052f13918d"
00013 _type = "worldmodel_msgs/Object"
00014 _has_header = True
00015 _full_text = """# This message represents an estimate of an object's pose and identity.
00016
00017 # The header.
00018 # stamp: Timestamp of last update.
00019 # frame_id: Coordinate frame, in which the pose is given
00020 Header header
00021
00022 # The pose
00023 geometry_msgs/PoseWithCovariance pose
00024
00025 # Further information about the object
00026 ObjectInfo info
00027
00028 # The tracked state of the object
00029 ObjectState state
00030
00031 ================================================================================
00032 MSG: std_msgs/Header
00033 # Standard metadata for higher-level stamped data types.
00034 # This is generally used to communicate timestamped data
00035 # in a particular coordinate frame.
00036 #
00037 # sequence ID: consecutively increasing ID
00038 uint32 seq
00039 #Two-integer timestamp that is expressed as:
00040 # * stamp.secs: seconds (stamp_secs) since epoch
00041 # * stamp.nsecs: nanoseconds since stamp_secs
00042 # time-handling sugar is provided by the client library
00043 time stamp
00044 #Frame this data is associated with
00045 # 0: no frame
00046 # 1: global frame
00047 string frame_id
00048
00049 ================================================================================
00050 MSG: geometry_msgs/PoseWithCovariance
00051 # This represents a pose in free space with uncertainty.
00052
00053 Pose pose
00054
00055 # Row-major representation of the 6x6 covariance matrix
00056 # The orientation parameters use a fixed-axis representation.
00057 # In order, the parameters are:
00058 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
00059 float64[36] covariance
00060
00061 ================================================================================
00062 MSG: geometry_msgs/Pose
00063 # A representation of pose in free space, composed of postion and orientation.
00064 Point position
00065 Quaternion orientation
00066
00067 ================================================================================
00068 MSG: geometry_msgs/Point
00069 # This contains the position of a point in free space
00070 float64 x
00071 float64 y
00072 float64 z
00073
00074 ================================================================================
00075 MSG: geometry_msgs/Quaternion
00076 # This represents an orientation in free space in quaternion form.
00077
00078 float64 x
00079 float64 y
00080 float64 z
00081 float64 w
00082
00083 ================================================================================
00084 MSG: worldmodel_msgs/ObjectInfo
00085 # This message contains information about the estimated class affiliation, object id and corresponding support
00086
00087 # A string identifying the object's class (all objects of a class look the same)
00088 string class_id
00089
00090 # A string identifying the specific object
00091 string object_id
00092
00093 # A string that contains the name or a description of the specific object
00094 string name
00095
00096 # The support (degree of belief) of the object's presence given as log odd ratio
00097 float32 support
00098
00099
00100 ================================================================================
00101 MSG: worldmodel_msgs/ObjectState
00102 # The state of an object estimate used to track
00103 # states smaller than 0 disable all updates
00104
00105 # Predefined states. Use states smaller than 0 or bigger than 63 for user defined states.
00106 int8 UNKNOWN = 0
00107 int8 PENDING = 1
00108 int8 ACTIVE = 2
00109 int8 INACTIVE = 3
00110 int8 CONFIRMED = -1
00111 int8 DISCARDED = -2
00112 int8 APPROACHING = -3
00113
00114 int8 state
00115
00116 """
00117 __slots__ = ['header','pose','info','state']
00118 _slot_types = ['std_msgs/Header','geometry_msgs/PoseWithCovariance','worldmodel_msgs/ObjectInfo','worldmodel_msgs/ObjectState']
00119
00120 def __init__(self, *args, **kwds):
00121 """
00122 Constructor. Any message fields that are implicitly/explicitly
00123 set to None will be assigned a default value. The recommend
00124 use is keyword arguments as this is more robust to future message
00125 changes. You cannot mix in-order arguments and keyword arguments.
00126
00127 The available fields are:
00128 header,pose,info,state
00129
00130 :param args: complete set of field values, in .msg order
00131 :param kwds: use keyword arguments corresponding to message field names
00132 to set specific fields.
00133 """
00134 if args or kwds:
00135 super(Object, self).__init__(*args, **kwds)
00136
00137 if self.header is None:
00138 self.header = std_msgs.msg.Header()
00139 if self.pose is None:
00140 self.pose = geometry_msgs.msg.PoseWithCovariance()
00141 if self.info is None:
00142 self.info = worldmodel_msgs.msg.ObjectInfo()
00143 if self.state is None:
00144 self.state = worldmodel_msgs.msg.ObjectState()
00145 else:
00146 self.header = std_msgs.msg.Header()
00147 self.pose = geometry_msgs.msg.PoseWithCovariance()
00148 self.info = worldmodel_msgs.msg.ObjectInfo()
00149 self.state = worldmodel_msgs.msg.ObjectState()
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.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00165 _x = self.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.pose.pose.position.x, _x.pose.pose.position.y, _x.pose.pose.position.z, _x.pose.pose.orientation.x, _x.pose.pose.orientation.y, _x.pose.pose.orientation.z, _x.pose.pose.orientation.w))
00173 buff.write(_struct_36d.pack(*self.pose.covariance))
00174 _x = self.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.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.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.info.support, _x.state.state))
00194 except struct.error as se: self._check_types(se)
00195 except TypeError as te: self._check_types(te)
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.header is None:
00204 self.header = std_msgs.msg.Header()
00205 if self.pose is None:
00206 self.pose = geometry_msgs.msg.PoseWithCovariance()
00207 if self.info is None:
00208 self.info = worldmodel_msgs.msg.ObjectInfo()
00209 if self.state is None:
00210 self.state = worldmodel_msgs.msg.ObjectState()
00211 end = 0
00212 _x = self
00213 start = end
00214 end += 12
00215 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00216 start = end
00217 end += 4
00218 (length,) = _struct_I.unpack(str[start:end])
00219 start = end
00220 end += length
00221 if python3:
00222 self.header.frame_id = str[start:end].decode('utf-8')
00223 else:
00224 self.header.frame_id = str[start:end]
00225 _x = self
00226 start = end
00227 end += 56
00228 (_x.pose.pose.position.x, _x.pose.pose.position.y, _x.pose.pose.position.z, _x.pose.pose.orientation.x, _x.pose.pose.orientation.y, _x.pose.pose.orientation.z, _x.pose.pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00229 start = end
00230 end += 288
00231 self.pose.covariance = _struct_36d.unpack(str[start:end])
00232 start = end
00233 end += 4
00234 (length,) = _struct_I.unpack(str[start:end])
00235 start = end
00236 end += length
00237 if python3:
00238 self.info.class_id = str[start:end].decode('utf-8')
00239 else:
00240 self.info.class_id = str[start:end]
00241 start = end
00242 end += 4
00243 (length,) = _struct_I.unpack(str[start:end])
00244 start = end
00245 end += length
00246 if python3:
00247 self.info.object_id = str[start:end].decode('utf-8')
00248 else:
00249 self.info.object_id = str[start:end]
00250 start = end
00251 end += 4
00252 (length,) = _struct_I.unpack(str[start:end])
00253 start = end
00254 end += length
00255 if python3:
00256 self.info.name = str[start:end].decode('utf-8')
00257 else:
00258 self.info.name = str[start:end]
00259 _x = self
00260 start = end
00261 end += 5
00262 (_x.info.support, _x.state.state,) = _struct_fb.unpack(str[start:end])
00263 return self
00264 except struct.error as e:
00265 raise genpy.DeserializationError(e)
00266
00267
00268 def serialize_numpy(self, buff, numpy):
00269 """
00270 serialize message with numpy array types into buffer
00271 :param buff: buffer, ``StringIO``
00272 :param numpy: numpy python module
00273 """
00274 try:
00275 _x = self
00276 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00277 _x = self.header.frame_id
00278 length = len(_x)
00279 if python3 or type(_x) == unicode:
00280 _x = _x.encode('utf-8')
00281 length = len(_x)
00282 buff.write(struct.pack('<I%ss'%length, length, _x))
00283 _x = self
00284 buff.write(_struct_7d.pack(_x.pose.pose.position.x, _x.pose.pose.position.y, _x.pose.pose.position.z, _x.pose.pose.orientation.x, _x.pose.pose.orientation.y, _x.pose.pose.orientation.z, _x.pose.pose.orientation.w))
00285 buff.write(self.pose.covariance.tostring())
00286 _x = self.info.class_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.info.object_id
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.info.name
00299 length = len(_x)
00300 if python3 or type(_x) == unicode:
00301 _x = _x.encode('utf-8')
00302 length = len(_x)
00303 buff.write(struct.pack('<I%ss'%length, length, _x))
00304 _x = self
00305 buff.write(_struct_fb.pack(_x.info.support, _x.state.state))
00306 except struct.error as se: self._check_types(se)
00307 except TypeError as te: self._check_types(te)
00308
00309 def deserialize_numpy(self, str, numpy):
00310 """
00311 unpack serialized message in str into this message instance using numpy for array types
00312 :param str: byte array of serialized message, ``str``
00313 :param numpy: numpy python module
00314 """
00315 try:
00316 if self.header is None:
00317 self.header = std_msgs.msg.Header()
00318 if self.pose is None:
00319 self.pose = geometry_msgs.msg.PoseWithCovariance()
00320 if self.info is None:
00321 self.info = worldmodel_msgs.msg.ObjectInfo()
00322 if self.state is None:
00323 self.state = worldmodel_msgs.msg.ObjectState()
00324 end = 0
00325 _x = self
00326 start = end
00327 end += 12
00328 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00329 start = end
00330 end += 4
00331 (length,) = _struct_I.unpack(str[start:end])
00332 start = end
00333 end += length
00334 if python3:
00335 self.header.frame_id = str[start:end].decode('utf-8')
00336 else:
00337 self.header.frame_id = str[start:end]
00338 _x = self
00339 start = end
00340 end += 56
00341 (_x.pose.pose.position.x, _x.pose.pose.position.y, _x.pose.pose.position.z, _x.pose.pose.orientation.x, _x.pose.pose.orientation.y, _x.pose.pose.orientation.z, _x.pose.pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00342 start = end
00343 end += 288
00344 self.pose.covariance = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=36)
00345 start = end
00346 end += 4
00347 (length,) = _struct_I.unpack(str[start:end])
00348 start = end
00349 end += length
00350 if python3:
00351 self.info.class_id = str[start:end].decode('utf-8')
00352 else:
00353 self.info.class_id = str[start:end]
00354 start = end
00355 end += 4
00356 (length,) = _struct_I.unpack(str[start:end])
00357 start = end
00358 end += length
00359 if python3:
00360 self.info.object_id = str[start:end].decode('utf-8')
00361 else:
00362 self.info.object_id = str[start:end]
00363 start = end
00364 end += 4
00365 (length,) = _struct_I.unpack(str[start:end])
00366 start = end
00367 end += length
00368 if python3:
00369 self.info.name = str[start:end].decode('utf-8')
00370 else:
00371 self.info.name = str[start:end]
00372 _x = self
00373 start = end
00374 end += 5
00375 (_x.info.support, _x.state.state,) = _struct_fb.unpack(str[start:end])
00376 return self
00377 except struct.error as e:
00378 raise genpy.DeserializationError(e)
00379
00380 _struct_I = genpy.struct_I
00381 _struct_fb = struct.Struct("<fb")
00382 _struct_3I = struct.Struct("<3I")
00383 _struct_7d = struct.Struct("<7d")
00384 _struct_36d = struct.Struct("<36d")