$search
00001 """autogenerated by genmsg_py from Object.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import geometry_msgs.msg 00006 import worldmodel_msgs.msg 00007 import std_msgs.msg 00008 00009 class Object(roslib.message.Message): 00010 _md5sum = "bc2b29ddef39c215dc87ef727bf53447" 00011 _type = "worldmodel_msgs/Object" 00012 _has_header = True #flag to mark the presence of a Header object 00013 _full_text = """# This message represents an estimate of an object's pose and identity. 00014 00015 # The header. 00016 # stamp: Timestamp of last update. 00017 # frame_id: Coordinate frame, in which the pose is given 00018 Header header 00019 00020 # The pose 00021 geometry_msgs/PoseWithCovariance pose 00022 00023 # Further information about the object 00024 ObjectInfo info 00025 00026 # The tracked state of the object 00027 ObjectState state 00028 00029 ================================================================================ 00030 MSG: std_msgs/Header 00031 # Standard metadata for higher-level stamped data types. 00032 # This is generally used to communicate timestamped data 00033 # in a particular coordinate frame. 00034 # 00035 # sequence ID: consecutively increasing ID 00036 uint32 seq 00037 #Two-integer timestamp that is expressed as: 00038 # * stamp.secs: seconds (stamp_secs) since epoch 00039 # * stamp.nsecs: nanoseconds since stamp_secs 00040 # time-handling sugar is provided by the client library 00041 time stamp 00042 #Frame this data is associated with 00043 # 0: no frame 00044 # 1: global frame 00045 string frame_id 00046 00047 ================================================================================ 00048 MSG: geometry_msgs/PoseWithCovariance 00049 # This represents a pose in free space with uncertainty. 00050 00051 Pose pose 00052 00053 # Row-major representation of the 6x6 covariance matrix 00054 # The orientation parameters use a fixed-axis representation. 00055 # In order, the parameters are: 00056 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) 00057 float64[36] covariance 00058 00059 ================================================================================ 00060 MSG: geometry_msgs/Pose 00061 # A representation of pose in free space, composed of postion and orientation. 00062 Point position 00063 Quaternion orientation 00064 00065 ================================================================================ 00066 MSG: geometry_msgs/Point 00067 # This contains the position of a point in free space 00068 float64 x 00069 float64 y 00070 float64 z 00071 00072 ================================================================================ 00073 MSG: geometry_msgs/Quaternion 00074 # This represents an orientation in free space in quaternion form. 00075 00076 float64 x 00077 float64 y 00078 float64 z 00079 float64 w 00080 00081 ================================================================================ 00082 MSG: worldmodel_msgs/ObjectInfo 00083 # This message contains information about the estimated class affiliation, object id and corresponding support 00084 00085 # A string identifying the object's class (all objects of a class look the same) 00086 string class_id 00087 00088 # A string identifying the specific object 00089 string object_id 00090 00091 # A string that contains the name or a description of the specific object 00092 string name 00093 00094 # The support (degree of belief) of the object's presence given as log odd ratio 00095 float32 support 00096 00097 00098 ================================================================================ 00099 MSG: worldmodel_msgs/ObjectState 00100 # The state of an object estimate used to track 00101 # states smaller than 0 disable all updates 00102 00103 int8 UNKNOWN = 0 00104 int8 PENDING = 1 00105 int8 ACTIVE = 2 00106 int8 CONFIRMED = -1 00107 int8 DISCARDED = -2 00108 int8 APPROACHING = -3 00109 00110 int8 state 00111 00112 """ 00113 __slots__ = ['header','pose','info','state'] 00114 _slot_types = ['Header','geometry_msgs/PoseWithCovariance','worldmodel_msgs/ObjectInfo','worldmodel_msgs/ObjectState'] 00115 00116 def __init__(self, *args, **kwds): 00117 """ 00118 Constructor. Any message fields that are implicitly/explicitly 00119 set to None will be assigned a default value. The recommend 00120 use is keyword arguments as this is more robust to future message 00121 changes. You cannot mix in-order arguments and keyword arguments. 00122 00123 The available fields are: 00124 header,pose,info,state 00125 00126 @param args: complete set of field values, in .msg order 00127 @param kwds: use keyword arguments corresponding to message field names 00128 to set specific fields. 00129 """ 00130 if args or kwds: 00131 super(Object, self).__init__(*args, **kwds) 00132 #message fields cannot be None, assign default values for those that are 00133 if self.header is None: 00134 self.header = std_msgs.msg._Header.Header() 00135 if self.pose is None: 00136 self.pose = geometry_msgs.msg.PoseWithCovariance() 00137 if self.info is None: 00138 self.info = worldmodel_msgs.msg.ObjectInfo() 00139 if self.state is None: 00140 self.state = worldmodel_msgs.msg.ObjectState() 00141 else: 00142 self.header = std_msgs.msg._Header.Header() 00143 self.pose = geometry_msgs.msg.PoseWithCovariance() 00144 self.info = worldmodel_msgs.msg.ObjectInfo() 00145 self.state = worldmodel_msgs.msg.ObjectState() 00146 00147 def _get_types(self): 00148 """ 00149 internal API method 00150 """ 00151 return self._slot_types 00152 00153 def serialize(self, buff): 00154 """ 00155 serialize message into buffer 00156 @param buff: buffer 00157 @type buff: StringIO 00158 """ 00159 try: 00160 _x = self 00161 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00162 _x = self.header.frame_id 00163 length = len(_x) 00164 buff.write(struct.pack('<I%ss'%length, length, _x)) 00165 _x = self 00166 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)) 00167 buff.write(_struct_36d.pack(*self.pose.covariance)) 00168 _x = self.info.class_id 00169 length = len(_x) 00170 buff.write(struct.pack('<I%ss'%length, length, _x)) 00171 _x = self.info.object_id 00172 length = len(_x) 00173 buff.write(struct.pack('<I%ss'%length, length, _x)) 00174 _x = self.info.name 00175 length = len(_x) 00176 buff.write(struct.pack('<I%ss'%length, length, _x)) 00177 _x = self 00178 buff.write(_struct_fb.pack(_x.info.support, _x.state.state)) 00179 except struct.error as se: self._check_types(se) 00180 except TypeError as te: self._check_types(te) 00181 00182 def deserialize(self, str): 00183 """ 00184 unpack serialized message in str into this message instance 00185 @param str: byte array of serialized message 00186 @type str: str 00187 """ 00188 try: 00189 if self.header is None: 00190 self.header = std_msgs.msg._Header.Header() 00191 if self.pose is None: 00192 self.pose = geometry_msgs.msg.PoseWithCovariance() 00193 if self.info is None: 00194 self.info = worldmodel_msgs.msg.ObjectInfo() 00195 if self.state is None: 00196 self.state = worldmodel_msgs.msg.ObjectState() 00197 end = 0 00198 _x = self 00199 start = end 00200 end += 12 00201 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00202 start = end 00203 end += 4 00204 (length,) = _struct_I.unpack(str[start:end]) 00205 start = end 00206 end += length 00207 self.header.frame_id = str[start:end] 00208 _x = self 00209 start = end 00210 end += 56 00211 (_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]) 00212 start = end 00213 end += 288 00214 self.pose.covariance = _struct_36d.unpack(str[start:end]) 00215 start = end 00216 end += 4 00217 (length,) = _struct_I.unpack(str[start:end]) 00218 start = end 00219 end += length 00220 self.info.class_id = str[start:end] 00221 start = end 00222 end += 4 00223 (length,) = _struct_I.unpack(str[start:end]) 00224 start = end 00225 end += length 00226 self.info.object_id = str[start:end] 00227 start = end 00228 end += 4 00229 (length,) = _struct_I.unpack(str[start:end]) 00230 start = end 00231 end += length 00232 self.info.name = str[start:end] 00233 _x = self 00234 start = end 00235 end += 5 00236 (_x.info.support, _x.state.state,) = _struct_fb.unpack(str[start:end]) 00237 return self 00238 except struct.error as e: 00239 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00240 00241 00242 def serialize_numpy(self, buff, numpy): 00243 """ 00244 serialize message with numpy array types into buffer 00245 @param buff: buffer 00246 @type buff: StringIO 00247 @param numpy: numpy python module 00248 @type numpy module 00249 """ 00250 try: 00251 _x = self 00252 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00253 _x = self.header.frame_id 00254 length = len(_x) 00255 buff.write(struct.pack('<I%ss'%length, length, _x)) 00256 _x = self 00257 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)) 00258 buff.write(self.pose.covariance.tostring()) 00259 _x = self.info.class_id 00260 length = len(_x) 00261 buff.write(struct.pack('<I%ss'%length, length, _x)) 00262 _x = self.info.object_id 00263 length = len(_x) 00264 buff.write(struct.pack('<I%ss'%length, length, _x)) 00265 _x = self.info.name 00266 length = len(_x) 00267 buff.write(struct.pack('<I%ss'%length, length, _x)) 00268 _x = self 00269 buff.write(_struct_fb.pack(_x.info.support, _x.state.state)) 00270 except struct.error as se: self._check_types(se) 00271 except TypeError as te: self._check_types(te) 00272 00273 def deserialize_numpy(self, str, numpy): 00274 """ 00275 unpack serialized message in str into this message instance using numpy for array types 00276 @param str: byte array of serialized message 00277 @type str: str 00278 @param numpy: numpy python module 00279 @type numpy: module 00280 """ 00281 try: 00282 if self.header is None: 00283 self.header = std_msgs.msg._Header.Header() 00284 if self.pose is None: 00285 self.pose = geometry_msgs.msg.PoseWithCovariance() 00286 if self.info is None: 00287 self.info = worldmodel_msgs.msg.ObjectInfo() 00288 if self.state is None: 00289 self.state = worldmodel_msgs.msg.ObjectState() 00290 end = 0 00291 _x = self 00292 start = end 00293 end += 12 00294 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00295 start = end 00296 end += 4 00297 (length,) = _struct_I.unpack(str[start:end]) 00298 start = end 00299 end += length 00300 self.header.frame_id = str[start:end] 00301 _x = self 00302 start = end 00303 end += 56 00304 (_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]) 00305 start = end 00306 end += 288 00307 self.pose.covariance = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=36) 00308 start = end 00309 end += 4 00310 (length,) = _struct_I.unpack(str[start:end]) 00311 start = end 00312 end += length 00313 self.info.class_id = str[start:end] 00314 start = end 00315 end += 4 00316 (length,) = _struct_I.unpack(str[start:end]) 00317 start = end 00318 end += length 00319 self.info.object_id = str[start:end] 00320 start = end 00321 end += 4 00322 (length,) = _struct_I.unpack(str[start:end]) 00323 start = end 00324 end += length 00325 self.info.name = str[start:end] 00326 _x = self 00327 start = end 00328 end += 5 00329 (_x.info.support, _x.state.state,) = _struct_fb.unpack(str[start:end]) 00330 return self 00331 except struct.error as e: 00332 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00333 00334 _struct_I = roslib.message.struct_I 00335 _struct_fb = struct.Struct("<fb") 00336 _struct_3I = struct.Struct("<3I") 00337 _struct_7d = struct.Struct("<7d") 00338 _struct_36d = struct.Struct("<36d")