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