_ObjectRecognitionGuiGoal.py
Go to the documentation of this file.
00001 """autogenerated by genpy from interactive_perception_msgs/ObjectRecognitionGuiGoal.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 shape_msgs.msg
00009 import std_msgs.msg
00010 import interactive_perception_msgs.msg
00011 import sensor_msgs.msg
00012 
00013 class ObjectRecognitionGuiGoal(genpy.Message):
00014   _md5sum = "9971b18121fb4c5c8caedc975ff0023a"
00015   _type = "interactive_perception_msgs/ObjectRecognitionGuiGoal"
00016   _has_header = False #flag to mark the presence of a Header object
00017   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00018 
00019 #the original sensor data (depth/disparity image)
00020 sensor_msgs/Image image
00021 sensor_msgs/CameraInfo camera_info
00022 
00023 #list of mesh/pose hypotheses for each recognized point cluster
00024 ModelHypothesisList[] model_hypotheses
00025 
00026 ================================================================================
00027 MSG: sensor_msgs/Image
00028 # This message contains an uncompressed image
00029 # (0, 0) is at top-left corner of image
00030 #
00031 
00032 Header header        # Header timestamp should be acquisition time of image
00033                      # Header frame_id should be optical frame of camera
00034                      # origin of frame should be optical center of cameara
00035                      # +x should point to the right in the image
00036                      # +y should point down in the image
00037                      # +z should point into to plane of the image
00038                      # If the frame_id here and the frame_id of the CameraInfo
00039                      # message associated with the image conflict
00040                      # the behavior is undefined
00041 
00042 uint32 height         # image height, that is, number of rows
00043 uint32 width          # image width, that is, number of columns
00044 
00045 # The legal values for encoding are in file src/image_encodings.cpp
00046 # If you want to standardize a new string format, join
00047 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00048 
00049 string encoding       # Encoding of pixels -- channel meaning, ordering, size
00050                       # taken from the list of strings in include/sensor_msgs/image_encodings.h
00051 
00052 uint8 is_bigendian    # is this data bigendian?
00053 uint32 step           # Full row length in bytes
00054 uint8[] data          # actual matrix data, size is (step * rows)
00055 
00056 ================================================================================
00057 MSG: std_msgs/Header
00058 # Standard metadata for higher-level stamped data types.
00059 # This is generally used to communicate timestamped data 
00060 # in a particular coordinate frame.
00061 # 
00062 # sequence ID: consecutively increasing ID 
00063 uint32 seq
00064 #Two-integer timestamp that is expressed as:
00065 # * stamp.secs: seconds (stamp_secs) since epoch
00066 # * stamp.nsecs: nanoseconds since stamp_secs
00067 # time-handling sugar is provided by the client library
00068 time stamp
00069 #Frame this data is associated with
00070 # 0: no frame
00071 # 1: global frame
00072 string frame_id
00073 
00074 ================================================================================
00075 MSG: sensor_msgs/CameraInfo
00076 # This message defines meta information for a camera. It should be in a
00077 # camera namespace on topic "camera_info" and accompanied by up to five
00078 # image topics named:
00079 #
00080 #   image_raw - raw data from the camera driver, possibly Bayer encoded
00081 #   image            - monochrome, distorted
00082 #   image_color      - color, distorted
00083 #   image_rect       - monochrome, rectified
00084 #   image_rect_color - color, rectified
00085 #
00086 # The image_pipeline contains packages (image_proc, stereo_image_proc)
00087 # for producing the four processed image topics from image_raw and
00088 # camera_info. The meaning of the camera parameters are described in
00089 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
00090 #
00091 # The image_geometry package provides a user-friendly interface to
00092 # common operations using this meta information. If you want to, e.g.,
00093 # project a 3d point into image coordinates, we strongly recommend
00094 # using image_geometry.
00095 #
00096 # If the camera is uncalibrated, the matrices D, K, R, P should be left
00097 # zeroed out. In particular, clients may assume that K[0] == 0.0
00098 # indicates an uncalibrated camera.
00099 
00100 #######################################################################
00101 #                     Image acquisition info                          #
00102 #######################################################################
00103 
00104 # Time of image acquisition, camera coordinate frame ID
00105 Header header    # Header timestamp should be acquisition time of image
00106                  # Header frame_id should be optical frame of camera
00107                  # origin of frame should be optical center of camera
00108                  # +x should point to the right in the image
00109                  # +y should point down in the image
00110                  # +z should point into the plane of the image
00111 
00112 
00113 #######################################################################
00114 #                      Calibration Parameters                         #
00115 #######################################################################
00116 # These are fixed during camera calibration. Their values will be the #
00117 # same in all messages until the camera is recalibrated. Note that    #
00118 # self-calibrating systems may "recalibrate" frequently.              #
00119 #                                                                     #
00120 # The internal parameters can be used to warp a raw (distorted) image #
00121 # to:                                                                 #
00122 #   1. An undistorted image (requires D and K)                        #
00123 #   2. A rectified image (requires D, K, R)                           #
00124 # The projection matrix P projects 3D points into the rectified image.#
00125 #######################################################################
00126 
00127 # The image dimensions with which the camera was calibrated. Normally
00128 # this will be the full camera resolution in pixels.
00129 uint32 height
00130 uint32 width
00131 
00132 # The distortion model used. Supported models are listed in
00133 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
00134 # simple model of radial and tangential distortion - is sufficent.
00135 string distortion_model
00136 
00137 # The distortion parameters, size depending on the distortion model.
00138 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
00139 float64[] D
00140 
00141 # Intrinsic camera matrix for the raw (distorted) images.
00142 #     [fx  0 cx]
00143 # K = [ 0 fy cy]
00144 #     [ 0  0  1]
00145 # Projects 3D points in the camera coordinate frame to 2D pixel
00146 # coordinates using the focal lengths (fx, fy) and principal point
00147 # (cx, cy).
00148 float64[9]  K # 3x3 row-major matrix
00149 
00150 # Rectification matrix (stereo cameras only)
00151 # A rotation matrix aligning the camera coordinate system to the ideal
00152 # stereo image plane so that epipolar lines in both stereo images are
00153 # parallel.
00154 float64[9]  R # 3x3 row-major matrix
00155 
00156 # Projection/camera matrix
00157 #     [fx'  0  cx' Tx]
00158 # P = [ 0  fy' cy' Ty]
00159 #     [ 0   0   1   0]
00160 # By convention, this matrix specifies the intrinsic (camera) matrix
00161 #  of the processed (rectified) image. That is, the left 3x3 portion
00162 #  is the normal camera intrinsic matrix for the rectified image.
00163 # It projects 3D points in the camera coordinate frame to 2D pixel
00164 #  coordinates using the focal lengths (fx', fy') and principal point
00165 #  (cx', cy') - these may differ from the values in K.
00166 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
00167 #  also have R = the identity and P[1:3,1:3] = K.
00168 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
00169 #  position of the optical center of the second camera in the first
00170 #  camera's frame. We assume Tz = 0 so both cameras are in the same
00171 #  stereo image plane. The first camera always has Tx = Ty = 0. For
00172 #  the right (second) camera of a horizontal stereo pair, Ty = 0 and
00173 #  Tx = -fx' * B, where B is the baseline between the cameras.
00174 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
00175 #  the rectified image is given by:
00176 #  [u v w]' = P * [X Y Z 1]'
00177 #         x = u / w
00178 #         y = v / w
00179 #  This holds for both images of a stereo pair.
00180 float64[12] P # 3x4 row-major matrix
00181 
00182 
00183 #######################################################################
00184 #                      Operational Parameters                         #
00185 #######################################################################
00186 # These define the image region actually captured by the camera       #
00187 # driver. Although they affect the geometry of the output image, they #
00188 # may be changed freely without recalibrating the camera.             #
00189 #######################################################################
00190 
00191 # Binning refers here to any camera setting which combines rectangular
00192 #  neighborhoods of pixels into larger "super-pixels." It reduces the
00193 #  resolution of the output image to
00194 #  (width / binning_x) x (height / binning_y).
00195 # The default values binning_x = binning_y = 0 is considered the same
00196 #  as binning_x = binning_y = 1 (no subsampling).
00197 uint32 binning_x
00198 uint32 binning_y
00199 
00200 # Region of interest (subwindow of full camera resolution), given in
00201 #  full resolution (unbinned) image coordinates. A particular ROI
00202 #  always denotes the same window of pixels on the camera sensor,
00203 #  regardless of binning settings.
00204 # The default setting of roi (all values 0) is considered the same as
00205 #  full resolution (roi.width = width, roi.height = height).
00206 RegionOfInterest roi
00207 
00208 ================================================================================
00209 MSG: sensor_msgs/RegionOfInterest
00210 # This message is used to specify a region of interest within an image.
00211 #
00212 # When used to specify the ROI setting of the camera when the image was
00213 # taken, the height and width fields should either match the height and
00214 # width fields for the associated image; or height = width = 0
00215 # indicates that the full resolution image was captured.
00216 
00217 uint32 x_offset  # Leftmost pixel of the ROI
00218                  # (0 if the ROI includes the left edge of the image)
00219 uint32 y_offset  # Topmost pixel of the ROI
00220                  # (0 if the ROI includes the top edge of the image)
00221 uint32 height    # Height of ROI
00222 uint32 width     # Width of ROI
00223 
00224 # True if a distinct rectified ROI should be calculated from the "raw"
00225 # ROI in this message. Typically this should be False if the full image
00226 # is captured (ROI not used), and True if a subwindow is captured (ROI
00227 # used).
00228 bool do_rectify
00229 
00230 ================================================================================
00231 MSG: interactive_perception_msgs/ModelHypothesisList
00232 ModelHypothesis[] hypotheses
00233 
00234 #initial guess if this can be a correct recognition result at all
00235 bool accept
00236 ================================================================================
00237 MSG: interactive_perception_msgs/ModelHypothesis
00238 #describes a hypothesis about a recognized object (mesh+pose)
00239 
00240 shape_msgs/Mesh mesh
00241 geometry_msgs/PoseStamped pose
00242 
00243 ================================================================================
00244 MSG: shape_msgs/Mesh
00245 # Definition of a mesh
00246 
00247 # list of triangles; the index values refer to positions in vertices[]
00248 MeshTriangle[] triangles
00249 
00250 # the actual vertices that make up the mesh
00251 geometry_msgs/Point[] vertices
00252 
00253 ================================================================================
00254 MSG: shape_msgs/MeshTriangle
00255 # Definition of a triangle's vertices
00256 uint32[3] vertex_indices
00257 
00258 ================================================================================
00259 MSG: geometry_msgs/Point
00260 # This contains the position of a point in free space
00261 float64 x
00262 float64 y
00263 float64 z
00264 
00265 ================================================================================
00266 MSG: geometry_msgs/PoseStamped
00267 # A Pose with reference coordinate frame and timestamp
00268 Header header
00269 Pose pose
00270 
00271 ================================================================================
00272 MSG: geometry_msgs/Pose
00273 # A representation of pose in free space, composed of postion and orientation. 
00274 Point position
00275 Quaternion orientation
00276 
00277 ================================================================================
00278 MSG: geometry_msgs/Quaternion
00279 # This represents an orientation in free space in quaternion form.
00280 
00281 float64 x
00282 float64 y
00283 float64 z
00284 float64 w
00285 
00286 """
00287   __slots__ = ['image','camera_info','model_hypotheses']
00288   _slot_types = ['sensor_msgs/Image','sensor_msgs/CameraInfo','interactive_perception_msgs/ModelHypothesisList[]']
00289 
00290   def __init__(self, *args, **kwds):
00291     """
00292     Constructor. Any message fields that are implicitly/explicitly
00293     set to None will be assigned a default value. The recommend
00294     use is keyword arguments as this is more robust to future message
00295     changes.  You cannot mix in-order arguments and keyword arguments.
00296 
00297     The available fields are:
00298        image,camera_info,model_hypotheses
00299 
00300     :param args: complete set of field values, in .msg order
00301     :param kwds: use keyword arguments corresponding to message field names
00302     to set specific fields.
00303     """
00304     if args or kwds:
00305       super(ObjectRecognitionGuiGoal, self).__init__(*args, **kwds)
00306       #message fields cannot be None, assign default values for those that are
00307       if self.image is None:
00308         self.image = sensor_msgs.msg.Image()
00309       if self.camera_info is None:
00310         self.camera_info = sensor_msgs.msg.CameraInfo()
00311       if self.model_hypotheses is None:
00312         self.model_hypotheses = []
00313     else:
00314       self.image = sensor_msgs.msg.Image()
00315       self.camera_info = sensor_msgs.msg.CameraInfo()
00316       self.model_hypotheses = []
00317 
00318   def _get_types(self):
00319     """
00320     internal API method
00321     """
00322     return self._slot_types
00323 
00324   def serialize(self, buff):
00325     """
00326     serialize message into buffer
00327     :param buff: buffer, ``StringIO``
00328     """
00329     try:
00330       _x = self
00331       buff.write(_struct_3I.pack(_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs))
00332       _x = self.image.header.frame_id
00333       length = len(_x)
00334       if python3 or type(_x) == unicode:
00335         _x = _x.encode('utf-8')
00336         length = len(_x)
00337       buff.write(struct.pack('<I%ss'%length, length, _x))
00338       _x = self
00339       buff.write(_struct_2I.pack(_x.image.height, _x.image.width))
00340       _x = self.image.encoding
00341       length = len(_x)
00342       if python3 or type(_x) == unicode:
00343         _x = _x.encode('utf-8')
00344         length = len(_x)
00345       buff.write(struct.pack('<I%ss'%length, length, _x))
00346       _x = self
00347       buff.write(_struct_BI.pack(_x.image.is_bigendian, _x.image.step))
00348       _x = self.image.data
00349       length = len(_x)
00350       # - if encoded as a list instead, serialize as bytes instead of string
00351       if type(_x) in [list, tuple]:
00352         buff.write(struct.pack('<I%sB'%length, length, *_x))
00353       else:
00354         buff.write(struct.pack('<I%ss'%length, length, _x))
00355       _x = self
00356       buff.write(_struct_3I.pack(_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs))
00357       _x = self.camera_info.header.frame_id
00358       length = len(_x)
00359       if python3 or type(_x) == unicode:
00360         _x = _x.encode('utf-8')
00361         length = len(_x)
00362       buff.write(struct.pack('<I%ss'%length, length, _x))
00363       _x = self
00364       buff.write(_struct_2I.pack(_x.camera_info.height, _x.camera_info.width))
00365       _x = self.camera_info.distortion_model
00366       length = len(_x)
00367       if python3 or type(_x) == unicode:
00368         _x = _x.encode('utf-8')
00369         length = len(_x)
00370       buff.write(struct.pack('<I%ss'%length, length, _x))
00371       length = len(self.camera_info.D)
00372       buff.write(_struct_I.pack(length))
00373       pattern = '<%sd'%length
00374       buff.write(struct.pack(pattern, *self.camera_info.D))
00375       buff.write(_struct_9d.pack(*self.camera_info.K))
00376       buff.write(_struct_9d.pack(*self.camera_info.R))
00377       buff.write(_struct_12d.pack(*self.camera_info.P))
00378       _x = self
00379       buff.write(_struct_6IB.pack(_x.camera_info.binning_x, _x.camera_info.binning_y, _x.camera_info.roi.x_offset, _x.camera_info.roi.y_offset, _x.camera_info.roi.height, _x.camera_info.roi.width, _x.camera_info.roi.do_rectify))
00380       length = len(self.model_hypotheses)
00381       buff.write(_struct_I.pack(length))
00382       for val1 in self.model_hypotheses:
00383         length = len(val1.hypotheses)
00384         buff.write(_struct_I.pack(length))
00385         for val2 in val1.hypotheses:
00386           _v1 = val2.mesh
00387           length = len(_v1.triangles)
00388           buff.write(_struct_I.pack(length))
00389           for val4 in _v1.triangles:
00390             buff.write(_struct_3I.pack(*val4.vertex_indices))
00391           length = len(_v1.vertices)
00392           buff.write(_struct_I.pack(length))
00393           for val4 in _v1.vertices:
00394             _x = val4
00395             buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00396           _v2 = val2.pose
00397           _v3 = _v2.header
00398           buff.write(_struct_I.pack(_v3.seq))
00399           _v4 = _v3.stamp
00400           _x = _v4
00401           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00402           _x = _v3.frame_id
00403           length = len(_x)
00404           if python3 or type(_x) == unicode:
00405             _x = _x.encode('utf-8')
00406             length = len(_x)
00407           buff.write(struct.pack('<I%ss'%length, length, _x))
00408           _v5 = _v2.pose
00409           _v6 = _v5.position
00410           _x = _v6
00411           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00412           _v7 = _v5.orientation
00413           _x = _v7
00414           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00415         buff.write(_struct_B.pack(val1.accept))
00416     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00417     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00418 
00419   def deserialize(self, str):
00420     """
00421     unpack serialized message in str into this message instance
00422     :param str: byte array of serialized message, ``str``
00423     """
00424     try:
00425       if self.image is None:
00426         self.image = sensor_msgs.msg.Image()
00427       if self.camera_info is None:
00428         self.camera_info = sensor_msgs.msg.CameraInfo()
00429       if self.model_hypotheses is None:
00430         self.model_hypotheses = None
00431       end = 0
00432       _x = self
00433       start = end
00434       end += 12
00435       (_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00436       start = end
00437       end += 4
00438       (length,) = _struct_I.unpack(str[start:end])
00439       start = end
00440       end += length
00441       if python3:
00442         self.image.header.frame_id = str[start:end].decode('utf-8')
00443       else:
00444         self.image.header.frame_id = str[start:end]
00445       _x = self
00446       start = end
00447       end += 8
00448       (_x.image.height, _x.image.width,) = _struct_2I.unpack(str[start:end])
00449       start = end
00450       end += 4
00451       (length,) = _struct_I.unpack(str[start:end])
00452       start = end
00453       end += length
00454       if python3:
00455         self.image.encoding = str[start:end].decode('utf-8')
00456       else:
00457         self.image.encoding = str[start:end]
00458       _x = self
00459       start = end
00460       end += 5
00461       (_x.image.is_bigendian, _x.image.step,) = _struct_BI.unpack(str[start:end])
00462       start = end
00463       end += 4
00464       (length,) = _struct_I.unpack(str[start:end])
00465       start = end
00466       end += length
00467       self.image.data = str[start:end]
00468       _x = self
00469       start = end
00470       end += 12
00471       (_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00472       start = end
00473       end += 4
00474       (length,) = _struct_I.unpack(str[start:end])
00475       start = end
00476       end += length
00477       if python3:
00478         self.camera_info.header.frame_id = str[start:end].decode('utf-8')
00479       else:
00480         self.camera_info.header.frame_id = str[start:end]
00481       _x = self
00482       start = end
00483       end += 8
00484       (_x.camera_info.height, _x.camera_info.width,) = _struct_2I.unpack(str[start:end])
00485       start = end
00486       end += 4
00487       (length,) = _struct_I.unpack(str[start:end])
00488       start = end
00489       end += length
00490       if python3:
00491         self.camera_info.distortion_model = str[start:end].decode('utf-8')
00492       else:
00493         self.camera_info.distortion_model = str[start:end]
00494       start = end
00495       end += 4
00496       (length,) = _struct_I.unpack(str[start:end])
00497       pattern = '<%sd'%length
00498       start = end
00499       end += struct.calcsize(pattern)
00500       self.camera_info.D = struct.unpack(pattern, str[start:end])
00501       start = end
00502       end += 72
00503       self.camera_info.K = _struct_9d.unpack(str[start:end])
00504       start = end
00505       end += 72
00506       self.camera_info.R = _struct_9d.unpack(str[start:end])
00507       start = end
00508       end += 96
00509       self.camera_info.P = _struct_12d.unpack(str[start:end])
00510       _x = self
00511       start = end
00512       end += 25
00513       (_x.camera_info.binning_x, _x.camera_info.binning_y, _x.camera_info.roi.x_offset, _x.camera_info.roi.y_offset, _x.camera_info.roi.height, _x.camera_info.roi.width, _x.camera_info.roi.do_rectify,) = _struct_6IB.unpack(str[start:end])
00514       self.camera_info.roi.do_rectify = bool(self.camera_info.roi.do_rectify)
00515       start = end
00516       end += 4
00517       (length,) = _struct_I.unpack(str[start:end])
00518       self.model_hypotheses = []
00519       for i in range(0, length):
00520         val1 = interactive_perception_msgs.msg.ModelHypothesisList()
00521         start = end
00522         end += 4
00523         (length,) = _struct_I.unpack(str[start:end])
00524         val1.hypotheses = []
00525         for i in range(0, length):
00526           val2 = interactive_perception_msgs.msg.ModelHypothesis()
00527           _v8 = val2.mesh
00528           start = end
00529           end += 4
00530           (length,) = _struct_I.unpack(str[start:end])
00531           _v8.triangles = []
00532           for i in range(0, length):
00533             val4 = shape_msgs.msg.MeshTriangle()
00534             start = end
00535             end += 12
00536             val4.vertex_indices = _struct_3I.unpack(str[start:end])
00537             _v8.triangles.append(val4)
00538           start = end
00539           end += 4
00540           (length,) = _struct_I.unpack(str[start:end])
00541           _v8.vertices = []
00542           for i in range(0, length):
00543             val4 = geometry_msgs.msg.Point()
00544             _x = val4
00545             start = end
00546             end += 24
00547             (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00548             _v8.vertices.append(val4)
00549           _v9 = val2.pose
00550           _v10 = _v9.header
00551           start = end
00552           end += 4
00553           (_v10.seq,) = _struct_I.unpack(str[start:end])
00554           _v11 = _v10.stamp
00555           _x = _v11
00556           start = end
00557           end += 8
00558           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00559           start = end
00560           end += 4
00561           (length,) = _struct_I.unpack(str[start:end])
00562           start = end
00563           end += length
00564           if python3:
00565             _v10.frame_id = str[start:end].decode('utf-8')
00566           else:
00567             _v10.frame_id = str[start:end]
00568           _v12 = _v9.pose
00569           _v13 = _v12.position
00570           _x = _v13
00571           start = end
00572           end += 24
00573           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00574           _v14 = _v12.orientation
00575           _x = _v14
00576           start = end
00577           end += 32
00578           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00579           val1.hypotheses.append(val2)
00580         start = end
00581         end += 1
00582         (val1.accept,) = _struct_B.unpack(str[start:end])
00583         val1.accept = bool(val1.accept)
00584         self.model_hypotheses.append(val1)
00585       return self
00586     except struct.error as e:
00587       raise genpy.DeserializationError(e) #most likely buffer underfill
00588 
00589 
00590   def serialize_numpy(self, buff, numpy):
00591     """
00592     serialize message with numpy array types into buffer
00593     :param buff: buffer, ``StringIO``
00594     :param numpy: numpy python module
00595     """
00596     try:
00597       _x = self
00598       buff.write(_struct_3I.pack(_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs))
00599       _x = self.image.header.frame_id
00600       length = len(_x)
00601       if python3 or type(_x) == unicode:
00602         _x = _x.encode('utf-8')
00603         length = len(_x)
00604       buff.write(struct.pack('<I%ss'%length, length, _x))
00605       _x = self
00606       buff.write(_struct_2I.pack(_x.image.height, _x.image.width))
00607       _x = self.image.encoding
00608       length = len(_x)
00609       if python3 or type(_x) == unicode:
00610         _x = _x.encode('utf-8')
00611         length = len(_x)
00612       buff.write(struct.pack('<I%ss'%length, length, _x))
00613       _x = self
00614       buff.write(_struct_BI.pack(_x.image.is_bigendian, _x.image.step))
00615       _x = self.image.data
00616       length = len(_x)
00617       # - if encoded as a list instead, serialize as bytes instead of string
00618       if type(_x) in [list, tuple]:
00619         buff.write(struct.pack('<I%sB'%length, length, *_x))
00620       else:
00621         buff.write(struct.pack('<I%ss'%length, length, _x))
00622       _x = self
00623       buff.write(_struct_3I.pack(_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs))
00624       _x = self.camera_info.header.frame_id
00625       length = len(_x)
00626       if python3 or type(_x) == unicode:
00627         _x = _x.encode('utf-8')
00628         length = len(_x)
00629       buff.write(struct.pack('<I%ss'%length, length, _x))
00630       _x = self
00631       buff.write(_struct_2I.pack(_x.camera_info.height, _x.camera_info.width))
00632       _x = self.camera_info.distortion_model
00633       length = len(_x)
00634       if python3 or type(_x) == unicode:
00635         _x = _x.encode('utf-8')
00636         length = len(_x)
00637       buff.write(struct.pack('<I%ss'%length, length, _x))
00638       length = len(self.camera_info.D)
00639       buff.write(_struct_I.pack(length))
00640       pattern = '<%sd'%length
00641       buff.write(self.camera_info.D.tostring())
00642       buff.write(self.camera_info.K.tostring())
00643       buff.write(self.camera_info.R.tostring())
00644       buff.write(self.camera_info.P.tostring())
00645       _x = self
00646       buff.write(_struct_6IB.pack(_x.camera_info.binning_x, _x.camera_info.binning_y, _x.camera_info.roi.x_offset, _x.camera_info.roi.y_offset, _x.camera_info.roi.height, _x.camera_info.roi.width, _x.camera_info.roi.do_rectify))
00647       length = len(self.model_hypotheses)
00648       buff.write(_struct_I.pack(length))
00649       for val1 in self.model_hypotheses:
00650         length = len(val1.hypotheses)
00651         buff.write(_struct_I.pack(length))
00652         for val2 in val1.hypotheses:
00653           _v15 = val2.mesh
00654           length = len(_v15.triangles)
00655           buff.write(_struct_I.pack(length))
00656           for val4 in _v15.triangles:
00657             buff.write(val4.vertex_indices.tostring())
00658           length = len(_v15.vertices)
00659           buff.write(_struct_I.pack(length))
00660           for val4 in _v15.vertices:
00661             _x = val4
00662             buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00663           _v16 = val2.pose
00664           _v17 = _v16.header
00665           buff.write(_struct_I.pack(_v17.seq))
00666           _v18 = _v17.stamp
00667           _x = _v18
00668           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00669           _x = _v17.frame_id
00670           length = len(_x)
00671           if python3 or type(_x) == unicode:
00672             _x = _x.encode('utf-8')
00673             length = len(_x)
00674           buff.write(struct.pack('<I%ss'%length, length, _x))
00675           _v19 = _v16.pose
00676           _v20 = _v19.position
00677           _x = _v20
00678           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00679           _v21 = _v19.orientation
00680           _x = _v21
00681           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00682         buff.write(_struct_B.pack(val1.accept))
00683     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00684     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00685 
00686   def deserialize_numpy(self, str, numpy):
00687     """
00688     unpack serialized message in str into this message instance using numpy for array types
00689     :param str: byte array of serialized message, ``str``
00690     :param numpy: numpy python module
00691     """
00692     try:
00693       if self.image is None:
00694         self.image = sensor_msgs.msg.Image()
00695       if self.camera_info is None:
00696         self.camera_info = sensor_msgs.msg.CameraInfo()
00697       if self.model_hypotheses is None:
00698         self.model_hypotheses = None
00699       end = 0
00700       _x = self
00701       start = end
00702       end += 12
00703       (_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00704       start = end
00705       end += 4
00706       (length,) = _struct_I.unpack(str[start:end])
00707       start = end
00708       end += length
00709       if python3:
00710         self.image.header.frame_id = str[start:end].decode('utf-8')
00711       else:
00712         self.image.header.frame_id = str[start:end]
00713       _x = self
00714       start = end
00715       end += 8
00716       (_x.image.height, _x.image.width,) = _struct_2I.unpack(str[start:end])
00717       start = end
00718       end += 4
00719       (length,) = _struct_I.unpack(str[start:end])
00720       start = end
00721       end += length
00722       if python3:
00723         self.image.encoding = str[start:end].decode('utf-8')
00724       else:
00725         self.image.encoding = str[start:end]
00726       _x = self
00727       start = end
00728       end += 5
00729       (_x.image.is_bigendian, _x.image.step,) = _struct_BI.unpack(str[start:end])
00730       start = end
00731       end += 4
00732       (length,) = _struct_I.unpack(str[start:end])
00733       start = end
00734       end += length
00735       self.image.data = str[start:end]
00736       _x = self
00737       start = end
00738       end += 12
00739       (_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00740       start = end
00741       end += 4
00742       (length,) = _struct_I.unpack(str[start:end])
00743       start = end
00744       end += length
00745       if python3:
00746         self.camera_info.header.frame_id = str[start:end].decode('utf-8')
00747       else:
00748         self.camera_info.header.frame_id = str[start:end]
00749       _x = self
00750       start = end
00751       end += 8
00752       (_x.camera_info.height, _x.camera_info.width,) = _struct_2I.unpack(str[start:end])
00753       start = end
00754       end += 4
00755       (length,) = _struct_I.unpack(str[start:end])
00756       start = end
00757       end += length
00758       if python3:
00759         self.camera_info.distortion_model = str[start:end].decode('utf-8')
00760       else:
00761         self.camera_info.distortion_model = str[start:end]
00762       start = end
00763       end += 4
00764       (length,) = _struct_I.unpack(str[start:end])
00765       pattern = '<%sd'%length
00766       start = end
00767       end += struct.calcsize(pattern)
00768       self.camera_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00769       start = end
00770       end += 72
00771       self.camera_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00772       start = end
00773       end += 72
00774       self.camera_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00775       start = end
00776       end += 96
00777       self.camera_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
00778       _x = self
00779       start = end
00780       end += 25
00781       (_x.camera_info.binning_x, _x.camera_info.binning_y, _x.camera_info.roi.x_offset, _x.camera_info.roi.y_offset, _x.camera_info.roi.height, _x.camera_info.roi.width, _x.camera_info.roi.do_rectify,) = _struct_6IB.unpack(str[start:end])
00782       self.camera_info.roi.do_rectify = bool(self.camera_info.roi.do_rectify)
00783       start = end
00784       end += 4
00785       (length,) = _struct_I.unpack(str[start:end])
00786       self.model_hypotheses = []
00787       for i in range(0, length):
00788         val1 = interactive_perception_msgs.msg.ModelHypothesisList()
00789         start = end
00790         end += 4
00791         (length,) = _struct_I.unpack(str[start:end])
00792         val1.hypotheses = []
00793         for i in range(0, length):
00794           val2 = interactive_perception_msgs.msg.ModelHypothesis()
00795           _v22 = val2.mesh
00796           start = end
00797           end += 4
00798           (length,) = _struct_I.unpack(str[start:end])
00799           _v22.triangles = []
00800           for i in range(0, length):
00801             val4 = shape_msgs.msg.MeshTriangle()
00802             start = end
00803             end += 12
00804             val4.vertex_indices = numpy.frombuffer(str[start:end], dtype=numpy.uint32, count=3)
00805             _v22.triangles.append(val4)
00806           start = end
00807           end += 4
00808           (length,) = _struct_I.unpack(str[start:end])
00809           _v22.vertices = []
00810           for i in range(0, length):
00811             val4 = geometry_msgs.msg.Point()
00812             _x = val4
00813             start = end
00814             end += 24
00815             (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00816             _v22.vertices.append(val4)
00817           _v23 = val2.pose
00818           _v24 = _v23.header
00819           start = end
00820           end += 4
00821           (_v24.seq,) = _struct_I.unpack(str[start:end])
00822           _v25 = _v24.stamp
00823           _x = _v25
00824           start = end
00825           end += 8
00826           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00827           start = end
00828           end += 4
00829           (length,) = _struct_I.unpack(str[start:end])
00830           start = end
00831           end += length
00832           if python3:
00833             _v24.frame_id = str[start:end].decode('utf-8')
00834           else:
00835             _v24.frame_id = str[start:end]
00836           _v26 = _v23.pose
00837           _v27 = _v26.position
00838           _x = _v27
00839           start = end
00840           end += 24
00841           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00842           _v28 = _v26.orientation
00843           _x = _v28
00844           start = end
00845           end += 32
00846           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00847           val1.hypotheses.append(val2)
00848         start = end
00849         end += 1
00850         (val1.accept,) = _struct_B.unpack(str[start:end])
00851         val1.accept = bool(val1.accept)
00852         self.model_hypotheses.append(val1)
00853       return self
00854     except struct.error as e:
00855       raise genpy.DeserializationError(e) #most likely buffer underfill
00856 
00857 _struct_I = genpy.struct_I
00858 _struct_6IB = struct.Struct("<6IB")
00859 _struct_B = struct.Struct("<B")
00860 _struct_12d = struct.Struct("<12d")
00861 _struct_9d = struct.Struct("<9d")
00862 _struct_BI = struct.Struct("<BI")
00863 _struct_3I = struct.Struct("<3I")
00864 _struct_4d = struct.Struct("<4d")
00865 _struct_2I = struct.Struct("<2I")
00866 _struct_3d = struct.Struct("<3d")


interactive_perception_msgs
Author(s): jbinney
autogenerated on Mon Oct 6 2014 11:51:20