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