$search
00001 """autogenerated by genmsg_py from PeopleDetection.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import geometry_msgs.msg 00006 import cob_people_detection_msgs.msg 00007 import sensor_msgs.msg 00008 import std_msgs.msg 00009 00010 class PeopleDetection(roslib.message.Message): 00011 _md5sum = "fc0d613513a2fabeb1eebd8491c53e68" 00012 _type = "cob_people_detection_msgs/PeopleDetection" 00013 _has_header = True #flag to mark the presence of a Header object 00014 _full_text = """Header header 00015 string label 00016 string detector 00017 float32 score 00018 Mask mask 00019 geometry_msgs/PoseStamped pose 00020 00021 ================================================================================ 00022 MSG: std_msgs/Header 00023 # Standard metadata for higher-level stamped data types. 00024 # This is generally used to communicate timestamped data 00025 # in a particular coordinate frame. 00026 # 00027 # sequence ID: consecutively increasing ID 00028 uint32 seq 00029 #Two-integer timestamp that is expressed as: 00030 # * stamp.secs: seconds (stamp_secs) since epoch 00031 # * stamp.nsecs: nanoseconds since stamp_secs 00032 # time-handling sugar is provided by the client library 00033 time stamp 00034 #Frame this data is associated with 00035 # 0: no frame 00036 # 1: global frame 00037 string frame_id 00038 00039 ================================================================================ 00040 MSG: cob_people_detection_msgs/Mask 00041 # this message is used to mark where an object is present in an image 00042 # this can be done either by a roi region on the image (less precise) or a mask (more precise) 00043 00044 Rect roi 00045 00046 # in the case when mask is used, 'roi' specifies the image region and 'mask' 00047 # (which should be of the same size) a binary mask in that region 00048 sensor_msgs/Image mask 00049 00050 # in the case there is 3D data available, 'indices' are used to index the 00051 # part of the point cloud representing the object 00052 #pcl/PointIndices indices 00053 00054 ================================================================================ 00055 MSG: cob_people_detection_msgs/Rect 00056 int32 x 00057 int32 y 00058 int32 width 00059 int32 height 00060 00061 ================================================================================ 00062 MSG: sensor_msgs/Image 00063 # This message contains an uncompressed image 00064 # (0, 0) is at top-left corner of image 00065 # 00066 00067 Header header # Header timestamp should be acquisition time of image 00068 # Header frame_id should be optical frame of camera 00069 # origin of frame should be optical center of cameara 00070 # +x should point to the right in the image 00071 # +y should point down in the image 00072 # +z should point into to plane of the image 00073 # If the frame_id here and the frame_id of the CameraInfo 00074 # message associated with the image conflict 00075 # the behavior is undefined 00076 00077 uint32 height # image height, that is, number of rows 00078 uint32 width # image width, that is, number of columns 00079 00080 # The legal values for encoding are in file src/image_encodings.cpp 00081 # If you want to standardize a new string format, join 00082 # ros-users@lists.sourceforge.net and send an email proposing a new encoding. 00083 00084 string encoding # Encoding of pixels -- channel meaning, ordering, size 00085 # taken from the list of strings in src/image_encodings.cpp 00086 00087 uint8 is_bigendian # is this data bigendian? 00088 uint32 step # Full row length in bytes 00089 uint8[] data # actual matrix data, size is (step * rows) 00090 00091 ================================================================================ 00092 MSG: geometry_msgs/PoseStamped 00093 # A Pose with reference coordinate frame and timestamp 00094 Header header 00095 Pose pose 00096 00097 ================================================================================ 00098 MSG: geometry_msgs/Pose 00099 # A representation of pose in free space, composed of postion and orientation. 00100 Point position 00101 Quaternion orientation 00102 00103 ================================================================================ 00104 MSG: geometry_msgs/Point 00105 # This contains the position of a point in free space 00106 float64 x 00107 float64 y 00108 float64 z 00109 00110 ================================================================================ 00111 MSG: geometry_msgs/Quaternion 00112 # This represents an orientation in free space in quaternion form. 00113 00114 float64 x 00115 float64 y 00116 float64 z 00117 float64 w 00118 00119 """ 00120 __slots__ = ['header','label','detector','score','mask','pose'] 00121 _slot_types = ['Header','string','string','float32','cob_people_detection_msgs/Mask','geometry_msgs/PoseStamped'] 00122 00123 def __init__(self, *args, **kwds): 00124 """ 00125 Constructor. Any message fields that are implicitly/explicitly 00126 set to None will be assigned a default value. The recommend 00127 use is keyword arguments as this is more robust to future message 00128 changes. You cannot mix in-order arguments and keyword arguments. 00129 00130 The available fields are: 00131 header,label,detector,score,mask,pose 00132 00133 @param args: complete set of field values, in .msg order 00134 @param kwds: use keyword arguments corresponding to message field names 00135 to set specific fields. 00136 """ 00137 if args or kwds: 00138 super(PeopleDetection, self).__init__(*args, **kwds) 00139 #message fields cannot be None, assign default values for those that are 00140 if self.header is None: 00141 self.header = std_msgs.msg._Header.Header() 00142 if self.label is None: 00143 self.label = '' 00144 if self.detector is None: 00145 self.detector = '' 00146 if self.score is None: 00147 self.score = 0. 00148 if self.mask is None: 00149 self.mask = cob_people_detection_msgs.msg.Mask() 00150 if self.pose is None: 00151 self.pose = geometry_msgs.msg.PoseStamped() 00152 else: 00153 self.header = std_msgs.msg._Header.Header() 00154 self.label = '' 00155 self.detector = '' 00156 self.score = 0. 00157 self.mask = cob_people_detection_msgs.msg.Mask() 00158 self.pose = geometry_msgs.msg.PoseStamped() 00159 00160 def _get_types(self): 00161 """ 00162 internal API method 00163 """ 00164 return self._slot_types 00165 00166 def serialize(self, buff): 00167 """ 00168 serialize message into buffer 00169 @param buff: buffer 00170 @type buff: StringIO 00171 """ 00172 try: 00173 _x = self 00174 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00175 _x = self.header.frame_id 00176 length = len(_x) 00177 buff.write(struct.pack('<I%ss'%length, length, _x)) 00178 _x = self.label 00179 length = len(_x) 00180 buff.write(struct.pack('<I%ss'%length, length, _x)) 00181 _x = self.detector 00182 length = len(_x) 00183 buff.write(struct.pack('<I%ss'%length, length, _x)) 00184 _x = self 00185 buff.write(_struct_f4i3I.pack(_x.score, _x.mask.roi.x, _x.mask.roi.y, _x.mask.roi.width, _x.mask.roi.height, _x.mask.mask.header.seq, _x.mask.mask.header.stamp.secs, _x.mask.mask.header.stamp.nsecs)) 00186 _x = self.mask.mask.header.frame_id 00187 length = len(_x) 00188 buff.write(struct.pack('<I%ss'%length, length, _x)) 00189 _x = self 00190 buff.write(_struct_2I.pack(_x.mask.mask.height, _x.mask.mask.width)) 00191 _x = self.mask.mask.encoding 00192 length = len(_x) 00193 buff.write(struct.pack('<I%ss'%length, length, _x)) 00194 _x = self 00195 buff.write(_struct_BI.pack(_x.mask.mask.is_bigendian, _x.mask.mask.step)) 00196 _x = self.mask.mask.data 00197 length = len(_x) 00198 # - if encoded as a list instead, serialize as bytes instead of string 00199 if type(_x) in [list, tuple]: 00200 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00201 else: 00202 buff.write(struct.pack('<I%ss'%length, length, _x)) 00203 _x = self 00204 buff.write(_struct_3I.pack(_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs)) 00205 _x = self.pose.header.frame_id 00206 length = len(_x) 00207 buff.write(struct.pack('<I%ss'%length, length, _x)) 00208 _x = self 00209 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)) 00210 except struct.error as se: self._check_types(se) 00211 except TypeError as te: self._check_types(te) 00212 00213 def deserialize(self, str): 00214 """ 00215 unpack serialized message in str into this message instance 00216 @param str: byte array of serialized message 00217 @type str: str 00218 """ 00219 try: 00220 if self.header is None: 00221 self.header = std_msgs.msg._Header.Header() 00222 if self.mask is None: 00223 self.mask = cob_people_detection_msgs.msg.Mask() 00224 if self.pose is None: 00225 self.pose = geometry_msgs.msg.PoseStamped() 00226 end = 0 00227 _x = self 00228 start = end 00229 end += 12 00230 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00231 start = end 00232 end += 4 00233 (length,) = _struct_I.unpack(str[start:end]) 00234 start = end 00235 end += length 00236 self.header.frame_id = str[start:end] 00237 start = end 00238 end += 4 00239 (length,) = _struct_I.unpack(str[start:end]) 00240 start = end 00241 end += length 00242 self.label = str[start:end] 00243 start = end 00244 end += 4 00245 (length,) = _struct_I.unpack(str[start:end]) 00246 start = end 00247 end += length 00248 self.detector = str[start:end] 00249 _x = self 00250 start = end 00251 end += 32 00252 (_x.score, _x.mask.roi.x, _x.mask.roi.y, _x.mask.roi.width, _x.mask.roi.height, _x.mask.mask.header.seq, _x.mask.mask.header.stamp.secs, _x.mask.mask.header.stamp.nsecs,) = _struct_f4i3I.unpack(str[start:end]) 00253 start = end 00254 end += 4 00255 (length,) = _struct_I.unpack(str[start:end]) 00256 start = end 00257 end += length 00258 self.mask.mask.header.frame_id = str[start:end] 00259 _x = self 00260 start = end 00261 end += 8 00262 (_x.mask.mask.height, _x.mask.mask.width,) = _struct_2I.unpack(str[start:end]) 00263 start = end 00264 end += 4 00265 (length,) = _struct_I.unpack(str[start:end]) 00266 start = end 00267 end += length 00268 self.mask.mask.encoding = str[start:end] 00269 _x = self 00270 start = end 00271 end += 5 00272 (_x.mask.mask.is_bigendian, _x.mask.mask.step,) = _struct_BI.unpack(str[start:end]) 00273 start = end 00274 end += 4 00275 (length,) = _struct_I.unpack(str[start:end]) 00276 start = end 00277 end += length 00278 self.mask.mask.data = str[start:end] 00279 _x = self 00280 start = end 00281 end += 12 00282 (_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00283 start = end 00284 end += 4 00285 (length,) = _struct_I.unpack(str[start:end]) 00286 start = end 00287 end += length 00288 self.pose.header.frame_id = str[start:end] 00289 _x = self 00290 start = end 00291 end += 56 00292 (_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]) 00293 return self 00294 except struct.error as e: 00295 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00296 00297 00298 def serialize_numpy(self, buff, numpy): 00299 """ 00300 serialize message with numpy array types into buffer 00301 @param buff: buffer 00302 @type buff: StringIO 00303 @param numpy: numpy python module 00304 @type numpy module 00305 """ 00306 try: 00307 _x = self 00308 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00309 _x = self.header.frame_id 00310 length = len(_x) 00311 buff.write(struct.pack('<I%ss'%length, length, _x)) 00312 _x = self.label 00313 length = len(_x) 00314 buff.write(struct.pack('<I%ss'%length, length, _x)) 00315 _x = self.detector 00316 length = len(_x) 00317 buff.write(struct.pack('<I%ss'%length, length, _x)) 00318 _x = self 00319 buff.write(_struct_f4i3I.pack(_x.score, _x.mask.roi.x, _x.mask.roi.y, _x.mask.roi.width, _x.mask.roi.height, _x.mask.mask.header.seq, _x.mask.mask.header.stamp.secs, _x.mask.mask.header.stamp.nsecs)) 00320 _x = self.mask.mask.header.frame_id 00321 length = len(_x) 00322 buff.write(struct.pack('<I%ss'%length, length, _x)) 00323 _x = self 00324 buff.write(_struct_2I.pack(_x.mask.mask.height, _x.mask.mask.width)) 00325 _x = self.mask.mask.encoding 00326 length = len(_x) 00327 buff.write(struct.pack('<I%ss'%length, length, _x)) 00328 _x = self 00329 buff.write(_struct_BI.pack(_x.mask.mask.is_bigendian, _x.mask.mask.step)) 00330 _x = self.mask.mask.data 00331 length = len(_x) 00332 # - if encoded as a list instead, serialize as bytes instead of string 00333 if type(_x) in [list, tuple]: 00334 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00335 else: 00336 buff.write(struct.pack('<I%ss'%length, length, _x)) 00337 _x = self 00338 buff.write(_struct_3I.pack(_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs)) 00339 _x = self.pose.header.frame_id 00340 length = len(_x) 00341 buff.write(struct.pack('<I%ss'%length, length, _x)) 00342 _x = self 00343 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)) 00344 except struct.error as se: self._check_types(se) 00345 except TypeError as te: self._check_types(te) 00346 00347 def deserialize_numpy(self, str, numpy): 00348 """ 00349 unpack serialized message in str into this message instance using numpy for array types 00350 @param str: byte array of serialized message 00351 @type str: str 00352 @param numpy: numpy python module 00353 @type numpy: module 00354 """ 00355 try: 00356 if self.header is None: 00357 self.header = std_msgs.msg._Header.Header() 00358 if self.mask is None: 00359 self.mask = cob_people_detection_msgs.msg.Mask() 00360 if self.pose is None: 00361 self.pose = geometry_msgs.msg.PoseStamped() 00362 end = 0 00363 _x = self 00364 start = end 00365 end += 12 00366 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00367 start = end 00368 end += 4 00369 (length,) = _struct_I.unpack(str[start:end]) 00370 start = end 00371 end += length 00372 self.header.frame_id = str[start:end] 00373 start = end 00374 end += 4 00375 (length,) = _struct_I.unpack(str[start:end]) 00376 start = end 00377 end += length 00378 self.label = str[start:end] 00379 start = end 00380 end += 4 00381 (length,) = _struct_I.unpack(str[start:end]) 00382 start = end 00383 end += length 00384 self.detector = str[start:end] 00385 _x = self 00386 start = end 00387 end += 32 00388 (_x.score, _x.mask.roi.x, _x.mask.roi.y, _x.mask.roi.width, _x.mask.roi.height, _x.mask.mask.header.seq, _x.mask.mask.header.stamp.secs, _x.mask.mask.header.stamp.nsecs,) = _struct_f4i3I.unpack(str[start:end]) 00389 start = end 00390 end += 4 00391 (length,) = _struct_I.unpack(str[start:end]) 00392 start = end 00393 end += length 00394 self.mask.mask.header.frame_id = str[start:end] 00395 _x = self 00396 start = end 00397 end += 8 00398 (_x.mask.mask.height, _x.mask.mask.width,) = _struct_2I.unpack(str[start:end]) 00399 start = end 00400 end += 4 00401 (length,) = _struct_I.unpack(str[start:end]) 00402 start = end 00403 end += length 00404 self.mask.mask.encoding = str[start:end] 00405 _x = self 00406 start = end 00407 end += 5 00408 (_x.mask.mask.is_bigendian, _x.mask.mask.step,) = _struct_BI.unpack(str[start:end]) 00409 start = end 00410 end += 4 00411 (length,) = _struct_I.unpack(str[start:end]) 00412 start = end 00413 end += length 00414 self.mask.mask.data = str[start:end] 00415 _x = self 00416 start = end 00417 end += 12 00418 (_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00419 start = end 00420 end += 4 00421 (length,) = _struct_I.unpack(str[start:end]) 00422 start = end 00423 end += length 00424 self.pose.header.frame_id = str[start:end] 00425 _x = self 00426 start = end 00427 end += 56 00428 (_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]) 00429 return self 00430 except struct.error as e: 00431 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00432 00433 _struct_I = roslib.message.struct_I 00434 _struct_3I = struct.Struct("<3I") 00435 _struct_7d = struct.Struct("<7d") 00436 _struct_BI = struct.Struct("<BI") 00437 _struct_f4i3I = struct.Struct("<f4i3I") 00438 _struct_2I = struct.Struct("<2I")