_DetectObjects.py
Go to the documentation of this file.
00001 """autogenerated by genpy from cob_object_detection_msgs/DetectObjectsRequest.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 sensor_msgs.msg
00008 import std_msgs.msg
00009 
00010 class DetectObjectsRequest(genpy.Message):
00011   _md5sum = "8d651fac3fa327d154d291de842e3994"
00012   _type = "cob_object_detection_msgs/DetectObjectsRequest"
00013   _has_header = False #flag to mark the presence of a Header object
00014   _full_text = """std_msgs/String object_name
00015 sensor_msgs/RegionOfInterest roi
00016 
00017 ================================================================================
00018 MSG: std_msgs/String
00019 string data
00020 
00021 ================================================================================
00022 MSG: sensor_msgs/RegionOfInterest
00023 # This message is used to specify a region of interest within an image.
00024 #
00025 # When used to specify the ROI setting of the camera when the image was
00026 # taken, the height and width fields should either match the height and
00027 # width fields for the associated image; or height = width = 0
00028 # indicates that the full resolution image was captured.
00029 
00030 uint32 x_offset  # Leftmost pixel of the ROI
00031                  # (0 if the ROI includes the left edge of the image)
00032 uint32 y_offset  # Topmost pixel of the ROI
00033                  # (0 if the ROI includes the top edge of the image)
00034 uint32 height    # Height of ROI
00035 uint32 width     # Width of ROI
00036 
00037 # True if a distinct rectified ROI should be calculated from the "raw"
00038 # ROI in this message. Typically this should be False if the full image
00039 # is captured (ROI not used), and True if a subwindow is captured (ROI
00040 # used).
00041 bool do_rectify
00042 
00043 """
00044   __slots__ = ['object_name','roi']
00045   _slot_types = ['std_msgs/String','sensor_msgs/RegionOfInterest']
00046 
00047   def __init__(self, *args, **kwds):
00048     """
00049     Constructor. Any message fields that are implicitly/explicitly
00050     set to None will be assigned a default value. The recommend
00051     use is keyword arguments as this is more robust to future message
00052     changes.  You cannot mix in-order arguments and keyword arguments.
00053 
00054     The available fields are:
00055        object_name,roi
00056 
00057     :param args: complete set of field values, in .msg order
00058     :param kwds: use keyword arguments corresponding to message field names
00059     to set specific fields.
00060     """
00061     if args or kwds:
00062       super(DetectObjectsRequest, self).__init__(*args, **kwds)
00063       #message fields cannot be None, assign default values for those that are
00064       if self.object_name is None:
00065         self.object_name = std_msgs.msg.String()
00066       if self.roi is None:
00067         self.roi = sensor_msgs.msg.RegionOfInterest()
00068     else:
00069       self.object_name = std_msgs.msg.String()
00070       self.roi = sensor_msgs.msg.RegionOfInterest()
00071 
00072   def _get_types(self):
00073     """
00074     internal API method
00075     """
00076     return self._slot_types
00077 
00078   def serialize(self, buff):
00079     """
00080     serialize message into buffer
00081     :param buff: buffer, ``StringIO``
00082     """
00083     try:
00084       _x = self.object_name.data
00085       length = len(_x)
00086       if python3 or type(_x) == unicode:
00087         _x = _x.encode('utf-8')
00088         length = len(_x)
00089       buff.write(struct.pack('<I%ss'%length, length, _x))
00090       _x = self
00091       buff.write(_struct_4IB.pack(_x.roi.x_offset, _x.roi.y_offset, _x.roi.height, _x.roi.width, _x.roi.do_rectify))
00092     except struct.error as se: self._check_types(se)
00093     except TypeError as te: self._check_types(te)
00094 
00095   def deserialize(self, str):
00096     """
00097     unpack serialized message in str into this message instance
00098     :param str: byte array of serialized message, ``str``
00099     """
00100     try:
00101       if self.object_name is None:
00102         self.object_name = std_msgs.msg.String()
00103       if self.roi is None:
00104         self.roi = sensor_msgs.msg.RegionOfInterest()
00105       end = 0
00106       start = end
00107       end += 4
00108       (length,) = _struct_I.unpack(str[start:end])
00109       start = end
00110       end += length
00111       if python3:
00112         self.object_name.data = str[start:end].decode('utf-8')
00113       else:
00114         self.object_name.data = str[start:end]
00115       _x = self
00116       start = end
00117       end += 17
00118       (_x.roi.x_offset, _x.roi.y_offset, _x.roi.height, _x.roi.width, _x.roi.do_rectify,) = _struct_4IB.unpack(str[start:end])
00119       self.roi.do_rectify = bool(self.roi.do_rectify)
00120       return self
00121     except struct.error as e:
00122       raise genpy.DeserializationError(e) #most likely buffer underfill
00123 
00124 
00125   def serialize_numpy(self, buff, numpy):
00126     """
00127     serialize message with numpy array types into buffer
00128     :param buff: buffer, ``StringIO``
00129     :param numpy: numpy python module
00130     """
00131     try:
00132       _x = self.object_name.data
00133       length = len(_x)
00134       if python3 or type(_x) == unicode:
00135         _x = _x.encode('utf-8')
00136         length = len(_x)
00137       buff.write(struct.pack('<I%ss'%length, length, _x))
00138       _x = self
00139       buff.write(_struct_4IB.pack(_x.roi.x_offset, _x.roi.y_offset, _x.roi.height, _x.roi.width, _x.roi.do_rectify))
00140     except struct.error as se: self._check_types(se)
00141     except TypeError as te: self._check_types(te)
00142 
00143   def deserialize_numpy(self, str, numpy):
00144     """
00145     unpack serialized message in str into this message instance using numpy for array types
00146     :param str: byte array of serialized message, ``str``
00147     :param numpy: numpy python module
00148     """
00149     try:
00150       if self.object_name is None:
00151         self.object_name = std_msgs.msg.String()
00152       if self.roi is None:
00153         self.roi = sensor_msgs.msg.RegionOfInterest()
00154       end = 0
00155       start = end
00156       end += 4
00157       (length,) = _struct_I.unpack(str[start:end])
00158       start = end
00159       end += length
00160       if python3:
00161         self.object_name.data = str[start:end].decode('utf-8')
00162       else:
00163         self.object_name.data = str[start:end]
00164       _x = self
00165       start = end
00166       end += 17
00167       (_x.roi.x_offset, _x.roi.y_offset, _x.roi.height, _x.roi.width, _x.roi.do_rectify,) = _struct_4IB.unpack(str[start:end])
00168       self.roi.do_rectify = bool(self.roi.do_rectify)
00169       return self
00170     except struct.error as e:
00171       raise genpy.DeserializationError(e) #most likely buffer underfill
00172 
00173 _struct_I = genpy.struct_I
00174 _struct_4IB = struct.Struct("<4IB")
00175 """autogenerated by genpy from cob_object_detection_msgs/DetectObjectsResponse.msg. Do not edit."""
00176 import sys
00177 python3 = True if sys.hexversion > 0x03000000 else False
00178 import genpy
00179 import struct
00180 
00181 import geometry_msgs.msg
00182 import cob_object_detection_msgs.msg
00183 import sensor_msgs.msg
00184 import std_msgs.msg
00185 
00186 class DetectObjectsResponse(genpy.Message):
00187   _md5sum = "6e46a64486bc23cca1c161460b4c92b6"
00188   _type = "cob_object_detection_msgs/DetectObjectsResponse"
00189   _has_header = False #flag to mark the presence of a Header object
00190   _full_text = """cob_object_detection_msgs/DetectionArray object_list
00191 
00192 
00193 ================================================================================
00194 MSG: cob_object_detection_msgs/DetectionArray
00195 Header header
00196 Detection[] detections
00197 
00198 ================================================================================
00199 MSG: std_msgs/Header
00200 # Standard metadata for higher-level stamped data types.
00201 # This is generally used to communicate timestamped data 
00202 # in a particular coordinate frame.
00203 # 
00204 # sequence ID: consecutively increasing ID 
00205 uint32 seq
00206 #Two-integer timestamp that is expressed as:
00207 # * stamp.secs: seconds (stamp_secs) since epoch
00208 # * stamp.nsecs: nanoseconds since stamp_secs
00209 # time-handling sugar is provided by the client library
00210 time stamp
00211 #Frame this data is associated with
00212 # 0: no frame
00213 # 1: global frame
00214 string frame_id
00215 
00216 ================================================================================
00217 MSG: cob_object_detection_msgs/Detection
00218 Header header
00219 string label
00220 string detector
00221 float32 score
00222 Mask mask
00223 geometry_msgs/PoseStamped pose
00224 geometry_msgs/Point bounding_box_lwh
00225 
00226 ================================================================================
00227 MSG: cob_object_detection_msgs/Mask
00228 # this message is used to mark where an object is present in an image
00229 # this can be done either by a roi region on the image (less precise) or a mask (more precise)
00230 
00231 Rect roi
00232 
00233 # in the case when mask is used, 'roi' specifies the image region and 'mask'
00234 # (which should be of the same size) a binary mask in that region
00235 sensor_msgs/Image mask
00236 
00237 # in the case there is 3D data available, 'indices' are used to index the 
00238 # part of the point cloud representing the object
00239 #pcl/PointIndices indices
00240 
00241 ================================================================================
00242 MSG: cob_object_detection_msgs/Rect
00243 int32 x
00244 int32 y
00245 int32 width
00246 int32 height
00247 
00248 ================================================================================
00249 MSG: sensor_msgs/Image
00250 # This message contains an uncompressed image
00251 # (0, 0) is at top-left corner of image
00252 #
00253 
00254 Header header        # Header timestamp should be acquisition time of image
00255                      # Header frame_id should be optical frame of camera
00256                      # origin of frame should be optical center of cameara
00257                      # +x should point to the right in the image
00258                      # +y should point down in the image
00259                      # +z should point into to plane of the image
00260                      # If the frame_id here and the frame_id of the CameraInfo
00261                      # message associated with the image conflict
00262                      # the behavior is undefined
00263 
00264 uint32 height         # image height, that is, number of rows
00265 uint32 width          # image width, that is, number of columns
00266 
00267 # The legal values for encoding are in file src/image_encodings.cpp
00268 # If you want to standardize a new string format, join
00269 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00270 
00271 string encoding       # Encoding of pixels -- channel meaning, ordering, size
00272                       # taken from the list of strings in include/sensor_msgs/image_encodings.h
00273 
00274 uint8 is_bigendian    # is this data bigendian?
00275 uint32 step           # Full row length in bytes
00276 uint8[] data          # actual matrix data, size is (step * rows)
00277 
00278 ================================================================================
00279 MSG: geometry_msgs/PoseStamped
00280 # A Pose with reference coordinate frame and timestamp
00281 Header header
00282 Pose pose
00283 
00284 ================================================================================
00285 MSG: geometry_msgs/Pose
00286 # A representation of pose in free space, composed of postion and orientation. 
00287 Point position
00288 Quaternion orientation
00289 
00290 ================================================================================
00291 MSG: geometry_msgs/Point
00292 # This contains the position of a point in free space
00293 float64 x
00294 float64 y
00295 float64 z
00296 
00297 ================================================================================
00298 MSG: geometry_msgs/Quaternion
00299 # This represents an orientation in free space in quaternion form.
00300 
00301 float64 x
00302 float64 y
00303 float64 z
00304 float64 w
00305 
00306 """
00307   __slots__ = ['object_list']
00308   _slot_types = ['cob_object_detection_msgs/DetectionArray']
00309 
00310   def __init__(self, *args, **kwds):
00311     """
00312     Constructor. Any message fields that are implicitly/explicitly
00313     set to None will be assigned a default value. The recommend
00314     use is keyword arguments as this is more robust to future message
00315     changes.  You cannot mix in-order arguments and keyword arguments.
00316 
00317     The available fields are:
00318        object_list
00319 
00320     :param args: complete set of field values, in .msg order
00321     :param kwds: use keyword arguments corresponding to message field names
00322     to set specific fields.
00323     """
00324     if args or kwds:
00325       super(DetectObjectsResponse, self).__init__(*args, **kwds)
00326       #message fields cannot be None, assign default values for those that are
00327       if self.object_list is None:
00328         self.object_list = cob_object_detection_msgs.msg.DetectionArray()
00329     else:
00330       self.object_list = cob_object_detection_msgs.msg.DetectionArray()
00331 
00332   def _get_types(self):
00333     """
00334     internal API method
00335     """
00336     return self._slot_types
00337 
00338   def serialize(self, buff):
00339     """
00340     serialize message into buffer
00341     :param buff: buffer, ``StringIO``
00342     """
00343     try:
00344       _x = self
00345       buff.write(_struct_3I.pack(_x.object_list.header.seq, _x.object_list.header.stamp.secs, _x.object_list.header.stamp.nsecs))
00346       _x = self.object_list.header.frame_id
00347       length = len(_x)
00348       if python3 or type(_x) == unicode:
00349         _x = _x.encode('utf-8')
00350         length = len(_x)
00351       buff.write(struct.pack('<I%ss'%length, length, _x))
00352       length = len(self.object_list.detections)
00353       buff.write(_struct_I.pack(length))
00354       for val1 in self.object_list.detections:
00355         _v1 = val1.header
00356         buff.write(_struct_I.pack(_v1.seq))
00357         _v2 = _v1.stamp
00358         _x = _v2
00359         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00360         _x = _v1.frame_id
00361         length = len(_x)
00362         if python3 or type(_x) == unicode:
00363           _x = _x.encode('utf-8')
00364           length = len(_x)
00365         buff.write(struct.pack('<I%ss'%length, length, _x))
00366         _x = val1.label
00367         length = len(_x)
00368         if python3 or type(_x) == unicode:
00369           _x = _x.encode('utf-8')
00370           length = len(_x)
00371         buff.write(struct.pack('<I%ss'%length, length, _x))
00372         _x = val1.detector
00373         length = len(_x)
00374         if python3 or type(_x) == unicode:
00375           _x = _x.encode('utf-8')
00376           length = len(_x)
00377         buff.write(struct.pack('<I%ss'%length, length, _x))
00378         buff.write(_struct_f.pack(val1.score))
00379         _v3 = val1.mask
00380         _v4 = _v3.roi
00381         _x = _v4
00382         buff.write(_struct_4i.pack(_x.x, _x.y, _x.width, _x.height))
00383         _v5 = _v3.mask
00384         _v6 = _v5.header
00385         buff.write(_struct_I.pack(_v6.seq))
00386         _v7 = _v6.stamp
00387         _x = _v7
00388         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00389         _x = _v6.frame_id
00390         length = len(_x)
00391         if python3 or type(_x) == unicode:
00392           _x = _x.encode('utf-8')
00393           length = len(_x)
00394         buff.write(struct.pack('<I%ss'%length, length, _x))
00395         _x = _v5
00396         buff.write(_struct_2I.pack(_x.height, _x.width))
00397         _x = _v5.encoding
00398         length = len(_x)
00399         if python3 or type(_x) == unicode:
00400           _x = _x.encode('utf-8')
00401           length = len(_x)
00402         buff.write(struct.pack('<I%ss'%length, length, _x))
00403         _x = _v5
00404         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
00405         _x = _v5.data
00406         length = len(_x)
00407         # - if encoded as a list instead, serialize as bytes instead of string
00408         if type(_x) in [list, tuple]:
00409           buff.write(struct.pack('<I%sB'%length, length, *_x))
00410         else:
00411           buff.write(struct.pack('<I%ss'%length, length, _x))
00412         _v8 = val1.pose
00413         _v9 = _v8.header
00414         buff.write(_struct_I.pack(_v9.seq))
00415         _v10 = _v9.stamp
00416         _x = _v10
00417         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00418         _x = _v9.frame_id
00419         length = len(_x)
00420         if python3 or type(_x) == unicode:
00421           _x = _x.encode('utf-8')
00422           length = len(_x)
00423         buff.write(struct.pack('<I%ss'%length, length, _x))
00424         _v11 = _v8.pose
00425         _v12 = _v11.position
00426         _x = _v12
00427         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00428         _v13 = _v11.orientation
00429         _x = _v13
00430         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00431         _v14 = val1.bounding_box_lwh
00432         _x = _v14
00433         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00434     except struct.error as se: self._check_types(se)
00435     except TypeError as te: self._check_types(te)
00436 
00437   def deserialize(self, str):
00438     """
00439     unpack serialized message in str into this message instance
00440     :param str: byte array of serialized message, ``str``
00441     """
00442     try:
00443       if self.object_list is None:
00444         self.object_list = cob_object_detection_msgs.msg.DetectionArray()
00445       end = 0
00446       _x = self
00447       start = end
00448       end += 12
00449       (_x.object_list.header.seq, _x.object_list.header.stamp.secs, _x.object_list.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00450       start = end
00451       end += 4
00452       (length,) = _struct_I.unpack(str[start:end])
00453       start = end
00454       end += length
00455       if python3:
00456         self.object_list.header.frame_id = str[start:end].decode('utf-8')
00457       else:
00458         self.object_list.header.frame_id = str[start:end]
00459       start = end
00460       end += 4
00461       (length,) = _struct_I.unpack(str[start:end])
00462       self.object_list.detections = []
00463       for i in range(0, length):
00464         val1 = cob_object_detection_msgs.msg.Detection()
00465         _v15 = val1.header
00466         start = end
00467         end += 4
00468         (_v15.seq,) = _struct_I.unpack(str[start:end])
00469         _v16 = _v15.stamp
00470         _x = _v16
00471         start = end
00472         end += 8
00473         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00474         start = end
00475         end += 4
00476         (length,) = _struct_I.unpack(str[start:end])
00477         start = end
00478         end += length
00479         if python3:
00480           _v15.frame_id = str[start:end].decode('utf-8')
00481         else:
00482           _v15.frame_id = str[start:end]
00483         start = end
00484         end += 4
00485         (length,) = _struct_I.unpack(str[start:end])
00486         start = end
00487         end += length
00488         if python3:
00489           val1.label = str[start:end].decode('utf-8')
00490         else:
00491           val1.label = str[start:end]
00492         start = end
00493         end += 4
00494         (length,) = _struct_I.unpack(str[start:end])
00495         start = end
00496         end += length
00497         if python3:
00498           val1.detector = str[start:end].decode('utf-8')
00499         else:
00500           val1.detector = str[start:end]
00501         start = end
00502         end += 4
00503         (val1.score,) = _struct_f.unpack(str[start:end])
00504         _v17 = val1.mask
00505         _v18 = _v17.roi
00506         _x = _v18
00507         start = end
00508         end += 16
00509         (_x.x, _x.y, _x.width, _x.height,) = _struct_4i.unpack(str[start:end])
00510         _v19 = _v17.mask
00511         _v20 = _v19.header
00512         start = end
00513         end += 4
00514         (_v20.seq,) = _struct_I.unpack(str[start:end])
00515         _v21 = _v20.stamp
00516         _x = _v21
00517         start = end
00518         end += 8
00519         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00520         start = end
00521         end += 4
00522         (length,) = _struct_I.unpack(str[start:end])
00523         start = end
00524         end += length
00525         if python3:
00526           _v20.frame_id = str[start:end].decode('utf-8')
00527         else:
00528           _v20.frame_id = str[start:end]
00529         _x = _v19
00530         start = end
00531         end += 8
00532         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
00533         start = end
00534         end += 4
00535         (length,) = _struct_I.unpack(str[start:end])
00536         start = end
00537         end += length
00538         if python3:
00539           _v19.encoding = str[start:end].decode('utf-8')
00540         else:
00541           _v19.encoding = str[start:end]
00542         _x = _v19
00543         start = end
00544         end += 5
00545         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
00546         start = end
00547         end += 4
00548         (length,) = _struct_I.unpack(str[start:end])
00549         start = end
00550         end += length
00551         if python3:
00552           _v19.data = str[start:end].decode('utf-8')
00553         else:
00554           _v19.data = str[start:end]
00555         _v22 = val1.pose
00556         _v23 = _v22.header
00557         start = end
00558         end += 4
00559         (_v23.seq,) = _struct_I.unpack(str[start:end])
00560         _v24 = _v23.stamp
00561         _x = _v24
00562         start = end
00563         end += 8
00564         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00565         start = end
00566         end += 4
00567         (length,) = _struct_I.unpack(str[start:end])
00568         start = end
00569         end += length
00570         if python3:
00571           _v23.frame_id = str[start:end].decode('utf-8')
00572         else:
00573           _v23.frame_id = str[start:end]
00574         _v25 = _v22.pose
00575         _v26 = _v25.position
00576         _x = _v26
00577         start = end
00578         end += 24
00579         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00580         _v27 = _v25.orientation
00581         _x = _v27
00582         start = end
00583         end += 32
00584         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00585         _v28 = val1.bounding_box_lwh
00586         _x = _v28
00587         start = end
00588         end += 24
00589         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00590         self.object_list.detections.append(val1)
00591       return self
00592     except struct.error as e:
00593       raise genpy.DeserializationError(e) #most likely buffer underfill
00594 
00595 
00596   def serialize_numpy(self, buff, numpy):
00597     """
00598     serialize message with numpy array types into buffer
00599     :param buff: buffer, ``StringIO``
00600     :param numpy: numpy python module
00601     """
00602     try:
00603       _x = self
00604       buff.write(_struct_3I.pack(_x.object_list.header.seq, _x.object_list.header.stamp.secs, _x.object_list.header.stamp.nsecs))
00605       _x = self.object_list.header.frame_id
00606       length = len(_x)
00607       if python3 or type(_x) == unicode:
00608         _x = _x.encode('utf-8')
00609         length = len(_x)
00610       buff.write(struct.pack('<I%ss'%length, length, _x))
00611       length = len(self.object_list.detections)
00612       buff.write(_struct_I.pack(length))
00613       for val1 in self.object_list.detections:
00614         _v29 = val1.header
00615         buff.write(_struct_I.pack(_v29.seq))
00616         _v30 = _v29.stamp
00617         _x = _v30
00618         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00619         _x = _v29.frame_id
00620         length = len(_x)
00621         if python3 or type(_x) == unicode:
00622           _x = _x.encode('utf-8')
00623           length = len(_x)
00624         buff.write(struct.pack('<I%ss'%length, length, _x))
00625         _x = val1.label
00626         length = len(_x)
00627         if python3 or type(_x) == unicode:
00628           _x = _x.encode('utf-8')
00629           length = len(_x)
00630         buff.write(struct.pack('<I%ss'%length, length, _x))
00631         _x = val1.detector
00632         length = len(_x)
00633         if python3 or type(_x) == unicode:
00634           _x = _x.encode('utf-8')
00635           length = len(_x)
00636         buff.write(struct.pack('<I%ss'%length, length, _x))
00637         buff.write(_struct_f.pack(val1.score))
00638         _v31 = val1.mask
00639         _v32 = _v31.roi
00640         _x = _v32
00641         buff.write(_struct_4i.pack(_x.x, _x.y, _x.width, _x.height))
00642         _v33 = _v31.mask
00643         _v34 = _v33.header
00644         buff.write(_struct_I.pack(_v34.seq))
00645         _v35 = _v34.stamp
00646         _x = _v35
00647         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00648         _x = _v34.frame_id
00649         length = len(_x)
00650         if python3 or type(_x) == unicode:
00651           _x = _x.encode('utf-8')
00652           length = len(_x)
00653         buff.write(struct.pack('<I%ss'%length, length, _x))
00654         _x = _v33
00655         buff.write(_struct_2I.pack(_x.height, _x.width))
00656         _x = _v33.encoding
00657         length = len(_x)
00658         if python3 or type(_x) == unicode:
00659           _x = _x.encode('utf-8')
00660           length = len(_x)
00661         buff.write(struct.pack('<I%ss'%length, length, _x))
00662         _x = _v33
00663         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
00664         _x = _v33.data
00665         length = len(_x)
00666         # - if encoded as a list instead, serialize as bytes instead of string
00667         if type(_x) in [list, tuple]:
00668           buff.write(struct.pack('<I%sB'%length, length, *_x))
00669         else:
00670           buff.write(struct.pack('<I%ss'%length, length, _x))
00671         _v36 = val1.pose
00672         _v37 = _v36.header
00673         buff.write(_struct_I.pack(_v37.seq))
00674         _v38 = _v37.stamp
00675         _x = _v38
00676         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00677         _x = _v37.frame_id
00678         length = len(_x)
00679         if python3 or type(_x) == unicode:
00680           _x = _x.encode('utf-8')
00681           length = len(_x)
00682         buff.write(struct.pack('<I%ss'%length, length, _x))
00683         _v39 = _v36.pose
00684         _v40 = _v39.position
00685         _x = _v40
00686         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00687         _v41 = _v39.orientation
00688         _x = _v41
00689         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00690         _v42 = val1.bounding_box_lwh
00691         _x = _v42
00692         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00693     except struct.error as se: self._check_types(se)
00694     except TypeError as te: self._check_types(te)
00695 
00696   def deserialize_numpy(self, str, numpy):
00697     """
00698     unpack serialized message in str into this message instance using numpy for array types
00699     :param str: byte array of serialized message, ``str``
00700     :param numpy: numpy python module
00701     """
00702     try:
00703       if self.object_list is None:
00704         self.object_list = cob_object_detection_msgs.msg.DetectionArray()
00705       end = 0
00706       _x = self
00707       start = end
00708       end += 12
00709       (_x.object_list.header.seq, _x.object_list.header.stamp.secs, _x.object_list.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00710       start = end
00711       end += 4
00712       (length,) = _struct_I.unpack(str[start:end])
00713       start = end
00714       end += length
00715       if python3:
00716         self.object_list.header.frame_id = str[start:end].decode('utf-8')
00717       else:
00718         self.object_list.header.frame_id = str[start:end]
00719       start = end
00720       end += 4
00721       (length,) = _struct_I.unpack(str[start:end])
00722       self.object_list.detections = []
00723       for i in range(0, length):
00724         val1 = cob_object_detection_msgs.msg.Detection()
00725         _v43 = val1.header
00726         start = end
00727         end += 4
00728         (_v43.seq,) = _struct_I.unpack(str[start:end])
00729         _v44 = _v43.stamp
00730         _x = _v44
00731         start = end
00732         end += 8
00733         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00734         start = end
00735         end += 4
00736         (length,) = _struct_I.unpack(str[start:end])
00737         start = end
00738         end += length
00739         if python3:
00740           _v43.frame_id = str[start:end].decode('utf-8')
00741         else:
00742           _v43.frame_id = str[start:end]
00743         start = end
00744         end += 4
00745         (length,) = _struct_I.unpack(str[start:end])
00746         start = end
00747         end += length
00748         if python3:
00749           val1.label = str[start:end].decode('utf-8')
00750         else:
00751           val1.label = str[start:end]
00752         start = end
00753         end += 4
00754         (length,) = _struct_I.unpack(str[start:end])
00755         start = end
00756         end += length
00757         if python3:
00758           val1.detector = str[start:end].decode('utf-8')
00759         else:
00760           val1.detector = str[start:end]
00761         start = end
00762         end += 4
00763         (val1.score,) = _struct_f.unpack(str[start:end])
00764         _v45 = val1.mask
00765         _v46 = _v45.roi
00766         _x = _v46
00767         start = end
00768         end += 16
00769         (_x.x, _x.y, _x.width, _x.height,) = _struct_4i.unpack(str[start:end])
00770         _v47 = _v45.mask
00771         _v48 = _v47.header
00772         start = end
00773         end += 4
00774         (_v48.seq,) = _struct_I.unpack(str[start:end])
00775         _v49 = _v48.stamp
00776         _x = _v49
00777         start = end
00778         end += 8
00779         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00780         start = end
00781         end += 4
00782         (length,) = _struct_I.unpack(str[start:end])
00783         start = end
00784         end += length
00785         if python3:
00786           _v48.frame_id = str[start:end].decode('utf-8')
00787         else:
00788           _v48.frame_id = str[start:end]
00789         _x = _v47
00790         start = end
00791         end += 8
00792         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
00793         start = end
00794         end += 4
00795         (length,) = _struct_I.unpack(str[start:end])
00796         start = end
00797         end += length
00798         if python3:
00799           _v47.encoding = str[start:end].decode('utf-8')
00800         else:
00801           _v47.encoding = str[start:end]
00802         _x = _v47
00803         start = end
00804         end += 5
00805         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
00806         start = end
00807         end += 4
00808         (length,) = _struct_I.unpack(str[start:end])
00809         start = end
00810         end += length
00811         if python3:
00812           _v47.data = str[start:end].decode('utf-8')
00813         else:
00814           _v47.data = str[start:end]
00815         _v50 = val1.pose
00816         _v51 = _v50.header
00817         start = end
00818         end += 4
00819         (_v51.seq,) = _struct_I.unpack(str[start:end])
00820         _v52 = _v51.stamp
00821         _x = _v52
00822         start = end
00823         end += 8
00824         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00825         start = end
00826         end += 4
00827         (length,) = _struct_I.unpack(str[start:end])
00828         start = end
00829         end += length
00830         if python3:
00831           _v51.frame_id = str[start:end].decode('utf-8')
00832         else:
00833           _v51.frame_id = str[start:end]
00834         _v53 = _v50.pose
00835         _v54 = _v53.position
00836         _x = _v54
00837         start = end
00838         end += 24
00839         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00840         _v55 = _v53.orientation
00841         _x = _v55
00842         start = end
00843         end += 32
00844         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00845         _v56 = val1.bounding_box_lwh
00846         _x = _v56
00847         start = end
00848         end += 24
00849         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00850         self.object_list.detections.append(val1)
00851       return self
00852     except struct.error as e:
00853       raise genpy.DeserializationError(e) #most likely buffer underfill
00854 
00855 _struct_I = genpy.struct_I
00856 _struct_f = struct.Struct("<f")
00857 _struct_BI = struct.Struct("<BI")
00858 _struct_3I = struct.Struct("<3I")
00859 _struct_4i = struct.Struct("<4i")
00860 _struct_4d = struct.Struct("<4d")
00861 _struct_2I = struct.Struct("<2I")
00862 _struct_3d = struct.Struct("<3d")
00863 class DetectObjects(object):
00864   _type          = 'cob_object_detection_msgs/DetectObjects'
00865   _md5sum = '3e7b1c8cc85eedd71f86f7179c8873b6'
00866   _request_class  = DetectObjectsRequest
00867   _response_class = DetectObjectsResponse
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


cob_object_detection_msgs
Author(s): Florian Weisshardt
autogenerated on Fri Mar 8 2013 15:04:09