_GraspPlanning.py
Go to the documentation of this file.
00001 """autogenerated by genpy from object_manipulation_msgs/GraspPlanningRequest.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 sensor_msgs.msg
00009 import std_msgs.msg
00010 import object_manipulation_msgs.msg
00011 import household_objects_database_msgs.msg
00012 
00013 class GraspPlanningRequest(genpy.Message):
00014   _md5sum = "5003fdf2225280c9d81c2bce4e645c20"
00015   _type = "object_manipulation_msgs/GraspPlanningRequest"
00016   _has_header = False #flag to mark the presence of a Header object
00017   _full_text = """
00018 
00019 
00020 
00021 string arm_name
00022 
00023 
00024 GraspableObject target
00025 
00026 
00027 
00028 string collision_object_name
00029 
00030 
00031 
00032 string collision_support_surface_name
00033 
00034 
00035 Grasp[] grasps_to_evaluate
00036 
00037 
00038 
00039 GraspableObject[] movable_obstacles
00040 
00041 
00042 ================================================================================
00043 MSG: object_manipulation_msgs/GraspableObject
00044 # an object that the object_manipulator can work on
00045 
00046 # a graspable object can be represented in multiple ways. This message
00047 # can contain all of them. Which one is actually used is up to the receiver
00048 # of this message. When adding new representations, one must be careful that
00049 # they have reasonable lightweight defaults indicating that that particular
00050 # representation is not available.
00051 
00052 # the tf frame to be used as a reference frame when combining information from
00053 # the different representations below
00054 string reference_frame_id
00055 
00056 # potential recognition results from a database of models
00057 # all poses are relative to the object reference pose
00058 household_objects_database_msgs/DatabaseModelPose[] potential_models
00059 
00060 # the point cloud itself
00061 sensor_msgs/PointCloud cluster
00062 
00063 # a region of a PointCloud2 of interest
00064 object_manipulation_msgs/SceneRegion region
00065 
00066 # the name that this object has in the collision environment
00067 string collision_name
00068 ================================================================================
00069 MSG: household_objects_database_msgs/DatabaseModelPose
00070 # Informs that a specific model from the Model Database has been 
00071 # identified at a certain location
00072 
00073 # the database id of the model
00074 int32 model_id
00075 
00076 # the pose that it can be found in
00077 geometry_msgs/PoseStamped pose
00078 
00079 # a measure of the confidence level in this detection result
00080 float32 confidence
00081 
00082 # the name of the object detector that generated this detection result
00083 string detector_name
00084 
00085 ================================================================================
00086 MSG: geometry_msgs/PoseStamped
00087 # A Pose with reference coordinate frame and timestamp
00088 Header header
00089 Pose pose
00090 
00091 ================================================================================
00092 MSG: std_msgs/Header
00093 # Standard metadata for higher-level stamped data types.
00094 # This is generally used to communicate timestamped data 
00095 # in a particular coordinate frame.
00096 # 
00097 # sequence ID: consecutively increasing ID 
00098 uint32 seq
00099 #Two-integer timestamp that is expressed as:
00100 # * stamp.secs: seconds (stamp_secs) since epoch
00101 # * stamp.nsecs: nanoseconds since stamp_secs
00102 # time-handling sugar is provided by the client library
00103 time stamp
00104 #Frame this data is associated with
00105 # 0: no frame
00106 # 1: global frame
00107 string frame_id
00108 
00109 ================================================================================
00110 MSG: geometry_msgs/Pose
00111 # A representation of pose in free space, composed of postion and orientation. 
00112 Point position
00113 Quaternion orientation
00114 
00115 ================================================================================
00116 MSG: geometry_msgs/Point
00117 # This contains the position of a point in free space
00118 float64 x
00119 float64 y
00120 float64 z
00121 
00122 ================================================================================
00123 MSG: geometry_msgs/Quaternion
00124 # This represents an orientation in free space in quaternion form.
00125 
00126 float64 x
00127 float64 y
00128 float64 z
00129 float64 w
00130 
00131 ================================================================================
00132 MSG: sensor_msgs/PointCloud
00133 # This message holds a collection of 3d points, plus optional additional
00134 # information about each point.
00135 
00136 # Time of sensor data acquisition, coordinate frame ID.
00137 Header header
00138 
00139 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00140 # in the frame given in the header.
00141 geometry_msgs/Point32[] points
00142 
00143 # Each channel should have the same number of elements as points array,
00144 # and the data in each channel should correspond 1:1 with each point.
00145 # Channel names in common practice are listed in ChannelFloat32.msg.
00146 ChannelFloat32[] channels
00147 
00148 ================================================================================
00149 MSG: geometry_msgs/Point32
00150 # This contains the position of a point in free space(with 32 bits of precision).
00151 # It is recommeded to use Point wherever possible instead of Point32.  
00152 # 
00153 # This recommendation is to promote interoperability.  
00154 #
00155 # This message is designed to take up less space when sending
00156 # lots of points at once, as in the case of a PointCloud.  
00157 
00158 float32 x
00159 float32 y
00160 float32 z
00161 ================================================================================
00162 MSG: sensor_msgs/ChannelFloat32
00163 # This message is used by the PointCloud message to hold optional data
00164 # associated with each point in the cloud. The length of the values
00165 # array should be the same as the length of the points array in the
00166 # PointCloud, and each value should be associated with the corresponding
00167 # point.
00168 
00169 # Channel names in existing practice include:
00170 #   "u", "v" - row and column (respectively) in the left stereo image.
00171 #              This is opposite to usual conventions but remains for
00172 #              historical reasons. The newer PointCloud2 message has no
00173 #              such problem.
00174 #   "rgb" - For point clouds produced by color stereo cameras. uint8
00175 #           (R,G,B) values packed into the least significant 24 bits,
00176 #           in order.
00177 #   "intensity" - laser or pixel intensity.
00178 #   "distance"
00179 
00180 # The channel name should give semantics of the channel (e.g.
00181 # "intensity" instead of "value").
00182 string name
00183 
00184 # The values array should be 1-1 with the elements of the associated
00185 # PointCloud.
00186 float32[] values
00187 
00188 ================================================================================
00189 MSG: object_manipulation_msgs/SceneRegion
00190 # Point cloud
00191 sensor_msgs/PointCloud2 cloud
00192 
00193 # Indices for the region of interest
00194 int32[] mask
00195 
00196 # One of the corresponding 2D images, if applicable
00197 sensor_msgs/Image image
00198 
00199 # The disparity image, if applicable
00200 sensor_msgs/Image disparity_image
00201 
00202 # Camera info for the camera that took the image
00203 sensor_msgs/CameraInfo cam_info
00204 
00205 # a 3D region of interest for grasp planning
00206 geometry_msgs/PoseStamped  roi_box_pose
00207 geometry_msgs/Vector3      roi_box_dims
00208 
00209 ================================================================================
00210 MSG: sensor_msgs/PointCloud2
00211 # This message holds a collection of N-dimensional points, which may
00212 # contain additional information such as normals, intensity, etc. The
00213 # point data is stored as a binary blob, its layout described by the
00214 # contents of the "fields" array.
00215 
00216 # The point cloud data may be organized 2d (image-like) or 1d
00217 # (unordered). Point clouds organized as 2d images may be produced by
00218 # camera depth sensors such as stereo or time-of-flight.
00219 
00220 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00221 # points).
00222 Header header
00223 
00224 # 2D structure of the point cloud. If the cloud is unordered, height is
00225 # 1 and width is the length of the point cloud.
00226 uint32 height
00227 uint32 width
00228 
00229 # Describes the channels and their layout in the binary data blob.
00230 PointField[] fields
00231 
00232 bool    is_bigendian # Is this data bigendian?
00233 uint32  point_step   # Length of a point in bytes
00234 uint32  row_step     # Length of a row in bytes
00235 uint8[] data         # Actual point data, size is (row_step*height)
00236 
00237 bool is_dense        # True if there are no invalid points
00238 
00239 ================================================================================
00240 MSG: sensor_msgs/PointField
00241 # This message holds the description of one point entry in the
00242 # PointCloud2 message format.
00243 uint8 INT8    = 1
00244 uint8 UINT8   = 2
00245 uint8 INT16   = 3
00246 uint8 UINT16  = 4
00247 uint8 INT32   = 5
00248 uint8 UINT32  = 6
00249 uint8 FLOAT32 = 7
00250 uint8 FLOAT64 = 8
00251 
00252 string name      # Name of field
00253 uint32 offset    # Offset from start of point struct
00254 uint8  datatype  # Datatype enumeration, see above
00255 uint32 count     # How many elements in the field
00256 
00257 ================================================================================
00258 MSG: sensor_msgs/Image
00259 # This message contains an uncompressed image
00260 # (0, 0) is at top-left corner of image
00261 #
00262 
00263 Header header        # Header timestamp should be acquisition time of image
00264                      # Header frame_id should be optical frame of camera
00265                      # origin of frame should be optical center of cameara
00266                      # +x should point to the right in the image
00267                      # +y should point down in the image
00268                      # +z should point into to plane of the image
00269                      # If the frame_id here and the frame_id of the CameraInfo
00270                      # message associated with the image conflict
00271                      # the behavior is undefined
00272 
00273 uint32 height         # image height, that is, number of rows
00274 uint32 width          # image width, that is, number of columns
00275 
00276 # The legal values for encoding are in file src/image_encodings.cpp
00277 # If you want to standardize a new string format, join
00278 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00279 
00280 string encoding       # Encoding of pixels -- channel meaning, ordering, size
00281                       # taken from the list of strings in src/image_encodings.cpp
00282 
00283 uint8 is_bigendian    # is this data bigendian?
00284 uint32 step           # Full row length in bytes
00285 uint8[] data          # actual matrix data, size is (step * rows)
00286 
00287 ================================================================================
00288 MSG: sensor_msgs/CameraInfo
00289 # This message defines meta information for a camera. It should be in a
00290 # camera namespace on topic "camera_info" and accompanied by up to five
00291 # image topics named:
00292 #
00293 #   image_raw - raw data from the camera driver, possibly Bayer encoded
00294 #   image            - monochrome, distorted
00295 #   image_color      - color, distorted
00296 #   image_rect       - monochrome, rectified
00297 #   image_rect_color - color, rectified
00298 #
00299 # The image_pipeline contains packages (image_proc, stereo_image_proc)
00300 # for producing the four processed image topics from image_raw and
00301 # camera_info. The meaning of the camera parameters are described in
00302 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
00303 #
00304 # The image_geometry package provides a user-friendly interface to
00305 # common operations using this meta information. If you want to, e.g.,
00306 # project a 3d point into image coordinates, we strongly recommend
00307 # using image_geometry.
00308 #
00309 # If the camera is uncalibrated, the matrices D, K, R, P should be left
00310 # zeroed out. In particular, clients may assume that K[0] == 0.0
00311 # indicates an uncalibrated camera.
00312 
00313 #######################################################################
00314 #                     Image acquisition info                          #
00315 #######################################################################
00316 
00317 # Time of image acquisition, camera coordinate frame ID
00318 Header header    # Header timestamp should be acquisition time of image
00319                  # Header frame_id should be optical frame of camera
00320                  # origin of frame should be optical center of camera
00321                  # +x should point to the right in the image
00322                  # +y should point down in the image
00323                  # +z should point into the plane of the image
00324 
00325 
00326 #######################################################################
00327 #                      Calibration Parameters                         #
00328 #######################################################################
00329 # These are fixed during camera calibration. Their values will be the #
00330 # same in all messages until the camera is recalibrated. Note that    #
00331 # self-calibrating systems may "recalibrate" frequently.              #
00332 #                                                                     #
00333 # The internal parameters can be used to warp a raw (distorted) image #
00334 # to:                                                                 #
00335 #   1. An undistorted image (requires D and K)                        #
00336 #   2. A rectified image (requires D, K, R)                           #
00337 # The projection matrix P projects 3D points into the rectified image.#
00338 #######################################################################
00339 
00340 # The image dimensions with which the camera was calibrated. Normally
00341 # this will be the full camera resolution in pixels.
00342 uint32 height
00343 uint32 width
00344 
00345 # The distortion model used. Supported models are listed in
00346 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
00347 # simple model of radial and tangential distortion - is sufficent.
00348 string distortion_model
00349 
00350 # The distortion parameters, size depending on the distortion model.
00351 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
00352 float64[] D
00353 
00354 # Intrinsic camera matrix for the raw (distorted) images.
00355 #     [fx  0 cx]
00356 # K = [ 0 fy cy]
00357 #     [ 0  0  1]
00358 # Projects 3D points in the camera coordinate frame to 2D pixel
00359 # coordinates using the focal lengths (fx, fy) and principal point
00360 # (cx, cy).
00361 float64[9]  K # 3x3 row-major matrix
00362 
00363 # Rectification matrix (stereo cameras only)
00364 # A rotation matrix aligning the camera coordinate system to the ideal
00365 # stereo image plane so that epipolar lines in both stereo images are
00366 # parallel.
00367 float64[9]  R # 3x3 row-major matrix
00368 
00369 # Projection/camera matrix
00370 #     [fx'  0  cx' Tx]
00371 # P = [ 0  fy' cy' Ty]
00372 #     [ 0   0   1   0]
00373 # By convention, this matrix specifies the intrinsic (camera) matrix
00374 #  of the processed (rectified) image. That is, the left 3x3 portion
00375 #  is the normal camera intrinsic matrix for the rectified image.
00376 # It projects 3D points in the camera coordinate frame to 2D pixel
00377 #  coordinates using the focal lengths (fx', fy') and principal point
00378 #  (cx', cy') - these may differ from the values in K.
00379 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
00380 #  also have R = the identity and P[1:3,1:3] = K.
00381 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
00382 #  position of the optical center of the second camera in the first
00383 #  camera's frame. We assume Tz = 0 so both cameras are in the same
00384 #  stereo image plane. The first camera always has Tx = Ty = 0. For
00385 #  the right (second) camera of a horizontal stereo pair, Ty = 0 and
00386 #  Tx = -fx' * B, where B is the baseline between the cameras.
00387 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
00388 #  the rectified image is given by:
00389 #  [u v w]' = P * [X Y Z 1]'
00390 #         x = u / w
00391 #         y = v / w
00392 #  This holds for both images of a stereo pair.
00393 float64[12] P # 3x4 row-major matrix
00394 
00395 
00396 #######################################################################
00397 #                      Operational Parameters                         #
00398 #######################################################################
00399 # These define the image region actually captured by the camera       #
00400 # driver. Although they affect the geometry of the output image, they #
00401 # may be changed freely without recalibrating the camera.             #
00402 #######################################################################
00403 
00404 # Binning refers here to any camera setting which combines rectangular
00405 #  neighborhoods of pixels into larger "super-pixels." It reduces the
00406 #  resolution of the output image to
00407 #  (width / binning_x) x (height / binning_y).
00408 # The default values binning_x = binning_y = 0 is considered the same
00409 #  as binning_x = binning_y = 1 (no subsampling).
00410 uint32 binning_x
00411 uint32 binning_y
00412 
00413 # Region of interest (subwindow of full camera resolution), given in
00414 #  full resolution (unbinned) image coordinates. A particular ROI
00415 #  always denotes the same window of pixels on the camera sensor,
00416 #  regardless of binning settings.
00417 # The default setting of roi (all values 0) is considered the same as
00418 #  full resolution (roi.width = width, roi.height = height).
00419 RegionOfInterest roi
00420 
00421 ================================================================================
00422 MSG: sensor_msgs/RegionOfInterest
00423 # This message is used to specify a region of interest within an image.
00424 #
00425 # When used to specify the ROI setting of the camera when the image was
00426 # taken, the height and width fields should either match the height and
00427 # width fields for the associated image; or height = width = 0
00428 # indicates that the full resolution image was captured.
00429 
00430 uint32 x_offset  # Leftmost pixel of the ROI
00431                  # (0 if the ROI includes the left edge of the image)
00432 uint32 y_offset  # Topmost pixel of the ROI
00433                  # (0 if the ROI includes the top edge of the image)
00434 uint32 height    # Height of ROI
00435 uint32 width     # Width of ROI
00436 
00437 # True if a distinct rectified ROI should be calculated from the "raw"
00438 # ROI in this message. Typically this should be False if the full image
00439 # is captured (ROI not used), and True if a subwindow is captured (ROI
00440 # used).
00441 bool do_rectify
00442 
00443 ================================================================================
00444 MSG: geometry_msgs/Vector3
00445 # This represents a vector in free space. 
00446 
00447 float64 x
00448 float64 y
00449 float64 z
00450 ================================================================================
00451 MSG: object_manipulation_msgs/Grasp
00452 
00453 # The internal posture of the hand for the pre-grasp
00454 # only positions are used
00455 sensor_msgs/JointState pre_grasp_posture
00456 
00457 # The internal posture of the hand for the grasp
00458 # positions and efforts are used
00459 sensor_msgs/JointState grasp_posture
00460 
00461 # The position of the end-effector for the grasp relative to a reference frame 
00462 # (that is always specified elsewhere, not in this message)
00463 geometry_msgs/Pose grasp_pose
00464 
00465 # The estimated probability of success for this grasp
00466 float64 success_probability
00467 
00468 # Debug flag to indicate that this grasp would be the best in its cluster
00469 bool cluster_rep
00470 
00471 # how far the pre-grasp should ideally be away from the grasp
00472 float32 desired_approach_distance
00473 
00474 # how much distance between pre-grasp and grasp must actually be feasible 
00475 # for the grasp not to be rejected
00476 float32 min_approach_distance
00477 
00478 # an optional list of obstacles that we have semantic information about
00479 # and that we expect might move in the course of executing this grasp
00480 # the grasp planner is expected to make sure they move in an OK way; during
00481 # execution, grasp executors will not check for collisions against these objects
00482 GraspableObject[] moved_obstacles
00483 
00484 ================================================================================
00485 MSG: sensor_msgs/JointState
00486 # This is a message that holds data to describe the state of a set of torque controlled joints. 
00487 #
00488 # The state of each joint (revolute or prismatic) is defined by:
00489 #  * the position of the joint (rad or m),
00490 #  * the velocity of the joint (rad/s or m/s) and 
00491 #  * the effort that is applied in the joint (Nm or N).
00492 #
00493 # Each joint is uniquely identified by its name
00494 # The header specifies the time at which the joint states were recorded. All the joint states
00495 # in one message have to be recorded at the same time.
00496 #
00497 # This message consists of a multiple arrays, one for each part of the joint state. 
00498 # The goal is to make each of the fields optional. When e.g. your joints have no
00499 # effort associated with them, you can leave the effort array empty. 
00500 #
00501 # All arrays in this message should have the same size, or be empty.
00502 # This is the only way to uniquely associate the joint name with the correct
00503 # states.
00504 
00505 
00506 Header header
00507 
00508 string[] name
00509 float64[] position
00510 float64[] velocity
00511 float64[] effort
00512 
00513 """
00514   __slots__ = ['arm_name','target','collision_object_name','collision_support_surface_name','grasps_to_evaluate','movable_obstacles']
00515   _slot_types = ['string','object_manipulation_msgs/GraspableObject','string','string','object_manipulation_msgs/Grasp[]','object_manipulation_msgs/GraspableObject[]']
00516 
00517   def __init__(self, *args, **kwds):
00518     """
00519     Constructor. Any message fields that are implicitly/explicitly
00520     set to None will be assigned a default value. The recommend
00521     use is keyword arguments as this is more robust to future message
00522     changes.  You cannot mix in-order arguments and keyword arguments.
00523 
00524     The available fields are:
00525        arm_name,target,collision_object_name,collision_support_surface_name,grasps_to_evaluate,movable_obstacles
00526 
00527     :param args: complete set of field values, in .msg order
00528     :param kwds: use keyword arguments corresponding to message field names
00529     to set specific fields.
00530     """
00531     if args or kwds:
00532       super(GraspPlanningRequest, self).__init__(*args, **kwds)
00533       #message fields cannot be None, assign default values for those that are
00534       if self.arm_name is None:
00535         self.arm_name = ''
00536       if self.target is None:
00537         self.target = object_manipulation_msgs.msg.GraspableObject()
00538       if self.collision_object_name is None:
00539         self.collision_object_name = ''
00540       if self.collision_support_surface_name is None:
00541         self.collision_support_surface_name = ''
00542       if self.grasps_to_evaluate is None:
00543         self.grasps_to_evaluate = []
00544       if self.movable_obstacles is None:
00545         self.movable_obstacles = []
00546     else:
00547       self.arm_name = ''
00548       self.target = object_manipulation_msgs.msg.GraspableObject()
00549       self.collision_object_name = ''
00550       self.collision_support_surface_name = ''
00551       self.grasps_to_evaluate = []
00552       self.movable_obstacles = []
00553 
00554   def _get_types(self):
00555     """
00556     internal API method
00557     """
00558     return self._slot_types
00559 
00560   def serialize(self, buff):
00561     """
00562     serialize message into buffer
00563     :param buff: buffer, ``StringIO``
00564     """
00565     try:
00566       _x = self.arm_name
00567       length = len(_x)
00568       if python3 or type(_x) == unicode:
00569         _x = _x.encode('utf-8')
00570         length = len(_x)
00571       buff.write(struct.pack('<I%ss'%length, length, _x))
00572       _x = self.target.reference_frame_id
00573       length = len(_x)
00574       if python3 or type(_x) == unicode:
00575         _x = _x.encode('utf-8')
00576         length = len(_x)
00577       buff.write(struct.pack('<I%ss'%length, length, _x))
00578       length = len(self.target.potential_models)
00579       buff.write(_struct_I.pack(length))
00580       for val1 in self.target.potential_models:
00581         buff.write(_struct_i.pack(val1.model_id))
00582         _v1 = val1.pose
00583         _v2 = _v1.header
00584         buff.write(_struct_I.pack(_v2.seq))
00585         _v3 = _v2.stamp
00586         _x = _v3
00587         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00588         _x = _v2.frame_id
00589         length = len(_x)
00590         if python3 or type(_x) == unicode:
00591           _x = _x.encode('utf-8')
00592           length = len(_x)
00593         buff.write(struct.pack('<I%ss'%length, length, _x))
00594         _v4 = _v1.pose
00595         _v5 = _v4.position
00596         _x = _v5
00597         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00598         _v6 = _v4.orientation
00599         _x = _v6
00600         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00601         buff.write(_struct_f.pack(val1.confidence))
00602         _x = val1.detector_name
00603         length = len(_x)
00604         if python3 or type(_x) == unicode:
00605           _x = _x.encode('utf-8')
00606           length = len(_x)
00607         buff.write(struct.pack('<I%ss'%length, length, _x))
00608       _x = self
00609       buff.write(_struct_3I.pack(_x.target.cluster.header.seq, _x.target.cluster.header.stamp.secs, _x.target.cluster.header.stamp.nsecs))
00610       _x = self.target.cluster.header.frame_id
00611       length = len(_x)
00612       if python3 or type(_x) == unicode:
00613         _x = _x.encode('utf-8')
00614         length = len(_x)
00615       buff.write(struct.pack('<I%ss'%length, length, _x))
00616       length = len(self.target.cluster.points)
00617       buff.write(_struct_I.pack(length))
00618       for val1 in self.target.cluster.points:
00619         _x = val1
00620         buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00621       length = len(self.target.cluster.channels)
00622       buff.write(_struct_I.pack(length))
00623       for val1 in self.target.cluster.channels:
00624         _x = val1.name
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         length = len(val1.values)
00631         buff.write(_struct_I.pack(length))
00632         pattern = '<%sf'%length
00633         buff.write(struct.pack(pattern, *val1.values))
00634       _x = self
00635       buff.write(_struct_3I.pack(_x.target.region.cloud.header.seq, _x.target.region.cloud.header.stamp.secs, _x.target.region.cloud.header.stamp.nsecs))
00636       _x = self.target.region.cloud.header.frame_id
00637       length = len(_x)
00638       if python3 or type(_x) == unicode:
00639         _x = _x.encode('utf-8')
00640         length = len(_x)
00641       buff.write(struct.pack('<I%ss'%length, length, _x))
00642       _x = self
00643       buff.write(_struct_2I.pack(_x.target.region.cloud.height, _x.target.region.cloud.width))
00644       length = len(self.target.region.cloud.fields)
00645       buff.write(_struct_I.pack(length))
00646       for val1 in self.target.region.cloud.fields:
00647         _x = val1.name
00648         length = len(_x)
00649         if python3 or type(_x) == unicode:
00650           _x = _x.encode('utf-8')
00651           length = len(_x)
00652         buff.write(struct.pack('<I%ss'%length, length, _x))
00653         _x = val1
00654         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00655       _x = self
00656       buff.write(_struct_B2I.pack(_x.target.region.cloud.is_bigendian, _x.target.region.cloud.point_step, _x.target.region.cloud.row_step))
00657       _x = self.target.region.cloud.data
00658       length = len(_x)
00659       # - if encoded as a list instead, serialize as bytes instead of string
00660       if type(_x) in [list, tuple]:
00661         buff.write(struct.pack('<I%sB'%length, length, *_x))
00662       else:
00663         buff.write(struct.pack('<I%ss'%length, length, _x))
00664       buff.write(_struct_B.pack(self.target.region.cloud.is_dense))
00665       length = len(self.target.region.mask)
00666       buff.write(_struct_I.pack(length))
00667       pattern = '<%si'%length
00668       buff.write(struct.pack(pattern, *self.target.region.mask))
00669       _x = self
00670       buff.write(_struct_3I.pack(_x.target.region.image.header.seq, _x.target.region.image.header.stamp.secs, _x.target.region.image.header.stamp.nsecs))
00671       _x = self.target.region.image.header.frame_id
00672       length = len(_x)
00673       if python3 or type(_x) == unicode:
00674         _x = _x.encode('utf-8')
00675         length = len(_x)
00676       buff.write(struct.pack('<I%ss'%length, length, _x))
00677       _x = self
00678       buff.write(_struct_2I.pack(_x.target.region.image.height, _x.target.region.image.width))
00679       _x = self.target.region.image.encoding
00680       length = len(_x)
00681       if python3 or type(_x) == unicode:
00682         _x = _x.encode('utf-8')
00683         length = len(_x)
00684       buff.write(struct.pack('<I%ss'%length, length, _x))
00685       _x = self
00686       buff.write(_struct_BI.pack(_x.target.region.image.is_bigendian, _x.target.region.image.step))
00687       _x = self.target.region.image.data
00688       length = len(_x)
00689       # - if encoded as a list instead, serialize as bytes instead of string
00690       if type(_x) in [list, tuple]:
00691         buff.write(struct.pack('<I%sB'%length, length, *_x))
00692       else:
00693         buff.write(struct.pack('<I%ss'%length, length, _x))
00694       _x = self
00695       buff.write(_struct_3I.pack(_x.target.region.disparity_image.header.seq, _x.target.region.disparity_image.header.stamp.secs, _x.target.region.disparity_image.header.stamp.nsecs))
00696       _x = self.target.region.disparity_image.header.frame_id
00697       length = len(_x)
00698       if python3 or type(_x) == unicode:
00699         _x = _x.encode('utf-8')
00700         length = len(_x)
00701       buff.write(struct.pack('<I%ss'%length, length, _x))
00702       _x = self
00703       buff.write(_struct_2I.pack(_x.target.region.disparity_image.height, _x.target.region.disparity_image.width))
00704       _x = self.target.region.disparity_image.encoding
00705       length = len(_x)
00706       if python3 or type(_x) == unicode:
00707         _x = _x.encode('utf-8')
00708         length = len(_x)
00709       buff.write(struct.pack('<I%ss'%length, length, _x))
00710       _x = self
00711       buff.write(_struct_BI.pack(_x.target.region.disparity_image.is_bigendian, _x.target.region.disparity_image.step))
00712       _x = self.target.region.disparity_image.data
00713       length = len(_x)
00714       # - if encoded as a list instead, serialize as bytes instead of string
00715       if type(_x) in [list, tuple]:
00716         buff.write(struct.pack('<I%sB'%length, length, *_x))
00717       else:
00718         buff.write(struct.pack('<I%ss'%length, length, _x))
00719       _x = self
00720       buff.write(_struct_3I.pack(_x.target.region.cam_info.header.seq, _x.target.region.cam_info.header.stamp.secs, _x.target.region.cam_info.header.stamp.nsecs))
00721       _x = self.target.region.cam_info.header.frame_id
00722       length = len(_x)
00723       if python3 or type(_x) == unicode:
00724         _x = _x.encode('utf-8')
00725         length = len(_x)
00726       buff.write(struct.pack('<I%ss'%length, length, _x))
00727       _x = self
00728       buff.write(_struct_2I.pack(_x.target.region.cam_info.height, _x.target.region.cam_info.width))
00729       _x = self.target.region.cam_info.distortion_model
00730       length = len(_x)
00731       if python3 or type(_x) == unicode:
00732         _x = _x.encode('utf-8')
00733         length = len(_x)
00734       buff.write(struct.pack('<I%ss'%length, length, _x))
00735       length = len(self.target.region.cam_info.D)
00736       buff.write(_struct_I.pack(length))
00737       pattern = '<%sd'%length
00738       buff.write(struct.pack(pattern, *self.target.region.cam_info.D))
00739       buff.write(_struct_9d.pack(*self.target.region.cam_info.K))
00740       buff.write(_struct_9d.pack(*self.target.region.cam_info.R))
00741       buff.write(_struct_12d.pack(*self.target.region.cam_info.P))
00742       _x = self
00743       buff.write(_struct_6IB3I.pack(_x.target.region.cam_info.binning_x, _x.target.region.cam_info.binning_y, _x.target.region.cam_info.roi.x_offset, _x.target.region.cam_info.roi.y_offset, _x.target.region.cam_info.roi.height, _x.target.region.cam_info.roi.width, _x.target.region.cam_info.roi.do_rectify, _x.target.region.roi_box_pose.header.seq, _x.target.region.roi_box_pose.header.stamp.secs, _x.target.region.roi_box_pose.header.stamp.nsecs))
00744       _x = self.target.region.roi_box_pose.header.frame_id
00745       length = len(_x)
00746       if python3 or type(_x) == unicode:
00747         _x = _x.encode('utf-8')
00748         length = len(_x)
00749       buff.write(struct.pack('<I%ss'%length, length, _x))
00750       _x = self
00751       buff.write(_struct_10d.pack(_x.target.region.roi_box_pose.pose.position.x, _x.target.region.roi_box_pose.pose.position.y, _x.target.region.roi_box_pose.pose.position.z, _x.target.region.roi_box_pose.pose.orientation.x, _x.target.region.roi_box_pose.pose.orientation.y, _x.target.region.roi_box_pose.pose.orientation.z, _x.target.region.roi_box_pose.pose.orientation.w, _x.target.region.roi_box_dims.x, _x.target.region.roi_box_dims.y, _x.target.region.roi_box_dims.z))
00752       _x = self.target.collision_name
00753       length = len(_x)
00754       if python3 or type(_x) == unicode:
00755         _x = _x.encode('utf-8')
00756         length = len(_x)
00757       buff.write(struct.pack('<I%ss'%length, length, _x))
00758       _x = self.collision_object_name
00759       length = len(_x)
00760       if python3 or type(_x) == unicode:
00761         _x = _x.encode('utf-8')
00762         length = len(_x)
00763       buff.write(struct.pack('<I%ss'%length, length, _x))
00764       _x = self.collision_support_surface_name
00765       length = len(_x)
00766       if python3 or type(_x) == unicode:
00767         _x = _x.encode('utf-8')
00768         length = len(_x)
00769       buff.write(struct.pack('<I%ss'%length, length, _x))
00770       length = len(self.grasps_to_evaluate)
00771       buff.write(_struct_I.pack(length))
00772       for val1 in self.grasps_to_evaluate:
00773         _v7 = val1.pre_grasp_posture
00774         _v8 = _v7.header
00775         buff.write(_struct_I.pack(_v8.seq))
00776         _v9 = _v8.stamp
00777         _x = _v9
00778         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00779         _x = _v8.frame_id
00780         length = len(_x)
00781         if python3 or type(_x) == unicode:
00782           _x = _x.encode('utf-8')
00783           length = len(_x)
00784         buff.write(struct.pack('<I%ss'%length, length, _x))
00785         length = len(_v7.name)
00786         buff.write(_struct_I.pack(length))
00787         for val3 in _v7.name:
00788           length = len(val3)
00789           if python3 or type(val3) == unicode:
00790             val3 = val3.encode('utf-8')
00791             length = len(val3)
00792           buff.write(struct.pack('<I%ss'%length, length, val3))
00793         length = len(_v7.position)
00794         buff.write(_struct_I.pack(length))
00795         pattern = '<%sd'%length
00796         buff.write(struct.pack(pattern, *_v7.position))
00797         length = len(_v7.velocity)
00798         buff.write(_struct_I.pack(length))
00799         pattern = '<%sd'%length
00800         buff.write(struct.pack(pattern, *_v7.velocity))
00801         length = len(_v7.effort)
00802         buff.write(_struct_I.pack(length))
00803         pattern = '<%sd'%length
00804         buff.write(struct.pack(pattern, *_v7.effort))
00805         _v10 = val1.grasp_posture
00806         _v11 = _v10.header
00807         buff.write(_struct_I.pack(_v11.seq))
00808         _v12 = _v11.stamp
00809         _x = _v12
00810         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00811         _x = _v11.frame_id
00812         length = len(_x)
00813         if python3 or type(_x) == unicode:
00814           _x = _x.encode('utf-8')
00815           length = len(_x)
00816         buff.write(struct.pack('<I%ss'%length, length, _x))
00817         length = len(_v10.name)
00818         buff.write(_struct_I.pack(length))
00819         for val3 in _v10.name:
00820           length = len(val3)
00821           if python3 or type(val3) == unicode:
00822             val3 = val3.encode('utf-8')
00823             length = len(val3)
00824           buff.write(struct.pack('<I%ss'%length, length, val3))
00825         length = len(_v10.position)
00826         buff.write(_struct_I.pack(length))
00827         pattern = '<%sd'%length
00828         buff.write(struct.pack(pattern, *_v10.position))
00829         length = len(_v10.velocity)
00830         buff.write(_struct_I.pack(length))
00831         pattern = '<%sd'%length
00832         buff.write(struct.pack(pattern, *_v10.velocity))
00833         length = len(_v10.effort)
00834         buff.write(_struct_I.pack(length))
00835         pattern = '<%sd'%length
00836         buff.write(struct.pack(pattern, *_v10.effort))
00837         _v13 = val1.grasp_pose
00838         _v14 = _v13.position
00839         _x = _v14
00840         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00841         _v15 = _v13.orientation
00842         _x = _v15
00843         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00844         _x = val1
00845         buff.write(_struct_dB2f.pack(_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance))
00846         length = len(val1.moved_obstacles)
00847         buff.write(_struct_I.pack(length))
00848         for val2 in val1.moved_obstacles:
00849           _x = val2.reference_frame_id
00850           length = len(_x)
00851           if python3 or type(_x) == unicode:
00852             _x = _x.encode('utf-8')
00853             length = len(_x)
00854           buff.write(struct.pack('<I%ss'%length, length, _x))
00855           length = len(val2.potential_models)
00856           buff.write(_struct_I.pack(length))
00857           for val3 in val2.potential_models:
00858             buff.write(_struct_i.pack(val3.model_id))
00859             _v16 = val3.pose
00860             _v17 = _v16.header
00861             buff.write(_struct_I.pack(_v17.seq))
00862             _v18 = _v17.stamp
00863             _x = _v18
00864             buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00865             _x = _v17.frame_id
00866             length = len(_x)
00867             if python3 or type(_x) == unicode:
00868               _x = _x.encode('utf-8')
00869               length = len(_x)
00870             buff.write(struct.pack('<I%ss'%length, length, _x))
00871             _v19 = _v16.pose
00872             _v20 = _v19.position
00873             _x = _v20
00874             buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00875             _v21 = _v19.orientation
00876             _x = _v21
00877             buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00878             buff.write(_struct_f.pack(val3.confidence))
00879             _x = val3.detector_name
00880             length = len(_x)
00881             if python3 or type(_x) == unicode:
00882               _x = _x.encode('utf-8')
00883               length = len(_x)
00884             buff.write(struct.pack('<I%ss'%length, length, _x))
00885           _v22 = val2.cluster
00886           _v23 = _v22.header
00887           buff.write(_struct_I.pack(_v23.seq))
00888           _v24 = _v23.stamp
00889           _x = _v24
00890           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00891           _x = _v23.frame_id
00892           length = len(_x)
00893           if python3 or type(_x) == unicode:
00894             _x = _x.encode('utf-8')
00895             length = len(_x)
00896           buff.write(struct.pack('<I%ss'%length, length, _x))
00897           length = len(_v22.points)
00898           buff.write(_struct_I.pack(length))
00899           for val4 in _v22.points:
00900             _x = val4
00901             buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00902           length = len(_v22.channels)
00903           buff.write(_struct_I.pack(length))
00904           for val4 in _v22.channels:
00905             _x = val4.name
00906             length = len(_x)
00907             if python3 or type(_x) == unicode:
00908               _x = _x.encode('utf-8')
00909               length = len(_x)
00910             buff.write(struct.pack('<I%ss'%length, length, _x))
00911             length = len(val4.values)
00912             buff.write(_struct_I.pack(length))
00913             pattern = '<%sf'%length
00914             buff.write(struct.pack(pattern, *val4.values))
00915           _v25 = val2.region
00916           _v26 = _v25.cloud
00917           _v27 = _v26.header
00918           buff.write(_struct_I.pack(_v27.seq))
00919           _v28 = _v27.stamp
00920           _x = _v28
00921           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00922           _x = _v27.frame_id
00923           length = len(_x)
00924           if python3 or type(_x) == unicode:
00925             _x = _x.encode('utf-8')
00926             length = len(_x)
00927           buff.write(struct.pack('<I%ss'%length, length, _x))
00928           _x = _v26
00929           buff.write(_struct_2I.pack(_x.height, _x.width))
00930           length = len(_v26.fields)
00931           buff.write(_struct_I.pack(length))
00932           for val5 in _v26.fields:
00933             _x = val5.name
00934             length = len(_x)
00935             if python3 or type(_x) == unicode:
00936               _x = _x.encode('utf-8')
00937               length = len(_x)
00938             buff.write(struct.pack('<I%ss'%length, length, _x))
00939             _x = val5
00940             buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00941           _x = _v26
00942           buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
00943           _x = _v26.data
00944           length = len(_x)
00945           # - if encoded as a list instead, serialize as bytes instead of string
00946           if type(_x) in [list, tuple]:
00947             buff.write(struct.pack('<I%sB'%length, length, *_x))
00948           else:
00949             buff.write(struct.pack('<I%ss'%length, length, _x))
00950           buff.write(_struct_B.pack(_v26.is_dense))
00951           length = len(_v25.mask)
00952           buff.write(_struct_I.pack(length))
00953           pattern = '<%si'%length
00954           buff.write(struct.pack(pattern, *_v25.mask))
00955           _v29 = _v25.image
00956           _v30 = _v29.header
00957           buff.write(_struct_I.pack(_v30.seq))
00958           _v31 = _v30.stamp
00959           _x = _v31
00960           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00961           _x = _v30.frame_id
00962           length = len(_x)
00963           if python3 or type(_x) == unicode:
00964             _x = _x.encode('utf-8')
00965             length = len(_x)
00966           buff.write(struct.pack('<I%ss'%length, length, _x))
00967           _x = _v29
00968           buff.write(_struct_2I.pack(_x.height, _x.width))
00969           _x = _v29.encoding
00970           length = len(_x)
00971           if python3 or type(_x) == unicode:
00972             _x = _x.encode('utf-8')
00973             length = len(_x)
00974           buff.write(struct.pack('<I%ss'%length, length, _x))
00975           _x = _v29
00976           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
00977           _x = _v29.data
00978           length = len(_x)
00979           # - if encoded as a list instead, serialize as bytes instead of string
00980           if type(_x) in [list, tuple]:
00981             buff.write(struct.pack('<I%sB'%length, length, *_x))
00982           else:
00983             buff.write(struct.pack('<I%ss'%length, length, _x))
00984           _v32 = _v25.disparity_image
00985           _v33 = _v32.header
00986           buff.write(_struct_I.pack(_v33.seq))
00987           _v34 = _v33.stamp
00988           _x = _v34
00989           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00990           _x = _v33.frame_id
00991           length = len(_x)
00992           if python3 or type(_x) == unicode:
00993             _x = _x.encode('utf-8')
00994             length = len(_x)
00995           buff.write(struct.pack('<I%ss'%length, length, _x))
00996           _x = _v32
00997           buff.write(_struct_2I.pack(_x.height, _x.width))
00998           _x = _v32.encoding
00999           length = len(_x)
01000           if python3 or type(_x) == unicode:
01001             _x = _x.encode('utf-8')
01002             length = len(_x)
01003           buff.write(struct.pack('<I%ss'%length, length, _x))
01004           _x = _v32
01005           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
01006           _x = _v32.data
01007           length = len(_x)
01008           # - if encoded as a list instead, serialize as bytes instead of string
01009           if type(_x) in [list, tuple]:
01010             buff.write(struct.pack('<I%sB'%length, length, *_x))
01011           else:
01012             buff.write(struct.pack('<I%ss'%length, length, _x))
01013           _v35 = _v25.cam_info
01014           _v36 = _v35.header
01015           buff.write(_struct_I.pack(_v36.seq))
01016           _v37 = _v36.stamp
01017           _x = _v37
01018           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01019           _x = _v36.frame_id
01020           length = len(_x)
01021           if python3 or type(_x) == unicode:
01022             _x = _x.encode('utf-8')
01023             length = len(_x)
01024           buff.write(struct.pack('<I%ss'%length, length, _x))
01025           _x = _v35
01026           buff.write(_struct_2I.pack(_x.height, _x.width))
01027           _x = _v35.distortion_model
01028           length = len(_x)
01029           if python3 or type(_x) == unicode:
01030             _x = _x.encode('utf-8')
01031             length = len(_x)
01032           buff.write(struct.pack('<I%ss'%length, length, _x))
01033           length = len(_v35.D)
01034           buff.write(_struct_I.pack(length))
01035           pattern = '<%sd'%length
01036           buff.write(struct.pack(pattern, *_v35.D))
01037           buff.write(_struct_9d.pack(*_v35.K))
01038           buff.write(_struct_9d.pack(*_v35.R))
01039           buff.write(_struct_12d.pack(*_v35.P))
01040           _x = _v35
01041           buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
01042           _v38 = _v35.roi
01043           _x = _v38
01044           buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
01045           _v39 = _v25.roi_box_pose
01046           _v40 = _v39.header
01047           buff.write(_struct_I.pack(_v40.seq))
01048           _v41 = _v40.stamp
01049           _x = _v41
01050           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01051           _x = _v40.frame_id
01052           length = len(_x)
01053           if python3 or type(_x) == unicode:
01054             _x = _x.encode('utf-8')
01055             length = len(_x)
01056           buff.write(struct.pack('<I%ss'%length, length, _x))
01057           _v42 = _v39.pose
01058           _v43 = _v42.position
01059           _x = _v43
01060           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01061           _v44 = _v42.orientation
01062           _x = _v44
01063           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01064           _v45 = _v25.roi_box_dims
01065           _x = _v45
01066           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01067           _x = val2.collision_name
01068           length = len(_x)
01069           if python3 or type(_x) == unicode:
01070             _x = _x.encode('utf-8')
01071             length = len(_x)
01072           buff.write(struct.pack('<I%ss'%length, length, _x))
01073       length = len(self.movable_obstacles)
01074       buff.write(_struct_I.pack(length))
01075       for val1 in self.movable_obstacles:
01076         _x = val1.reference_frame_id
01077         length = len(_x)
01078         if python3 or type(_x) == unicode:
01079           _x = _x.encode('utf-8')
01080           length = len(_x)
01081         buff.write(struct.pack('<I%ss'%length, length, _x))
01082         length = len(val1.potential_models)
01083         buff.write(_struct_I.pack(length))
01084         for val2 in val1.potential_models:
01085           buff.write(_struct_i.pack(val2.model_id))
01086           _v46 = val2.pose
01087           _v47 = _v46.header
01088           buff.write(_struct_I.pack(_v47.seq))
01089           _v48 = _v47.stamp
01090           _x = _v48
01091           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01092           _x = _v47.frame_id
01093           length = len(_x)
01094           if python3 or type(_x) == unicode:
01095             _x = _x.encode('utf-8')
01096             length = len(_x)
01097           buff.write(struct.pack('<I%ss'%length, length, _x))
01098           _v49 = _v46.pose
01099           _v50 = _v49.position
01100           _x = _v50
01101           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01102           _v51 = _v49.orientation
01103           _x = _v51
01104           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01105           buff.write(_struct_f.pack(val2.confidence))
01106           _x = val2.detector_name
01107           length = len(_x)
01108           if python3 or type(_x) == unicode:
01109             _x = _x.encode('utf-8')
01110             length = len(_x)
01111           buff.write(struct.pack('<I%ss'%length, length, _x))
01112         _v52 = val1.cluster
01113         _v53 = _v52.header
01114         buff.write(_struct_I.pack(_v53.seq))
01115         _v54 = _v53.stamp
01116         _x = _v54
01117         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01118         _x = _v53.frame_id
01119         length = len(_x)
01120         if python3 or type(_x) == unicode:
01121           _x = _x.encode('utf-8')
01122           length = len(_x)
01123         buff.write(struct.pack('<I%ss'%length, length, _x))
01124         length = len(_v52.points)
01125         buff.write(_struct_I.pack(length))
01126         for val3 in _v52.points:
01127           _x = val3
01128           buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
01129         length = len(_v52.channels)
01130         buff.write(_struct_I.pack(length))
01131         for val3 in _v52.channels:
01132           _x = val3.name
01133           length = len(_x)
01134           if python3 or type(_x) == unicode:
01135             _x = _x.encode('utf-8')
01136             length = len(_x)
01137           buff.write(struct.pack('<I%ss'%length, length, _x))
01138           length = len(val3.values)
01139           buff.write(_struct_I.pack(length))
01140           pattern = '<%sf'%length
01141           buff.write(struct.pack(pattern, *val3.values))
01142         _v55 = val1.region
01143         _v56 = _v55.cloud
01144         _v57 = _v56.header
01145         buff.write(_struct_I.pack(_v57.seq))
01146         _v58 = _v57.stamp
01147         _x = _v58
01148         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01149         _x = _v57.frame_id
01150         length = len(_x)
01151         if python3 or type(_x) == unicode:
01152           _x = _x.encode('utf-8')
01153           length = len(_x)
01154         buff.write(struct.pack('<I%ss'%length, length, _x))
01155         _x = _v56
01156         buff.write(_struct_2I.pack(_x.height, _x.width))
01157         length = len(_v56.fields)
01158         buff.write(_struct_I.pack(length))
01159         for val4 in _v56.fields:
01160           _x = val4.name
01161           length = len(_x)
01162           if python3 or type(_x) == unicode:
01163             _x = _x.encode('utf-8')
01164             length = len(_x)
01165           buff.write(struct.pack('<I%ss'%length, length, _x))
01166           _x = val4
01167           buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
01168         _x = _v56
01169         buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
01170         _x = _v56.data
01171         length = len(_x)
01172         # - if encoded as a list instead, serialize as bytes instead of string
01173         if type(_x) in [list, tuple]:
01174           buff.write(struct.pack('<I%sB'%length, length, *_x))
01175         else:
01176           buff.write(struct.pack('<I%ss'%length, length, _x))
01177         buff.write(_struct_B.pack(_v56.is_dense))
01178         length = len(_v55.mask)
01179         buff.write(_struct_I.pack(length))
01180         pattern = '<%si'%length
01181         buff.write(struct.pack(pattern, *_v55.mask))
01182         _v59 = _v55.image
01183         _v60 = _v59.header
01184         buff.write(_struct_I.pack(_v60.seq))
01185         _v61 = _v60.stamp
01186         _x = _v61
01187         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01188         _x = _v60.frame_id
01189         length = len(_x)
01190         if python3 or type(_x) == unicode:
01191           _x = _x.encode('utf-8')
01192           length = len(_x)
01193         buff.write(struct.pack('<I%ss'%length, length, _x))
01194         _x = _v59
01195         buff.write(_struct_2I.pack(_x.height, _x.width))
01196         _x = _v59.encoding
01197         length = len(_x)
01198         if python3 or type(_x) == unicode:
01199           _x = _x.encode('utf-8')
01200           length = len(_x)
01201         buff.write(struct.pack('<I%ss'%length, length, _x))
01202         _x = _v59
01203         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
01204         _x = _v59.data
01205         length = len(_x)
01206         # - if encoded as a list instead, serialize as bytes instead of string
01207         if type(_x) in [list, tuple]:
01208           buff.write(struct.pack('<I%sB'%length, length, *_x))
01209         else:
01210           buff.write(struct.pack('<I%ss'%length, length, _x))
01211         _v62 = _v55.disparity_image
01212         _v63 = _v62.header
01213         buff.write(_struct_I.pack(_v63.seq))
01214         _v64 = _v63.stamp
01215         _x = _v64
01216         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01217         _x = _v63.frame_id
01218         length = len(_x)
01219         if python3 or type(_x) == unicode:
01220           _x = _x.encode('utf-8')
01221           length = len(_x)
01222         buff.write(struct.pack('<I%ss'%length, length, _x))
01223         _x = _v62
01224         buff.write(_struct_2I.pack(_x.height, _x.width))
01225         _x = _v62.encoding
01226         length = len(_x)
01227         if python3 or type(_x) == unicode:
01228           _x = _x.encode('utf-8')
01229           length = len(_x)
01230         buff.write(struct.pack('<I%ss'%length, length, _x))
01231         _x = _v62
01232         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
01233         _x = _v62.data
01234         length = len(_x)
01235         # - if encoded as a list instead, serialize as bytes instead of string
01236         if type(_x) in [list, tuple]:
01237           buff.write(struct.pack('<I%sB'%length, length, *_x))
01238         else:
01239           buff.write(struct.pack('<I%ss'%length, length, _x))
01240         _v65 = _v55.cam_info
01241         _v66 = _v65.header
01242         buff.write(_struct_I.pack(_v66.seq))
01243         _v67 = _v66.stamp
01244         _x = _v67
01245         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01246         _x = _v66.frame_id
01247         length = len(_x)
01248         if python3 or type(_x) == unicode:
01249           _x = _x.encode('utf-8')
01250           length = len(_x)
01251         buff.write(struct.pack('<I%ss'%length, length, _x))
01252         _x = _v65
01253         buff.write(_struct_2I.pack(_x.height, _x.width))
01254         _x = _v65.distortion_model
01255         length = len(_x)
01256         if python3 or type(_x) == unicode:
01257           _x = _x.encode('utf-8')
01258           length = len(_x)
01259         buff.write(struct.pack('<I%ss'%length, length, _x))
01260         length = len(_v65.D)
01261         buff.write(_struct_I.pack(length))
01262         pattern = '<%sd'%length
01263         buff.write(struct.pack(pattern, *_v65.D))
01264         buff.write(_struct_9d.pack(*_v65.K))
01265         buff.write(_struct_9d.pack(*_v65.R))
01266         buff.write(_struct_12d.pack(*_v65.P))
01267         _x = _v65
01268         buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
01269         _v68 = _v65.roi
01270         _x = _v68
01271         buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
01272         _v69 = _v55.roi_box_pose
01273         _v70 = _v69.header
01274         buff.write(_struct_I.pack(_v70.seq))
01275         _v71 = _v70.stamp
01276         _x = _v71
01277         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01278         _x = _v70.frame_id
01279         length = len(_x)
01280         if python3 or type(_x) == unicode:
01281           _x = _x.encode('utf-8')
01282           length = len(_x)
01283         buff.write(struct.pack('<I%ss'%length, length, _x))
01284         _v72 = _v69.pose
01285         _v73 = _v72.position
01286         _x = _v73
01287         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01288         _v74 = _v72.orientation
01289         _x = _v74
01290         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01291         _v75 = _v55.roi_box_dims
01292         _x = _v75
01293         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01294         _x = val1.collision_name
01295         length = len(_x)
01296         if python3 or type(_x) == unicode:
01297           _x = _x.encode('utf-8')
01298           length = len(_x)
01299         buff.write(struct.pack('<I%ss'%length, length, _x))
01300     except struct.error as se: self._check_types(se)
01301     except TypeError as te: self._check_types(te)
01302 
01303   def deserialize(self, str):
01304     """
01305     unpack serialized message in str into this message instance
01306     :param str: byte array of serialized message, ``str``
01307     """
01308     try:
01309       if self.target is None:
01310         self.target = object_manipulation_msgs.msg.GraspableObject()
01311       if self.grasps_to_evaluate is None:
01312         self.grasps_to_evaluate = None
01313       if self.movable_obstacles is None:
01314         self.movable_obstacles = None
01315       end = 0
01316       start = end
01317       end += 4
01318       (length,) = _struct_I.unpack(str[start:end])
01319       start = end
01320       end += length
01321       if python3:
01322         self.arm_name = str[start:end].decode('utf-8')
01323       else:
01324         self.arm_name = str[start:end]
01325       start = end
01326       end += 4
01327       (length,) = _struct_I.unpack(str[start:end])
01328       start = end
01329       end += length
01330       if python3:
01331         self.target.reference_frame_id = str[start:end].decode('utf-8')
01332       else:
01333         self.target.reference_frame_id = str[start:end]
01334       start = end
01335       end += 4
01336       (length,) = _struct_I.unpack(str[start:end])
01337       self.target.potential_models = []
01338       for i in range(0, length):
01339         val1 = household_objects_database_msgs.msg.DatabaseModelPose()
01340         start = end
01341         end += 4
01342         (val1.model_id,) = _struct_i.unpack(str[start:end])
01343         _v76 = val1.pose
01344         _v77 = _v76.header
01345         start = end
01346         end += 4
01347         (_v77.seq,) = _struct_I.unpack(str[start:end])
01348         _v78 = _v77.stamp
01349         _x = _v78
01350         start = end
01351         end += 8
01352         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01353         start = end
01354         end += 4
01355         (length,) = _struct_I.unpack(str[start:end])
01356         start = end
01357         end += length
01358         if python3:
01359           _v77.frame_id = str[start:end].decode('utf-8')
01360         else:
01361           _v77.frame_id = str[start:end]
01362         _v79 = _v76.pose
01363         _v80 = _v79.position
01364         _x = _v80
01365         start = end
01366         end += 24
01367         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01368         _v81 = _v79.orientation
01369         _x = _v81
01370         start = end
01371         end += 32
01372         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01373         start = end
01374         end += 4
01375         (val1.confidence,) = _struct_f.unpack(str[start:end])
01376         start = end
01377         end += 4
01378         (length,) = _struct_I.unpack(str[start:end])
01379         start = end
01380         end += length
01381         if python3:
01382           val1.detector_name = str[start:end].decode('utf-8')
01383         else:
01384           val1.detector_name = str[start:end]
01385         self.target.potential_models.append(val1)
01386       _x = self
01387       start = end
01388       end += 12
01389       (_x.target.cluster.header.seq, _x.target.cluster.header.stamp.secs, _x.target.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01390       start = end
01391       end += 4
01392       (length,) = _struct_I.unpack(str[start:end])
01393       start = end
01394       end += length
01395       if python3:
01396         self.target.cluster.header.frame_id = str[start:end].decode('utf-8')
01397       else:
01398         self.target.cluster.header.frame_id = str[start:end]
01399       start = end
01400       end += 4
01401       (length,) = _struct_I.unpack(str[start:end])
01402       self.target.cluster.points = []
01403       for i in range(0, length):
01404         val1 = geometry_msgs.msg.Point32()
01405         _x = val1
01406         start = end
01407         end += 12
01408         (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01409         self.target.cluster.points.append(val1)
01410       start = end
01411       end += 4
01412       (length,) = _struct_I.unpack(str[start:end])
01413       self.target.cluster.channels = []
01414       for i in range(0, length):
01415         val1 = sensor_msgs.msg.ChannelFloat32()
01416         start = end
01417         end += 4
01418         (length,) = _struct_I.unpack(str[start:end])
01419         start = end
01420         end += length
01421         if python3:
01422           val1.name = str[start:end].decode('utf-8')
01423         else:
01424           val1.name = str[start:end]
01425         start = end
01426         end += 4
01427         (length,) = _struct_I.unpack(str[start:end])
01428         pattern = '<%sf'%length
01429         start = end
01430         end += struct.calcsize(pattern)
01431         val1.values = struct.unpack(pattern, str[start:end])
01432         self.target.cluster.channels.append(val1)
01433       _x = self
01434       start = end
01435       end += 12
01436       (_x.target.region.cloud.header.seq, _x.target.region.cloud.header.stamp.secs, _x.target.region.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01437       start = end
01438       end += 4
01439       (length,) = _struct_I.unpack(str[start:end])
01440       start = end
01441       end += length
01442       if python3:
01443         self.target.region.cloud.header.frame_id = str[start:end].decode('utf-8')
01444       else:
01445         self.target.region.cloud.header.frame_id = str[start:end]
01446       _x = self
01447       start = end
01448       end += 8
01449       (_x.target.region.cloud.height, _x.target.region.cloud.width,) = _struct_2I.unpack(str[start:end])
01450       start = end
01451       end += 4
01452       (length,) = _struct_I.unpack(str[start:end])
01453       self.target.region.cloud.fields = []
01454       for i in range(0, length):
01455         val1 = sensor_msgs.msg.PointField()
01456         start = end
01457         end += 4
01458         (length,) = _struct_I.unpack(str[start:end])
01459         start = end
01460         end += length
01461         if python3:
01462           val1.name = str[start:end].decode('utf-8')
01463         else:
01464           val1.name = str[start:end]
01465         _x = val1
01466         start = end
01467         end += 9
01468         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01469         self.target.region.cloud.fields.append(val1)
01470       _x = self
01471       start = end
01472       end += 9
01473       (_x.target.region.cloud.is_bigendian, _x.target.region.cloud.point_step, _x.target.region.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
01474       self.target.region.cloud.is_bigendian = bool(self.target.region.cloud.is_bigendian)
01475       start = end
01476       end += 4
01477       (length,) = _struct_I.unpack(str[start:end])
01478       start = end
01479       end += length
01480       if python3:
01481         self.target.region.cloud.data = str[start:end].decode('utf-8')
01482       else:
01483         self.target.region.cloud.data = str[start:end]
01484       start = end
01485       end += 1
01486       (self.target.region.cloud.is_dense,) = _struct_B.unpack(str[start:end])
01487       self.target.region.cloud.is_dense = bool(self.target.region.cloud.is_dense)
01488       start = end
01489       end += 4
01490       (length,) = _struct_I.unpack(str[start:end])
01491       pattern = '<%si'%length
01492       start = end
01493       end += struct.calcsize(pattern)
01494       self.target.region.mask = struct.unpack(pattern, str[start:end])
01495       _x = self
01496       start = end
01497       end += 12
01498       (_x.target.region.image.header.seq, _x.target.region.image.header.stamp.secs, _x.target.region.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01499       start = end
01500       end += 4
01501       (length,) = _struct_I.unpack(str[start:end])
01502       start = end
01503       end += length
01504       if python3:
01505         self.target.region.image.header.frame_id = str[start:end].decode('utf-8')
01506       else:
01507         self.target.region.image.header.frame_id = str[start:end]
01508       _x = self
01509       start = end
01510       end += 8
01511       (_x.target.region.image.height, _x.target.region.image.width,) = _struct_2I.unpack(str[start:end])
01512       start = end
01513       end += 4
01514       (length,) = _struct_I.unpack(str[start:end])
01515       start = end
01516       end += length
01517       if python3:
01518         self.target.region.image.encoding = str[start:end].decode('utf-8')
01519       else:
01520         self.target.region.image.encoding = str[start:end]
01521       _x = self
01522       start = end
01523       end += 5
01524       (_x.target.region.image.is_bigendian, _x.target.region.image.step,) = _struct_BI.unpack(str[start:end])
01525       start = end
01526       end += 4
01527       (length,) = _struct_I.unpack(str[start:end])
01528       start = end
01529       end += length
01530       if python3:
01531         self.target.region.image.data = str[start:end].decode('utf-8')
01532       else:
01533         self.target.region.image.data = str[start:end]
01534       _x = self
01535       start = end
01536       end += 12
01537       (_x.target.region.disparity_image.header.seq, _x.target.region.disparity_image.header.stamp.secs, _x.target.region.disparity_image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01538       start = end
01539       end += 4
01540       (length,) = _struct_I.unpack(str[start:end])
01541       start = end
01542       end += length
01543       if python3:
01544         self.target.region.disparity_image.header.frame_id = str[start:end].decode('utf-8')
01545       else:
01546         self.target.region.disparity_image.header.frame_id = str[start:end]
01547       _x = self
01548       start = end
01549       end += 8
01550       (_x.target.region.disparity_image.height, _x.target.region.disparity_image.width,) = _struct_2I.unpack(str[start:end])
01551       start = end
01552       end += 4
01553       (length,) = _struct_I.unpack(str[start:end])
01554       start = end
01555       end += length
01556       if python3:
01557         self.target.region.disparity_image.encoding = str[start:end].decode('utf-8')
01558       else:
01559         self.target.region.disparity_image.encoding = str[start:end]
01560       _x = self
01561       start = end
01562       end += 5
01563       (_x.target.region.disparity_image.is_bigendian, _x.target.region.disparity_image.step,) = _struct_BI.unpack(str[start:end])
01564       start = end
01565       end += 4
01566       (length,) = _struct_I.unpack(str[start:end])
01567       start = end
01568       end += length
01569       if python3:
01570         self.target.region.disparity_image.data = str[start:end].decode('utf-8')
01571       else:
01572         self.target.region.disparity_image.data = str[start:end]
01573       _x = self
01574       start = end
01575       end += 12
01576       (_x.target.region.cam_info.header.seq, _x.target.region.cam_info.header.stamp.secs, _x.target.region.cam_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01577       start = end
01578       end += 4
01579       (length,) = _struct_I.unpack(str[start:end])
01580       start = end
01581       end += length
01582       if python3:
01583         self.target.region.cam_info.header.frame_id = str[start:end].decode('utf-8')
01584       else:
01585         self.target.region.cam_info.header.frame_id = str[start:end]
01586       _x = self
01587       start = end
01588       end += 8
01589       (_x.target.region.cam_info.height, _x.target.region.cam_info.width,) = _struct_2I.unpack(str[start:end])
01590       start = end
01591       end += 4
01592       (length,) = _struct_I.unpack(str[start:end])
01593       start = end
01594       end += length
01595       if python3:
01596         self.target.region.cam_info.distortion_model = str[start:end].decode('utf-8')
01597       else:
01598         self.target.region.cam_info.distortion_model = str[start:end]
01599       start = end
01600       end += 4
01601       (length,) = _struct_I.unpack(str[start:end])
01602       pattern = '<%sd'%length
01603       start = end
01604       end += struct.calcsize(pattern)
01605       self.target.region.cam_info.D = struct.unpack(pattern, str[start:end])
01606       start = end
01607       end += 72
01608       self.target.region.cam_info.K = _struct_9d.unpack(str[start:end])
01609       start = end
01610       end += 72
01611       self.target.region.cam_info.R = _struct_9d.unpack(str[start:end])
01612       start = end
01613       end += 96
01614       self.target.region.cam_info.P = _struct_12d.unpack(str[start:end])
01615       _x = self
01616       start = end
01617       end += 37
01618       (_x.target.region.cam_info.binning_x, _x.target.region.cam_info.binning_y, _x.target.region.cam_info.roi.x_offset, _x.target.region.cam_info.roi.y_offset, _x.target.region.cam_info.roi.height, _x.target.region.cam_info.roi.width, _x.target.region.cam_info.roi.do_rectify, _x.target.region.roi_box_pose.header.seq, _x.target.region.roi_box_pose.header.stamp.secs, _x.target.region.roi_box_pose.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
01619       self.target.region.cam_info.roi.do_rectify = bool(self.target.region.cam_info.roi.do_rectify)
01620       start = end
01621       end += 4
01622       (length,) = _struct_I.unpack(str[start:end])
01623       start = end
01624       end += length
01625       if python3:
01626         self.target.region.roi_box_pose.header.frame_id = str[start:end].decode('utf-8')
01627       else:
01628         self.target.region.roi_box_pose.header.frame_id = str[start:end]
01629       _x = self
01630       start = end
01631       end += 80
01632       (_x.target.region.roi_box_pose.pose.position.x, _x.target.region.roi_box_pose.pose.position.y, _x.target.region.roi_box_pose.pose.position.z, _x.target.region.roi_box_pose.pose.orientation.x, _x.target.region.roi_box_pose.pose.orientation.y, _x.target.region.roi_box_pose.pose.orientation.z, _x.target.region.roi_box_pose.pose.orientation.w, _x.target.region.roi_box_dims.x, _x.target.region.roi_box_dims.y, _x.target.region.roi_box_dims.z,) = _struct_10d.unpack(str[start:end])
01633       start = end
01634       end += 4
01635       (length,) = _struct_I.unpack(str[start:end])
01636       start = end
01637       end += length
01638       if python3:
01639         self.target.collision_name = str[start:end].decode('utf-8')
01640       else:
01641         self.target.collision_name = str[start:end]
01642       start = end
01643       end += 4
01644       (length,) = _struct_I.unpack(str[start:end])
01645       start = end
01646       end += length
01647       if python3:
01648         self.collision_object_name = str[start:end].decode('utf-8')
01649       else:
01650         self.collision_object_name = str[start:end]
01651       start = end
01652       end += 4
01653       (length,) = _struct_I.unpack(str[start:end])
01654       start = end
01655       end += length
01656       if python3:
01657         self.collision_support_surface_name = str[start:end].decode('utf-8')
01658       else:
01659         self.collision_support_surface_name = str[start:end]
01660       start = end
01661       end += 4
01662       (length,) = _struct_I.unpack(str[start:end])
01663       self.grasps_to_evaluate = []
01664       for i in range(0, length):
01665         val1 = object_manipulation_msgs.msg.Grasp()
01666         _v82 = val1.pre_grasp_posture
01667         _v83 = _v82.header
01668         start = end
01669         end += 4
01670         (_v83.seq,) = _struct_I.unpack(str[start:end])
01671         _v84 = _v83.stamp
01672         _x = _v84
01673         start = end
01674         end += 8
01675         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01676         start = end
01677         end += 4
01678         (length,) = _struct_I.unpack(str[start:end])
01679         start = end
01680         end += length
01681         if python3:
01682           _v83.frame_id = str[start:end].decode('utf-8')
01683         else:
01684           _v83.frame_id = str[start:end]
01685         start = end
01686         end += 4
01687         (length,) = _struct_I.unpack(str[start:end])
01688         _v82.name = []
01689         for i in range(0, length):
01690           start = end
01691           end += 4
01692           (length,) = _struct_I.unpack(str[start:end])
01693           start = end
01694           end += length
01695           if python3:
01696             val3 = str[start:end].decode('utf-8')
01697           else:
01698             val3 = str[start:end]
01699           _v82.name.append(val3)
01700         start = end
01701         end += 4
01702         (length,) = _struct_I.unpack(str[start:end])
01703         pattern = '<%sd'%length
01704         start = end
01705         end += struct.calcsize(pattern)
01706         _v82.position = struct.unpack(pattern, str[start:end])
01707         start = end
01708         end += 4
01709         (length,) = _struct_I.unpack(str[start:end])
01710         pattern = '<%sd'%length
01711         start = end
01712         end += struct.calcsize(pattern)
01713         _v82.velocity = struct.unpack(pattern, str[start:end])
01714         start = end
01715         end += 4
01716         (length,) = _struct_I.unpack(str[start:end])
01717         pattern = '<%sd'%length
01718         start = end
01719         end += struct.calcsize(pattern)
01720         _v82.effort = struct.unpack(pattern, str[start:end])
01721         _v85 = val1.grasp_posture
01722         _v86 = _v85.header
01723         start = end
01724         end += 4
01725         (_v86.seq,) = _struct_I.unpack(str[start:end])
01726         _v87 = _v86.stamp
01727         _x = _v87
01728         start = end
01729         end += 8
01730         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01731         start = end
01732         end += 4
01733         (length,) = _struct_I.unpack(str[start:end])
01734         start = end
01735         end += length
01736         if python3:
01737           _v86.frame_id = str[start:end].decode('utf-8')
01738         else:
01739           _v86.frame_id = str[start:end]
01740         start = end
01741         end += 4
01742         (length,) = _struct_I.unpack(str[start:end])
01743         _v85.name = []
01744         for i in range(0, length):
01745           start = end
01746           end += 4
01747           (length,) = _struct_I.unpack(str[start:end])
01748           start = end
01749           end += length
01750           if python3:
01751             val3 = str[start:end].decode('utf-8')
01752           else:
01753             val3 = str[start:end]
01754           _v85.name.append(val3)
01755         start = end
01756         end += 4
01757         (length,) = _struct_I.unpack(str[start:end])
01758         pattern = '<%sd'%length
01759         start = end
01760         end += struct.calcsize(pattern)
01761         _v85.position = struct.unpack(pattern, str[start:end])
01762         start = end
01763         end += 4
01764         (length,) = _struct_I.unpack(str[start:end])
01765         pattern = '<%sd'%length
01766         start = end
01767         end += struct.calcsize(pattern)
01768         _v85.velocity = struct.unpack(pattern, str[start:end])
01769         start = end
01770         end += 4
01771         (length,) = _struct_I.unpack(str[start:end])
01772         pattern = '<%sd'%length
01773         start = end
01774         end += struct.calcsize(pattern)
01775         _v85.effort = struct.unpack(pattern, str[start:end])
01776         _v88 = val1.grasp_pose
01777         _v89 = _v88.position
01778         _x = _v89
01779         start = end
01780         end += 24
01781         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01782         _v90 = _v88.orientation
01783         _x = _v90
01784         start = end
01785         end += 32
01786         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01787         _x = val1
01788         start = end
01789         end += 17
01790         (_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance,) = _struct_dB2f.unpack(str[start:end])
01791         val1.cluster_rep = bool(val1.cluster_rep)
01792         start = end
01793         end += 4
01794         (length,) = _struct_I.unpack(str[start:end])
01795         val1.moved_obstacles = []
01796         for i in range(0, length):
01797           val2 = object_manipulation_msgs.msg.GraspableObject()
01798           start = end
01799           end += 4
01800           (length,) = _struct_I.unpack(str[start:end])
01801           start = end
01802           end += length
01803           if python3:
01804             val2.reference_frame_id = str[start:end].decode('utf-8')
01805           else:
01806             val2.reference_frame_id = str[start:end]
01807           start = end
01808           end += 4
01809           (length,) = _struct_I.unpack(str[start:end])
01810           val2.potential_models = []
01811           for i in range(0, length):
01812             val3 = household_objects_database_msgs.msg.DatabaseModelPose()
01813             start = end
01814             end += 4
01815             (val3.model_id,) = _struct_i.unpack(str[start:end])
01816             _v91 = val3.pose
01817             _v92 = _v91.header
01818             start = end
01819             end += 4
01820             (_v92.seq,) = _struct_I.unpack(str[start:end])
01821             _v93 = _v92.stamp
01822             _x = _v93
01823             start = end
01824             end += 8
01825             (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01826             start = end
01827             end += 4
01828             (length,) = _struct_I.unpack(str[start:end])
01829             start = end
01830             end += length
01831             if python3:
01832               _v92.frame_id = str[start:end].decode('utf-8')
01833             else:
01834               _v92.frame_id = str[start:end]
01835             _v94 = _v91.pose
01836             _v95 = _v94.position
01837             _x = _v95
01838             start = end
01839             end += 24
01840             (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01841             _v96 = _v94.orientation
01842             _x = _v96
01843             start = end
01844             end += 32
01845             (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01846             start = end
01847             end += 4
01848             (val3.confidence,) = _struct_f.unpack(str[start:end])
01849             start = end
01850             end += 4
01851             (length,) = _struct_I.unpack(str[start:end])
01852             start = end
01853             end += length
01854             if python3:
01855               val3.detector_name = str[start:end].decode('utf-8')
01856             else:
01857               val3.detector_name = str[start:end]
01858             val2.potential_models.append(val3)
01859           _v97 = val2.cluster
01860           _v98 = _v97.header
01861           start = end
01862           end += 4
01863           (_v98.seq,) = _struct_I.unpack(str[start:end])
01864           _v99 = _v98.stamp
01865           _x = _v99
01866           start = end
01867           end += 8
01868           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01869           start = end
01870           end += 4
01871           (length,) = _struct_I.unpack(str[start:end])
01872           start = end
01873           end += length
01874           if python3:
01875             _v98.frame_id = str[start:end].decode('utf-8')
01876           else:
01877             _v98.frame_id = str[start:end]
01878           start = end
01879           end += 4
01880           (length,) = _struct_I.unpack(str[start:end])
01881           _v97.points = []
01882           for i in range(0, length):
01883             val4 = geometry_msgs.msg.Point32()
01884             _x = val4
01885             start = end
01886             end += 12
01887             (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01888             _v97.points.append(val4)
01889           start = end
01890           end += 4
01891           (length,) = _struct_I.unpack(str[start:end])
01892           _v97.channels = []
01893           for i in range(0, length):
01894             val4 = sensor_msgs.msg.ChannelFloat32()
01895             start = end
01896             end += 4
01897             (length,) = _struct_I.unpack(str[start:end])
01898             start = end
01899             end += length
01900             if python3:
01901               val4.name = str[start:end].decode('utf-8')
01902             else:
01903               val4.name = str[start:end]
01904             start = end
01905             end += 4
01906             (length,) = _struct_I.unpack(str[start:end])
01907             pattern = '<%sf'%length
01908             start = end
01909             end += struct.calcsize(pattern)
01910             val4.values = struct.unpack(pattern, str[start:end])
01911             _v97.channels.append(val4)
01912           _v100 = val2.region
01913           _v101 = _v100.cloud
01914           _v102 = _v101.header
01915           start = end
01916           end += 4
01917           (_v102.seq,) = _struct_I.unpack(str[start:end])
01918           _v103 = _v102.stamp
01919           _x = _v103
01920           start = end
01921           end += 8
01922           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01923           start = end
01924           end += 4
01925           (length,) = _struct_I.unpack(str[start:end])
01926           start = end
01927           end += length
01928           if python3:
01929             _v102.frame_id = str[start:end].decode('utf-8')
01930           else:
01931             _v102.frame_id = str[start:end]
01932           _x = _v101
01933           start = end
01934           end += 8
01935           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01936           start = end
01937           end += 4
01938           (length,) = _struct_I.unpack(str[start:end])
01939           _v101.fields = []
01940           for i in range(0, length):
01941             val5 = sensor_msgs.msg.PointField()
01942             start = end
01943             end += 4
01944             (length,) = _struct_I.unpack(str[start:end])
01945             start = end
01946             end += length
01947             if python3:
01948               val5.name = str[start:end].decode('utf-8')
01949             else:
01950               val5.name = str[start:end]
01951             _x = val5
01952             start = end
01953             end += 9
01954             (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01955             _v101.fields.append(val5)
01956           _x = _v101
01957           start = end
01958           end += 9
01959           (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
01960           _v101.is_bigendian = bool(_v101.is_bigendian)
01961           start = end
01962           end += 4
01963           (length,) = _struct_I.unpack(str[start:end])
01964           start = end
01965           end += length
01966           if python3:
01967             _v101.data = str[start:end].decode('utf-8')
01968           else:
01969             _v101.data = str[start:end]
01970           start = end
01971           end += 1
01972           (_v101.is_dense,) = _struct_B.unpack(str[start:end])
01973           _v101.is_dense = bool(_v101.is_dense)
01974           start = end
01975           end += 4
01976           (length,) = _struct_I.unpack(str[start:end])
01977           pattern = '<%si'%length
01978           start = end
01979           end += struct.calcsize(pattern)
01980           _v100.mask = struct.unpack(pattern, str[start:end])
01981           _v104 = _v100.image
01982           _v105 = _v104.header
01983           start = end
01984           end += 4
01985           (_v105.seq,) = _struct_I.unpack(str[start:end])
01986           _v106 = _v105.stamp
01987           _x = _v106
01988           start = end
01989           end += 8
01990           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01991           start = end
01992           end += 4
01993           (length,) = _struct_I.unpack(str[start:end])
01994           start = end
01995           end += length
01996           if python3:
01997             _v105.frame_id = str[start:end].decode('utf-8')
01998           else:
01999             _v105.frame_id = str[start:end]
02000           _x = _v104
02001           start = end
02002           end += 8
02003           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02004           start = end
02005           end += 4
02006           (length,) = _struct_I.unpack(str[start:end])
02007           start = end
02008           end += length
02009           if python3:
02010             _v104.encoding = str[start:end].decode('utf-8')
02011           else:
02012             _v104.encoding = str[start:end]
02013           _x = _v104
02014           start = end
02015           end += 5
02016           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
02017           start = end
02018           end += 4
02019           (length,) = _struct_I.unpack(str[start:end])
02020           start = end
02021           end += length
02022           if python3:
02023             _v104.data = str[start:end].decode('utf-8')
02024           else:
02025             _v104.data = str[start:end]
02026           _v107 = _v100.disparity_image
02027           _v108 = _v107.header
02028           start = end
02029           end += 4
02030           (_v108.seq,) = _struct_I.unpack(str[start:end])
02031           _v109 = _v108.stamp
02032           _x = _v109
02033           start = end
02034           end += 8
02035           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02036           start = end
02037           end += 4
02038           (length,) = _struct_I.unpack(str[start:end])
02039           start = end
02040           end += length
02041           if python3:
02042             _v108.frame_id = str[start:end].decode('utf-8')
02043           else:
02044             _v108.frame_id = str[start:end]
02045           _x = _v107
02046           start = end
02047           end += 8
02048           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02049           start = end
02050           end += 4
02051           (length,) = _struct_I.unpack(str[start:end])
02052           start = end
02053           end += length
02054           if python3:
02055             _v107.encoding = str[start:end].decode('utf-8')
02056           else:
02057             _v107.encoding = str[start:end]
02058           _x = _v107
02059           start = end
02060           end += 5
02061           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
02062           start = end
02063           end += 4
02064           (length,) = _struct_I.unpack(str[start:end])
02065           start = end
02066           end += length
02067           if python3:
02068             _v107.data = str[start:end].decode('utf-8')
02069           else:
02070             _v107.data = str[start:end]
02071           _v110 = _v100.cam_info
02072           _v111 = _v110.header
02073           start = end
02074           end += 4
02075           (_v111.seq,) = _struct_I.unpack(str[start:end])
02076           _v112 = _v111.stamp
02077           _x = _v112
02078           start = end
02079           end += 8
02080           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02081           start = end
02082           end += 4
02083           (length,) = _struct_I.unpack(str[start:end])
02084           start = end
02085           end += length
02086           if python3:
02087             _v111.frame_id = str[start:end].decode('utf-8')
02088           else:
02089             _v111.frame_id = str[start:end]
02090           _x = _v110
02091           start = end
02092           end += 8
02093           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02094           start = end
02095           end += 4
02096           (length,) = _struct_I.unpack(str[start:end])
02097           start = end
02098           end += length
02099           if python3:
02100             _v110.distortion_model = str[start:end].decode('utf-8')
02101           else:
02102             _v110.distortion_model = str[start:end]
02103           start = end
02104           end += 4
02105           (length,) = _struct_I.unpack(str[start:end])
02106           pattern = '<%sd'%length
02107           start = end
02108           end += struct.calcsize(pattern)
02109           _v110.D = struct.unpack(pattern, str[start:end])
02110           start = end
02111           end += 72
02112           _v110.K = _struct_9d.unpack(str[start:end])
02113           start = end
02114           end += 72
02115           _v110.R = _struct_9d.unpack(str[start:end])
02116           start = end
02117           end += 96
02118           _v110.P = _struct_12d.unpack(str[start:end])
02119           _x = _v110
02120           start = end
02121           end += 8
02122           (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
02123           _v113 = _v110.roi
02124           _x = _v113
02125           start = end
02126           end += 17
02127           (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
02128           _v113.do_rectify = bool(_v113.do_rectify)
02129           _v114 = _v100.roi_box_pose
02130           _v115 = _v114.header
02131           start = end
02132           end += 4
02133           (_v115.seq,) = _struct_I.unpack(str[start:end])
02134           _v116 = _v115.stamp
02135           _x = _v116
02136           start = end
02137           end += 8
02138           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02139           start = end
02140           end += 4
02141           (length,) = _struct_I.unpack(str[start:end])
02142           start = end
02143           end += length
02144           if python3:
02145             _v115.frame_id = str[start:end].decode('utf-8')
02146           else:
02147             _v115.frame_id = str[start:end]
02148           _v117 = _v114.pose
02149           _v118 = _v117.position
02150           _x = _v118
02151           start = end
02152           end += 24
02153           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02154           _v119 = _v117.orientation
02155           _x = _v119
02156           start = end
02157           end += 32
02158           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02159           _v120 = _v100.roi_box_dims
02160           _x = _v120
02161           start = end
02162           end += 24
02163           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02164           start = end
02165           end += 4
02166           (length,) = _struct_I.unpack(str[start:end])
02167           start = end
02168           end += length
02169           if python3:
02170             val2.collision_name = str[start:end].decode('utf-8')
02171           else:
02172             val2.collision_name = str[start:end]
02173           val1.moved_obstacles.append(val2)
02174         self.grasps_to_evaluate.append(val1)
02175       start = end
02176       end += 4
02177       (length,) = _struct_I.unpack(str[start:end])
02178       self.movable_obstacles = []
02179       for i in range(0, length):
02180         val1 = object_manipulation_msgs.msg.GraspableObject()
02181         start = end
02182         end += 4
02183         (length,) = _struct_I.unpack(str[start:end])
02184         start = end
02185         end += length
02186         if python3:
02187           val1.reference_frame_id = str[start:end].decode('utf-8')
02188         else:
02189           val1.reference_frame_id = str[start:end]
02190         start = end
02191         end += 4
02192         (length,) = _struct_I.unpack(str[start:end])
02193         val1.potential_models = []
02194         for i in range(0, length):
02195           val2 = household_objects_database_msgs.msg.DatabaseModelPose()
02196           start = end
02197           end += 4
02198           (val2.model_id,) = _struct_i.unpack(str[start:end])
02199           _v121 = val2.pose
02200           _v122 = _v121.header
02201           start = end
02202           end += 4
02203           (_v122.seq,) = _struct_I.unpack(str[start:end])
02204           _v123 = _v122.stamp
02205           _x = _v123
02206           start = end
02207           end += 8
02208           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02209           start = end
02210           end += 4
02211           (length,) = _struct_I.unpack(str[start:end])
02212           start = end
02213           end += length
02214           if python3:
02215             _v122.frame_id = str[start:end].decode('utf-8')
02216           else:
02217             _v122.frame_id = str[start:end]
02218           _v124 = _v121.pose
02219           _v125 = _v124.position
02220           _x = _v125
02221           start = end
02222           end += 24
02223           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02224           _v126 = _v124.orientation
02225           _x = _v126
02226           start = end
02227           end += 32
02228           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02229           start = end
02230           end += 4
02231           (val2.confidence,) = _struct_f.unpack(str[start:end])
02232           start = end
02233           end += 4
02234           (length,) = _struct_I.unpack(str[start:end])
02235           start = end
02236           end += length
02237           if python3:
02238             val2.detector_name = str[start:end].decode('utf-8')
02239           else:
02240             val2.detector_name = str[start:end]
02241           val1.potential_models.append(val2)
02242         _v127 = val1.cluster
02243         _v128 = _v127.header
02244         start = end
02245         end += 4
02246         (_v128.seq,) = _struct_I.unpack(str[start:end])
02247         _v129 = _v128.stamp
02248         _x = _v129
02249         start = end
02250         end += 8
02251         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02252         start = end
02253         end += 4
02254         (length,) = _struct_I.unpack(str[start:end])
02255         start = end
02256         end += length
02257         if python3:
02258           _v128.frame_id = str[start:end].decode('utf-8')
02259         else:
02260           _v128.frame_id = str[start:end]
02261         start = end
02262         end += 4
02263         (length,) = _struct_I.unpack(str[start:end])
02264         _v127.points = []
02265         for i in range(0, length):
02266           val3 = geometry_msgs.msg.Point32()
02267           _x = val3
02268           start = end
02269           end += 12
02270           (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
02271           _v127.points.append(val3)
02272         start = end
02273         end += 4
02274         (length,) = _struct_I.unpack(str[start:end])
02275         _v127.channels = []
02276         for i in range(0, length):
02277           val3 = sensor_msgs.msg.ChannelFloat32()
02278           start = end
02279           end += 4
02280           (length,) = _struct_I.unpack(str[start:end])
02281           start = end
02282           end += length
02283           if python3:
02284             val3.name = str[start:end].decode('utf-8')
02285           else:
02286             val3.name = str[start:end]
02287           start = end
02288           end += 4
02289           (length,) = _struct_I.unpack(str[start:end])
02290           pattern = '<%sf'%length
02291           start = end
02292           end += struct.calcsize(pattern)
02293           val3.values = struct.unpack(pattern, str[start:end])
02294           _v127.channels.append(val3)
02295         _v130 = val1.region
02296         _v131 = _v130.cloud
02297         _v132 = _v131.header
02298         start = end
02299         end += 4
02300         (_v132.seq,) = _struct_I.unpack(str[start:end])
02301         _v133 = _v132.stamp
02302         _x = _v133
02303         start = end
02304         end += 8
02305         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02306         start = end
02307         end += 4
02308         (length,) = _struct_I.unpack(str[start:end])
02309         start = end
02310         end += length
02311         if python3:
02312           _v132.frame_id = str[start:end].decode('utf-8')
02313         else:
02314           _v132.frame_id = str[start:end]
02315         _x = _v131
02316         start = end
02317         end += 8
02318         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02319         start = end
02320         end += 4
02321         (length,) = _struct_I.unpack(str[start:end])
02322         _v131.fields = []
02323         for i in range(0, length):
02324           val4 = sensor_msgs.msg.PointField()
02325           start = end
02326           end += 4
02327           (length,) = _struct_I.unpack(str[start:end])
02328           start = end
02329           end += length
02330           if python3:
02331             val4.name = str[start:end].decode('utf-8')
02332           else:
02333             val4.name = str[start:end]
02334           _x = val4
02335           start = end
02336           end += 9
02337           (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
02338           _v131.fields.append(val4)
02339         _x = _v131
02340         start = end
02341         end += 9
02342         (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
02343         _v131.is_bigendian = bool(_v131.is_bigendian)
02344         start = end
02345         end += 4
02346         (length,) = _struct_I.unpack(str[start:end])
02347         start = end
02348         end += length
02349         if python3:
02350           _v131.data = str[start:end].decode('utf-8')
02351         else:
02352           _v131.data = str[start:end]
02353         start = end
02354         end += 1
02355         (_v131.is_dense,) = _struct_B.unpack(str[start:end])
02356         _v131.is_dense = bool(_v131.is_dense)
02357         start = end
02358         end += 4
02359         (length,) = _struct_I.unpack(str[start:end])
02360         pattern = '<%si'%length
02361         start = end
02362         end += struct.calcsize(pattern)
02363         _v130.mask = struct.unpack(pattern, str[start:end])
02364         _v134 = _v130.image
02365         _v135 = _v134.header
02366         start = end
02367         end += 4
02368         (_v135.seq,) = _struct_I.unpack(str[start:end])
02369         _v136 = _v135.stamp
02370         _x = _v136
02371         start = end
02372         end += 8
02373         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02374         start = end
02375         end += 4
02376         (length,) = _struct_I.unpack(str[start:end])
02377         start = end
02378         end += length
02379         if python3:
02380           _v135.frame_id = str[start:end].decode('utf-8')
02381         else:
02382           _v135.frame_id = str[start:end]
02383         _x = _v134
02384         start = end
02385         end += 8
02386         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02387         start = end
02388         end += 4
02389         (length,) = _struct_I.unpack(str[start:end])
02390         start = end
02391         end += length
02392         if python3:
02393           _v134.encoding = str[start:end].decode('utf-8')
02394         else:
02395           _v134.encoding = str[start:end]
02396         _x = _v134
02397         start = end
02398         end += 5
02399         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
02400         start = end
02401         end += 4
02402         (length,) = _struct_I.unpack(str[start:end])
02403         start = end
02404         end += length
02405         if python3:
02406           _v134.data = str[start:end].decode('utf-8')
02407         else:
02408           _v134.data = str[start:end]
02409         _v137 = _v130.disparity_image
02410         _v138 = _v137.header
02411         start = end
02412         end += 4
02413         (_v138.seq,) = _struct_I.unpack(str[start:end])
02414         _v139 = _v138.stamp
02415         _x = _v139
02416         start = end
02417         end += 8
02418         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02419         start = end
02420         end += 4
02421         (length,) = _struct_I.unpack(str[start:end])
02422         start = end
02423         end += length
02424         if python3:
02425           _v138.frame_id = str[start:end].decode('utf-8')
02426         else:
02427           _v138.frame_id = str[start:end]
02428         _x = _v137
02429         start = end
02430         end += 8
02431         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02432         start = end
02433         end += 4
02434         (length,) = _struct_I.unpack(str[start:end])
02435         start = end
02436         end += length
02437         if python3:
02438           _v137.encoding = str[start:end].decode('utf-8')
02439         else:
02440           _v137.encoding = str[start:end]
02441         _x = _v137
02442         start = end
02443         end += 5
02444         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
02445         start = end
02446         end += 4
02447         (length,) = _struct_I.unpack(str[start:end])
02448         start = end
02449         end += length
02450         if python3:
02451           _v137.data = str[start:end].decode('utf-8')
02452         else:
02453           _v137.data = str[start:end]
02454         _v140 = _v130.cam_info
02455         _v141 = _v140.header
02456         start = end
02457         end += 4
02458         (_v141.seq,) = _struct_I.unpack(str[start:end])
02459         _v142 = _v141.stamp
02460         _x = _v142
02461         start = end
02462         end += 8
02463         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02464         start = end
02465         end += 4
02466         (length,) = _struct_I.unpack(str[start:end])
02467         start = end
02468         end += length
02469         if python3:
02470           _v141.frame_id = str[start:end].decode('utf-8')
02471         else:
02472           _v141.frame_id = str[start:end]
02473         _x = _v140
02474         start = end
02475         end += 8
02476         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02477         start = end
02478         end += 4
02479         (length,) = _struct_I.unpack(str[start:end])
02480         start = end
02481         end += length
02482         if python3:
02483           _v140.distortion_model = str[start:end].decode('utf-8')
02484         else:
02485           _v140.distortion_model = str[start:end]
02486         start = end
02487         end += 4
02488         (length,) = _struct_I.unpack(str[start:end])
02489         pattern = '<%sd'%length
02490         start = end
02491         end += struct.calcsize(pattern)
02492         _v140.D = struct.unpack(pattern, str[start:end])
02493         start = end
02494         end += 72
02495         _v140.K = _struct_9d.unpack(str[start:end])
02496         start = end
02497         end += 72
02498         _v140.R = _struct_9d.unpack(str[start:end])
02499         start = end
02500         end += 96
02501         _v140.P = _struct_12d.unpack(str[start:end])
02502         _x = _v140
02503         start = end
02504         end += 8
02505         (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
02506         _v143 = _v140.roi
02507         _x = _v143
02508         start = end
02509         end += 17
02510         (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
02511         _v143.do_rectify = bool(_v143.do_rectify)
02512         _v144 = _v130.roi_box_pose
02513         _v145 = _v144.header
02514         start = end
02515         end += 4
02516         (_v145.seq,) = _struct_I.unpack(str[start:end])
02517         _v146 = _v145.stamp
02518         _x = _v146
02519         start = end
02520         end += 8
02521         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02522         start = end
02523         end += 4
02524         (length,) = _struct_I.unpack(str[start:end])
02525         start = end
02526         end += length
02527         if python3:
02528           _v145.frame_id = str[start:end].decode('utf-8')
02529         else:
02530           _v145.frame_id = str[start:end]
02531         _v147 = _v144.pose
02532         _v148 = _v147.position
02533         _x = _v148
02534         start = end
02535         end += 24
02536         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02537         _v149 = _v147.orientation
02538         _x = _v149
02539         start = end
02540         end += 32
02541         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02542         _v150 = _v130.roi_box_dims
02543         _x = _v150
02544         start = end
02545         end += 24
02546         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02547         start = end
02548         end += 4
02549         (length,) = _struct_I.unpack(str[start:end])
02550         start = end
02551         end += length
02552         if python3:
02553           val1.collision_name = str[start:end].decode('utf-8')
02554         else:
02555           val1.collision_name = str[start:end]
02556         self.movable_obstacles.append(val1)
02557       return self
02558     except struct.error as e:
02559       raise genpy.DeserializationError(e) #most likely buffer underfill
02560 
02561 
02562   def serialize_numpy(self, buff, numpy):
02563     """
02564     serialize message with numpy array types into buffer
02565     :param buff: buffer, ``StringIO``
02566     :param numpy: numpy python module
02567     """
02568     try:
02569       _x = self.arm_name
02570       length = len(_x)
02571       if python3 or type(_x) == unicode:
02572         _x = _x.encode('utf-8')
02573         length = len(_x)
02574       buff.write(struct.pack('<I%ss'%length, length, _x))
02575       _x = self.target.reference_frame_id
02576       length = len(_x)
02577       if python3 or type(_x) == unicode:
02578         _x = _x.encode('utf-8')
02579         length = len(_x)
02580       buff.write(struct.pack('<I%ss'%length, length, _x))
02581       length = len(self.target.potential_models)
02582       buff.write(_struct_I.pack(length))
02583       for val1 in self.target.potential_models:
02584         buff.write(_struct_i.pack(val1.model_id))
02585         _v151 = val1.pose
02586         _v152 = _v151.header
02587         buff.write(_struct_I.pack(_v152.seq))
02588         _v153 = _v152.stamp
02589         _x = _v153
02590         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02591         _x = _v152.frame_id
02592         length = len(_x)
02593         if python3 or type(_x) == unicode:
02594           _x = _x.encode('utf-8')
02595           length = len(_x)
02596         buff.write(struct.pack('<I%ss'%length, length, _x))
02597         _v154 = _v151.pose
02598         _v155 = _v154.position
02599         _x = _v155
02600         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02601         _v156 = _v154.orientation
02602         _x = _v156
02603         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02604         buff.write(_struct_f.pack(val1.confidence))
02605         _x = val1.detector_name
02606         length = len(_x)
02607         if python3 or type(_x) == unicode:
02608           _x = _x.encode('utf-8')
02609           length = len(_x)
02610         buff.write(struct.pack('<I%ss'%length, length, _x))
02611       _x = self
02612       buff.write(_struct_3I.pack(_x.target.cluster.header.seq, _x.target.cluster.header.stamp.secs, _x.target.cluster.header.stamp.nsecs))
02613       _x = self.target.cluster.header.frame_id
02614       length = len(_x)
02615       if python3 or type(_x) == unicode:
02616         _x = _x.encode('utf-8')
02617         length = len(_x)
02618       buff.write(struct.pack('<I%ss'%length, length, _x))
02619       length = len(self.target.cluster.points)
02620       buff.write(_struct_I.pack(length))
02621       for val1 in self.target.cluster.points:
02622         _x = val1
02623         buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
02624       length = len(self.target.cluster.channels)
02625       buff.write(_struct_I.pack(length))
02626       for val1 in self.target.cluster.channels:
02627         _x = val1.name
02628         length = len(_x)
02629         if python3 or type(_x) == unicode:
02630           _x = _x.encode('utf-8')
02631           length = len(_x)
02632         buff.write(struct.pack('<I%ss'%length, length, _x))
02633         length = len(val1.values)
02634         buff.write(_struct_I.pack(length))
02635         pattern = '<%sf'%length
02636         buff.write(val1.values.tostring())
02637       _x = self
02638       buff.write(_struct_3I.pack(_x.target.region.cloud.header.seq, _x.target.region.cloud.header.stamp.secs, _x.target.region.cloud.header.stamp.nsecs))
02639       _x = self.target.region.cloud.header.frame_id
02640       length = len(_x)
02641       if python3 or type(_x) == unicode:
02642         _x = _x.encode('utf-8')
02643         length = len(_x)
02644       buff.write(struct.pack('<I%ss'%length, length, _x))
02645       _x = self
02646       buff.write(_struct_2I.pack(_x.target.region.cloud.height, _x.target.region.cloud.width))
02647       length = len(self.target.region.cloud.fields)
02648       buff.write(_struct_I.pack(length))
02649       for val1 in self.target.region.cloud.fields:
02650         _x = val1.name
02651         length = len(_x)
02652         if python3 or type(_x) == unicode:
02653           _x = _x.encode('utf-8')
02654           length = len(_x)
02655         buff.write(struct.pack('<I%ss'%length, length, _x))
02656         _x = val1
02657         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
02658       _x = self
02659       buff.write(_struct_B2I.pack(_x.target.region.cloud.is_bigendian, _x.target.region.cloud.point_step, _x.target.region.cloud.row_step))
02660       _x = self.target.region.cloud.data
02661       length = len(_x)
02662       # - if encoded as a list instead, serialize as bytes instead of string
02663       if type(_x) in [list, tuple]:
02664         buff.write(struct.pack('<I%sB'%length, length, *_x))
02665       else:
02666         buff.write(struct.pack('<I%ss'%length, length, _x))
02667       buff.write(_struct_B.pack(self.target.region.cloud.is_dense))
02668       length = len(self.target.region.mask)
02669       buff.write(_struct_I.pack(length))
02670       pattern = '<%si'%length
02671       buff.write(self.target.region.mask.tostring())
02672       _x = self
02673       buff.write(_struct_3I.pack(_x.target.region.image.header.seq, _x.target.region.image.header.stamp.secs, _x.target.region.image.header.stamp.nsecs))
02674       _x = self.target.region.image.header.frame_id
02675       length = len(_x)
02676       if python3 or type(_x) == unicode:
02677         _x = _x.encode('utf-8')
02678         length = len(_x)
02679       buff.write(struct.pack('<I%ss'%length, length, _x))
02680       _x = self
02681       buff.write(_struct_2I.pack(_x.target.region.image.height, _x.target.region.image.width))
02682       _x = self.target.region.image.encoding
02683       length = len(_x)
02684       if python3 or type(_x) == unicode:
02685         _x = _x.encode('utf-8')
02686         length = len(_x)
02687       buff.write(struct.pack('<I%ss'%length, length, _x))
02688       _x = self
02689       buff.write(_struct_BI.pack(_x.target.region.image.is_bigendian, _x.target.region.image.step))
02690       _x = self.target.region.image.data
02691       length = len(_x)
02692       # - if encoded as a list instead, serialize as bytes instead of string
02693       if type(_x) in [list, tuple]:
02694         buff.write(struct.pack('<I%sB'%length, length, *_x))
02695       else:
02696         buff.write(struct.pack('<I%ss'%length, length, _x))
02697       _x = self
02698       buff.write(_struct_3I.pack(_x.target.region.disparity_image.header.seq, _x.target.region.disparity_image.header.stamp.secs, _x.target.region.disparity_image.header.stamp.nsecs))
02699       _x = self.target.region.disparity_image.header.frame_id
02700       length = len(_x)
02701       if python3 or type(_x) == unicode:
02702         _x = _x.encode('utf-8')
02703         length = len(_x)
02704       buff.write(struct.pack('<I%ss'%length, length, _x))
02705       _x = self
02706       buff.write(_struct_2I.pack(_x.target.region.disparity_image.height, _x.target.region.disparity_image.width))
02707       _x = self.target.region.disparity_image.encoding
02708       length = len(_x)
02709       if python3 or type(_x) == unicode:
02710         _x = _x.encode('utf-8')
02711         length = len(_x)
02712       buff.write(struct.pack('<I%ss'%length, length, _x))
02713       _x = self
02714       buff.write(_struct_BI.pack(_x.target.region.disparity_image.is_bigendian, _x.target.region.disparity_image.step))
02715       _x = self.target.region.disparity_image.data
02716       length = len(_x)
02717       # - if encoded as a list instead, serialize as bytes instead of string
02718       if type(_x) in [list, tuple]:
02719         buff.write(struct.pack('<I%sB'%length, length, *_x))
02720       else:
02721         buff.write(struct.pack('<I%ss'%length, length, _x))
02722       _x = self
02723       buff.write(_struct_3I.pack(_x.target.region.cam_info.header.seq, _x.target.region.cam_info.header.stamp.secs, _x.target.region.cam_info.header.stamp.nsecs))
02724       _x = self.target.region.cam_info.header.frame_id
02725       length = len(_x)
02726       if python3 or type(_x) == unicode:
02727         _x = _x.encode('utf-8')
02728         length = len(_x)
02729       buff.write(struct.pack('<I%ss'%length, length, _x))
02730       _x = self
02731       buff.write(_struct_2I.pack(_x.target.region.cam_info.height, _x.target.region.cam_info.width))
02732       _x = self.target.region.cam_info.distortion_model
02733       length = len(_x)
02734       if python3 or type(_x) == unicode:
02735         _x = _x.encode('utf-8')
02736         length = len(_x)
02737       buff.write(struct.pack('<I%ss'%length, length, _x))
02738       length = len(self.target.region.cam_info.D)
02739       buff.write(_struct_I.pack(length))
02740       pattern = '<%sd'%length
02741       buff.write(self.target.region.cam_info.D.tostring())
02742       buff.write(self.target.region.cam_info.K.tostring())
02743       buff.write(self.target.region.cam_info.R.tostring())
02744       buff.write(self.target.region.cam_info.P.tostring())
02745       _x = self
02746       buff.write(_struct_6IB3I.pack(_x.target.region.cam_info.binning_x, _x.target.region.cam_info.binning_y, _x.target.region.cam_info.roi.x_offset, _x.target.region.cam_info.roi.y_offset, _x.target.region.cam_info.roi.height, _x.target.region.cam_info.roi.width, _x.target.region.cam_info.roi.do_rectify, _x.target.region.roi_box_pose.header.seq, _x.target.region.roi_box_pose.header.stamp.secs, _x.target.region.roi_box_pose.header.stamp.nsecs))
02747       _x = self.target.region.roi_box_pose.header.frame_id
02748       length = len(_x)
02749       if python3 or type(_x) == unicode:
02750         _x = _x.encode('utf-8')
02751         length = len(_x)
02752       buff.write(struct.pack('<I%ss'%length, length, _x))
02753       _x = self
02754       buff.write(_struct_10d.pack(_x.target.region.roi_box_pose.pose.position.x, _x.target.region.roi_box_pose.pose.position.y, _x.target.region.roi_box_pose.pose.position.z, _x.target.region.roi_box_pose.pose.orientation.x, _x.target.region.roi_box_pose.pose.orientation.y, _x.target.region.roi_box_pose.pose.orientation.z, _x.target.region.roi_box_pose.pose.orientation.w, _x.target.region.roi_box_dims.x, _x.target.region.roi_box_dims.y, _x.target.region.roi_box_dims.z))
02755       _x = self.target.collision_name
02756       length = len(_x)
02757       if python3 or type(_x) == unicode:
02758         _x = _x.encode('utf-8')
02759         length = len(_x)
02760       buff.write(struct.pack('<I%ss'%length, length, _x))
02761       _x = self.collision_object_name
02762       length = len(_x)
02763       if python3 or type(_x) == unicode:
02764         _x = _x.encode('utf-8')
02765         length = len(_x)
02766       buff.write(struct.pack('<I%ss'%length, length, _x))
02767       _x = self.collision_support_surface_name
02768       length = len(_x)
02769       if python3 or type(_x) == unicode:
02770         _x = _x.encode('utf-8')
02771         length = len(_x)
02772       buff.write(struct.pack('<I%ss'%length, length, _x))
02773       length = len(self.grasps_to_evaluate)
02774       buff.write(_struct_I.pack(length))
02775       for val1 in self.grasps_to_evaluate:
02776         _v157 = val1.pre_grasp_posture
02777         _v158 = _v157.header
02778         buff.write(_struct_I.pack(_v158.seq))
02779         _v159 = _v158.stamp
02780         _x = _v159
02781         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02782         _x = _v158.frame_id
02783         length = len(_x)
02784         if python3 or type(_x) == unicode:
02785           _x = _x.encode('utf-8')
02786           length = len(_x)
02787         buff.write(struct.pack('<I%ss'%length, length, _x))
02788         length = len(_v157.name)
02789         buff.write(_struct_I.pack(length))
02790         for val3 in _v157.name:
02791           length = len(val3)
02792           if python3 or type(val3) == unicode:
02793             val3 = val3.encode('utf-8')
02794             length = len(val3)
02795           buff.write(struct.pack('<I%ss'%length, length, val3))
02796         length = len(_v157.position)
02797         buff.write(_struct_I.pack(length))
02798         pattern = '<%sd'%length
02799         buff.write(_v157.position.tostring())
02800         length = len(_v157.velocity)
02801         buff.write(_struct_I.pack(length))
02802         pattern = '<%sd'%length
02803         buff.write(_v157.velocity.tostring())
02804         length = len(_v157.effort)
02805         buff.write(_struct_I.pack(length))
02806         pattern = '<%sd'%length
02807         buff.write(_v157.effort.tostring())
02808         _v160 = val1.grasp_posture
02809         _v161 = _v160.header
02810         buff.write(_struct_I.pack(_v161.seq))
02811         _v162 = _v161.stamp
02812         _x = _v162
02813         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02814         _x = _v161.frame_id
02815         length = len(_x)
02816         if python3 or type(_x) == unicode:
02817           _x = _x.encode('utf-8')
02818           length = len(_x)
02819         buff.write(struct.pack('<I%ss'%length, length, _x))
02820         length = len(_v160.name)
02821         buff.write(_struct_I.pack(length))
02822         for val3 in _v160.name:
02823           length = len(val3)
02824           if python3 or type(val3) == unicode:
02825             val3 = val3.encode('utf-8')
02826             length = len(val3)
02827           buff.write(struct.pack('<I%ss'%length, length, val3))
02828         length = len(_v160.position)
02829         buff.write(_struct_I.pack(length))
02830         pattern = '<%sd'%length
02831         buff.write(_v160.position.tostring())
02832         length = len(_v160.velocity)
02833         buff.write(_struct_I.pack(length))
02834         pattern = '<%sd'%length
02835         buff.write(_v160.velocity.tostring())
02836         length = len(_v160.effort)
02837         buff.write(_struct_I.pack(length))
02838         pattern = '<%sd'%length
02839         buff.write(_v160.effort.tostring())
02840         _v163 = val1.grasp_pose
02841         _v164 = _v163.position
02842         _x = _v164
02843         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02844         _v165 = _v163.orientation
02845         _x = _v165
02846         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02847         _x = val1
02848         buff.write(_struct_dB2f.pack(_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance))
02849         length = len(val1.moved_obstacles)
02850         buff.write(_struct_I.pack(length))
02851         for val2 in val1.moved_obstacles:
02852           _x = val2.reference_frame_id
02853           length = len(_x)
02854           if python3 or type(_x) == unicode:
02855             _x = _x.encode('utf-8')
02856             length = len(_x)
02857           buff.write(struct.pack('<I%ss'%length, length, _x))
02858           length = len(val2.potential_models)
02859           buff.write(_struct_I.pack(length))
02860           for val3 in val2.potential_models:
02861             buff.write(_struct_i.pack(val3.model_id))
02862             _v166 = val3.pose
02863             _v167 = _v166.header
02864             buff.write(_struct_I.pack(_v167.seq))
02865             _v168 = _v167.stamp
02866             _x = _v168
02867             buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02868             _x = _v167.frame_id
02869             length = len(_x)
02870             if python3 or type(_x) == unicode:
02871               _x = _x.encode('utf-8')
02872               length = len(_x)
02873             buff.write(struct.pack('<I%ss'%length, length, _x))
02874             _v169 = _v166.pose
02875             _v170 = _v169.position
02876             _x = _v170
02877             buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02878             _v171 = _v169.orientation
02879             _x = _v171
02880             buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02881             buff.write(_struct_f.pack(val3.confidence))
02882             _x = val3.detector_name
02883             length = len(_x)
02884             if python3 or type(_x) == unicode:
02885               _x = _x.encode('utf-8')
02886               length = len(_x)
02887             buff.write(struct.pack('<I%ss'%length, length, _x))
02888           _v172 = val2.cluster
02889           _v173 = _v172.header
02890           buff.write(_struct_I.pack(_v173.seq))
02891           _v174 = _v173.stamp
02892           _x = _v174
02893           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02894           _x = _v173.frame_id
02895           length = len(_x)
02896           if python3 or type(_x) == unicode:
02897             _x = _x.encode('utf-8')
02898             length = len(_x)
02899           buff.write(struct.pack('<I%ss'%length, length, _x))
02900           length = len(_v172.points)
02901           buff.write(_struct_I.pack(length))
02902           for val4 in _v172.points:
02903             _x = val4
02904             buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
02905           length = len(_v172.channels)
02906           buff.write(_struct_I.pack(length))
02907           for val4 in _v172.channels:
02908             _x = val4.name
02909             length = len(_x)
02910             if python3 or type(_x) == unicode:
02911               _x = _x.encode('utf-8')
02912               length = len(_x)
02913             buff.write(struct.pack('<I%ss'%length, length, _x))
02914             length = len(val4.values)
02915             buff.write(_struct_I.pack(length))
02916             pattern = '<%sf'%length
02917             buff.write(val4.values.tostring())
02918           _v175 = val2.region
02919           _v176 = _v175.cloud
02920           _v177 = _v176.header
02921           buff.write(_struct_I.pack(_v177.seq))
02922           _v178 = _v177.stamp
02923           _x = _v178
02924           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02925           _x = _v177.frame_id
02926           length = len(_x)
02927           if python3 or type(_x) == unicode:
02928             _x = _x.encode('utf-8')
02929             length = len(_x)
02930           buff.write(struct.pack('<I%ss'%length, length, _x))
02931           _x = _v176
02932           buff.write(_struct_2I.pack(_x.height, _x.width))
02933           length = len(_v176.fields)
02934           buff.write(_struct_I.pack(length))
02935           for val5 in _v176.fields:
02936             _x = val5.name
02937             length = len(_x)
02938             if python3 or type(_x) == unicode:
02939               _x = _x.encode('utf-8')
02940               length = len(_x)
02941             buff.write(struct.pack('<I%ss'%length, length, _x))
02942             _x = val5
02943             buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
02944           _x = _v176
02945           buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
02946           _x = _v176.data
02947           length = len(_x)
02948           # - if encoded as a list instead, serialize as bytes instead of string
02949           if type(_x) in [list, tuple]:
02950             buff.write(struct.pack('<I%sB'%length, length, *_x))
02951           else:
02952             buff.write(struct.pack('<I%ss'%length, length, _x))
02953           buff.write(_struct_B.pack(_v176.is_dense))
02954           length = len(_v175.mask)
02955           buff.write(_struct_I.pack(length))
02956           pattern = '<%si'%length
02957           buff.write(_v175.mask.tostring())
02958           _v179 = _v175.image
02959           _v180 = _v179.header
02960           buff.write(_struct_I.pack(_v180.seq))
02961           _v181 = _v180.stamp
02962           _x = _v181
02963           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02964           _x = _v180.frame_id
02965           length = len(_x)
02966           if python3 or type(_x) == unicode:
02967             _x = _x.encode('utf-8')
02968             length = len(_x)
02969           buff.write(struct.pack('<I%ss'%length, length, _x))
02970           _x = _v179
02971           buff.write(_struct_2I.pack(_x.height, _x.width))
02972           _x = _v179.encoding
02973           length = len(_x)
02974           if python3 or type(_x) == unicode:
02975             _x = _x.encode('utf-8')
02976             length = len(_x)
02977           buff.write(struct.pack('<I%ss'%length, length, _x))
02978           _x = _v179
02979           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
02980           _x = _v179.data
02981           length = len(_x)
02982           # - if encoded as a list instead, serialize as bytes instead of string
02983           if type(_x) in [list, tuple]:
02984             buff.write(struct.pack('<I%sB'%length, length, *_x))
02985           else:
02986             buff.write(struct.pack('<I%ss'%length, length, _x))
02987           _v182 = _v175.disparity_image
02988           _v183 = _v182.header
02989           buff.write(_struct_I.pack(_v183.seq))
02990           _v184 = _v183.stamp
02991           _x = _v184
02992           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02993           _x = _v183.frame_id
02994           length = len(_x)
02995           if python3 or type(_x) == unicode:
02996             _x = _x.encode('utf-8')
02997             length = len(_x)
02998           buff.write(struct.pack('<I%ss'%length, length, _x))
02999           _x = _v182
03000           buff.write(_struct_2I.pack(_x.height, _x.width))
03001           _x = _v182.encoding
03002           length = len(_x)
03003           if python3 or type(_x) == unicode:
03004             _x = _x.encode('utf-8')
03005             length = len(_x)
03006           buff.write(struct.pack('<I%ss'%length, length, _x))
03007           _x = _v182
03008           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
03009           _x = _v182.data
03010           length = len(_x)
03011           # - if encoded as a list instead, serialize as bytes instead of string
03012           if type(_x) in [list, tuple]:
03013             buff.write(struct.pack('<I%sB'%length, length, *_x))
03014           else:
03015             buff.write(struct.pack('<I%ss'%length, length, _x))
03016           _v185 = _v175.cam_info
03017           _v186 = _v185.header
03018           buff.write(_struct_I.pack(_v186.seq))
03019           _v187 = _v186.stamp
03020           _x = _v187
03021           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03022           _x = _v186.frame_id
03023           length = len(_x)
03024           if python3 or type(_x) == unicode:
03025             _x = _x.encode('utf-8')
03026             length = len(_x)
03027           buff.write(struct.pack('<I%ss'%length, length, _x))
03028           _x = _v185
03029           buff.write(_struct_2I.pack(_x.height, _x.width))
03030           _x = _v185.distortion_model
03031           length = len(_x)
03032           if python3 or type(_x) == unicode:
03033             _x = _x.encode('utf-8')
03034             length = len(_x)
03035           buff.write(struct.pack('<I%ss'%length, length, _x))
03036           length = len(_v185.D)
03037           buff.write(_struct_I.pack(length))
03038           pattern = '<%sd'%length
03039           buff.write(_v185.D.tostring())
03040           buff.write(_v185.K.tostring())
03041           buff.write(_v185.R.tostring())
03042           buff.write(_v185.P.tostring())
03043           _x = _v185
03044           buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
03045           _v188 = _v185.roi
03046           _x = _v188
03047           buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
03048           _v189 = _v175.roi_box_pose
03049           _v190 = _v189.header
03050           buff.write(_struct_I.pack(_v190.seq))
03051           _v191 = _v190.stamp
03052           _x = _v191
03053           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03054           _x = _v190.frame_id
03055           length = len(_x)
03056           if python3 or type(_x) == unicode:
03057             _x = _x.encode('utf-8')
03058             length = len(_x)
03059           buff.write(struct.pack('<I%ss'%length, length, _x))
03060           _v192 = _v189.pose
03061           _v193 = _v192.position
03062           _x = _v193
03063           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03064           _v194 = _v192.orientation
03065           _x = _v194
03066           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03067           _v195 = _v175.roi_box_dims
03068           _x = _v195
03069           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03070           _x = val2.collision_name
03071           length = len(_x)
03072           if python3 or type(_x) == unicode:
03073             _x = _x.encode('utf-8')
03074             length = len(_x)
03075           buff.write(struct.pack('<I%ss'%length, length, _x))
03076       length = len(self.movable_obstacles)
03077       buff.write(_struct_I.pack(length))
03078       for val1 in self.movable_obstacles:
03079         _x = val1.reference_frame_id
03080         length = len(_x)
03081         if python3 or type(_x) == unicode:
03082           _x = _x.encode('utf-8')
03083           length = len(_x)
03084         buff.write(struct.pack('<I%ss'%length, length, _x))
03085         length = len(val1.potential_models)
03086         buff.write(_struct_I.pack(length))
03087         for val2 in val1.potential_models:
03088           buff.write(_struct_i.pack(val2.model_id))
03089           _v196 = val2.pose
03090           _v197 = _v196.header
03091           buff.write(_struct_I.pack(_v197.seq))
03092           _v198 = _v197.stamp
03093           _x = _v198
03094           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03095           _x = _v197.frame_id
03096           length = len(_x)
03097           if python3 or type(_x) == unicode:
03098             _x = _x.encode('utf-8')
03099             length = len(_x)
03100           buff.write(struct.pack('<I%ss'%length, length, _x))
03101           _v199 = _v196.pose
03102           _v200 = _v199.position
03103           _x = _v200
03104           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03105           _v201 = _v199.orientation
03106           _x = _v201
03107           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03108           buff.write(_struct_f.pack(val2.confidence))
03109           _x = val2.detector_name
03110           length = len(_x)
03111           if python3 or type(_x) == unicode:
03112             _x = _x.encode('utf-8')
03113             length = len(_x)
03114           buff.write(struct.pack('<I%ss'%length, length, _x))
03115         _v202 = val1.cluster
03116         _v203 = _v202.header
03117         buff.write(_struct_I.pack(_v203.seq))
03118         _v204 = _v203.stamp
03119         _x = _v204
03120         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03121         _x = _v203.frame_id
03122         length = len(_x)
03123         if python3 or type(_x) == unicode:
03124           _x = _x.encode('utf-8')
03125           length = len(_x)
03126         buff.write(struct.pack('<I%ss'%length, length, _x))
03127         length = len(_v202.points)
03128         buff.write(_struct_I.pack(length))
03129         for val3 in _v202.points:
03130           _x = val3
03131           buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
03132         length = len(_v202.channels)
03133         buff.write(_struct_I.pack(length))
03134         for val3 in _v202.channels:
03135           _x = val3.name
03136           length = len(_x)
03137           if python3 or type(_x) == unicode:
03138             _x = _x.encode('utf-8')
03139             length = len(_x)
03140           buff.write(struct.pack('<I%ss'%length, length, _x))
03141           length = len(val3.values)
03142           buff.write(_struct_I.pack(length))
03143           pattern = '<%sf'%length
03144           buff.write(val3.values.tostring())
03145         _v205 = val1.region
03146         _v206 = _v205.cloud
03147         _v207 = _v206.header
03148         buff.write(_struct_I.pack(_v207.seq))
03149         _v208 = _v207.stamp
03150         _x = _v208
03151         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03152         _x = _v207.frame_id
03153         length = len(_x)
03154         if python3 or type(_x) == unicode:
03155           _x = _x.encode('utf-8')
03156           length = len(_x)
03157         buff.write(struct.pack('<I%ss'%length, length, _x))
03158         _x = _v206
03159         buff.write(_struct_2I.pack(_x.height, _x.width))
03160         length = len(_v206.fields)
03161         buff.write(_struct_I.pack(length))
03162         for val4 in _v206.fields:
03163           _x = val4.name
03164           length = len(_x)
03165           if python3 or type(_x) == unicode:
03166             _x = _x.encode('utf-8')
03167             length = len(_x)
03168           buff.write(struct.pack('<I%ss'%length, length, _x))
03169           _x = val4
03170           buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
03171         _x = _v206
03172         buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
03173         _x = _v206.data
03174         length = len(_x)
03175         # - if encoded as a list instead, serialize as bytes instead of string
03176         if type(_x) in [list, tuple]:
03177           buff.write(struct.pack('<I%sB'%length, length, *_x))
03178         else:
03179           buff.write(struct.pack('<I%ss'%length, length, _x))
03180         buff.write(_struct_B.pack(_v206.is_dense))
03181         length = len(_v205.mask)
03182         buff.write(_struct_I.pack(length))
03183         pattern = '<%si'%length
03184         buff.write(_v205.mask.tostring())
03185         _v209 = _v205.image
03186         _v210 = _v209.header
03187         buff.write(_struct_I.pack(_v210.seq))
03188         _v211 = _v210.stamp
03189         _x = _v211
03190         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03191         _x = _v210.frame_id
03192         length = len(_x)
03193         if python3 or type(_x) == unicode:
03194           _x = _x.encode('utf-8')
03195           length = len(_x)
03196         buff.write(struct.pack('<I%ss'%length, length, _x))
03197         _x = _v209
03198         buff.write(_struct_2I.pack(_x.height, _x.width))
03199         _x = _v209.encoding
03200         length = len(_x)
03201         if python3 or type(_x) == unicode:
03202           _x = _x.encode('utf-8')
03203           length = len(_x)
03204         buff.write(struct.pack('<I%ss'%length, length, _x))
03205         _x = _v209
03206         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
03207         _x = _v209.data
03208         length = len(_x)
03209         # - if encoded as a list instead, serialize as bytes instead of string
03210         if type(_x) in [list, tuple]:
03211           buff.write(struct.pack('<I%sB'%length, length, *_x))
03212         else:
03213           buff.write(struct.pack('<I%ss'%length, length, _x))
03214         _v212 = _v205.disparity_image
03215         _v213 = _v212.header
03216         buff.write(_struct_I.pack(_v213.seq))
03217         _v214 = _v213.stamp
03218         _x = _v214
03219         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03220         _x = _v213.frame_id
03221         length = len(_x)
03222         if python3 or type(_x) == unicode:
03223           _x = _x.encode('utf-8')
03224           length = len(_x)
03225         buff.write(struct.pack('<I%ss'%length, length, _x))
03226         _x = _v212
03227         buff.write(_struct_2I.pack(_x.height, _x.width))
03228         _x = _v212.encoding
03229         length = len(_x)
03230         if python3 or type(_x) == unicode:
03231           _x = _x.encode('utf-8')
03232           length = len(_x)
03233         buff.write(struct.pack('<I%ss'%length, length, _x))
03234         _x = _v212
03235         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
03236         _x = _v212.data
03237         length = len(_x)
03238         # - if encoded as a list instead, serialize as bytes instead of string
03239         if type(_x) in [list, tuple]:
03240           buff.write(struct.pack('<I%sB'%length, length, *_x))
03241         else:
03242           buff.write(struct.pack('<I%ss'%length, length, _x))
03243         _v215 = _v205.cam_info
03244         _v216 = _v215.header
03245         buff.write(_struct_I.pack(_v216.seq))
03246         _v217 = _v216.stamp
03247         _x = _v217
03248         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03249         _x = _v216.frame_id
03250         length = len(_x)
03251         if python3 or type(_x) == unicode:
03252           _x = _x.encode('utf-8')
03253           length = len(_x)
03254         buff.write(struct.pack('<I%ss'%length, length, _x))
03255         _x = _v215
03256         buff.write(_struct_2I.pack(_x.height, _x.width))
03257         _x = _v215.distortion_model
03258         length = len(_x)
03259         if python3 or type(_x) == unicode:
03260           _x = _x.encode('utf-8')
03261           length = len(_x)
03262         buff.write(struct.pack('<I%ss'%length, length, _x))
03263         length = len(_v215.D)
03264         buff.write(_struct_I.pack(length))
03265         pattern = '<%sd'%length
03266         buff.write(_v215.D.tostring())
03267         buff.write(_v215.K.tostring())
03268         buff.write(_v215.R.tostring())
03269         buff.write(_v215.P.tostring())
03270         _x = _v215
03271         buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
03272         _v218 = _v215.roi
03273         _x = _v218
03274         buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
03275         _v219 = _v205.roi_box_pose
03276         _v220 = _v219.header
03277         buff.write(_struct_I.pack(_v220.seq))
03278         _v221 = _v220.stamp
03279         _x = _v221
03280         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03281         _x = _v220.frame_id
03282         length = len(_x)
03283         if python3 or type(_x) == unicode:
03284           _x = _x.encode('utf-8')
03285           length = len(_x)
03286         buff.write(struct.pack('<I%ss'%length, length, _x))
03287         _v222 = _v219.pose
03288         _v223 = _v222.position
03289         _x = _v223
03290         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03291         _v224 = _v222.orientation
03292         _x = _v224
03293         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03294         _v225 = _v205.roi_box_dims
03295         _x = _v225
03296         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03297         _x = val1.collision_name
03298         length = len(_x)
03299         if python3 or type(_x) == unicode:
03300           _x = _x.encode('utf-8')
03301           length = len(_x)
03302         buff.write(struct.pack('<I%ss'%length, length, _x))
03303     except struct.error as se: self._check_types(se)
03304     except TypeError as te: self._check_types(te)
03305 
03306   def deserialize_numpy(self, str, numpy):
03307     """
03308     unpack serialized message in str into this message instance using numpy for array types
03309     :param str: byte array of serialized message, ``str``
03310     :param numpy: numpy python module
03311     """
03312     try:
03313       if self.target is None:
03314         self.target = object_manipulation_msgs.msg.GraspableObject()
03315       if self.grasps_to_evaluate is None:
03316         self.grasps_to_evaluate = None
03317       if self.movable_obstacles is None:
03318         self.movable_obstacles = None
03319       end = 0
03320       start = end
03321       end += 4
03322       (length,) = _struct_I.unpack(str[start:end])
03323       start = end
03324       end += length
03325       if python3:
03326         self.arm_name = str[start:end].decode('utf-8')
03327       else:
03328         self.arm_name = str[start:end]
03329       start = end
03330       end += 4
03331       (length,) = _struct_I.unpack(str[start:end])
03332       start = end
03333       end += length
03334       if python3:
03335         self.target.reference_frame_id = str[start:end].decode('utf-8')
03336       else:
03337         self.target.reference_frame_id = str[start:end]
03338       start = end
03339       end += 4
03340       (length,) = _struct_I.unpack(str[start:end])
03341       self.target.potential_models = []
03342       for i in range(0, length):
03343         val1 = household_objects_database_msgs.msg.DatabaseModelPose()
03344         start = end
03345         end += 4
03346         (val1.model_id,) = _struct_i.unpack(str[start:end])
03347         _v226 = val1.pose
03348         _v227 = _v226.header
03349         start = end
03350         end += 4
03351         (_v227.seq,) = _struct_I.unpack(str[start:end])
03352         _v228 = _v227.stamp
03353         _x = _v228
03354         start = end
03355         end += 8
03356         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03357         start = end
03358         end += 4
03359         (length,) = _struct_I.unpack(str[start:end])
03360         start = end
03361         end += length
03362         if python3:
03363           _v227.frame_id = str[start:end].decode('utf-8')
03364         else:
03365           _v227.frame_id = str[start:end]
03366         _v229 = _v226.pose
03367         _v230 = _v229.position
03368         _x = _v230
03369         start = end
03370         end += 24
03371         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03372         _v231 = _v229.orientation
03373         _x = _v231
03374         start = end
03375         end += 32
03376         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03377         start = end
03378         end += 4
03379         (val1.confidence,) = _struct_f.unpack(str[start:end])
03380         start = end
03381         end += 4
03382         (length,) = _struct_I.unpack(str[start:end])
03383         start = end
03384         end += length
03385         if python3:
03386           val1.detector_name = str[start:end].decode('utf-8')
03387         else:
03388           val1.detector_name = str[start:end]
03389         self.target.potential_models.append(val1)
03390       _x = self
03391       start = end
03392       end += 12
03393       (_x.target.cluster.header.seq, _x.target.cluster.header.stamp.secs, _x.target.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03394       start = end
03395       end += 4
03396       (length,) = _struct_I.unpack(str[start:end])
03397       start = end
03398       end += length
03399       if python3:
03400         self.target.cluster.header.frame_id = str[start:end].decode('utf-8')
03401       else:
03402         self.target.cluster.header.frame_id = str[start:end]
03403       start = end
03404       end += 4
03405       (length,) = _struct_I.unpack(str[start:end])
03406       self.target.cluster.points = []
03407       for i in range(0, length):
03408         val1 = geometry_msgs.msg.Point32()
03409         _x = val1
03410         start = end
03411         end += 12
03412         (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
03413         self.target.cluster.points.append(val1)
03414       start = end
03415       end += 4
03416       (length,) = _struct_I.unpack(str[start:end])
03417       self.target.cluster.channels = []
03418       for i in range(0, length):
03419         val1 = sensor_msgs.msg.ChannelFloat32()
03420         start = end
03421         end += 4
03422         (length,) = _struct_I.unpack(str[start:end])
03423         start = end
03424         end += length
03425         if python3:
03426           val1.name = str[start:end].decode('utf-8')
03427         else:
03428           val1.name = str[start:end]
03429         start = end
03430         end += 4
03431         (length,) = _struct_I.unpack(str[start:end])
03432         pattern = '<%sf'%length
03433         start = end
03434         end += struct.calcsize(pattern)
03435         val1.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
03436         self.target.cluster.channels.append(val1)
03437       _x = self
03438       start = end
03439       end += 12
03440       (_x.target.region.cloud.header.seq, _x.target.region.cloud.header.stamp.secs, _x.target.region.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03441       start = end
03442       end += 4
03443       (length,) = _struct_I.unpack(str[start:end])
03444       start = end
03445       end += length
03446       if python3:
03447         self.target.region.cloud.header.frame_id = str[start:end].decode('utf-8')
03448       else:
03449         self.target.region.cloud.header.frame_id = str[start:end]
03450       _x = self
03451       start = end
03452       end += 8
03453       (_x.target.region.cloud.height, _x.target.region.cloud.width,) = _struct_2I.unpack(str[start:end])
03454       start = end
03455       end += 4
03456       (length,) = _struct_I.unpack(str[start:end])
03457       self.target.region.cloud.fields = []
03458       for i in range(0, length):
03459         val1 = sensor_msgs.msg.PointField()
03460         start = end
03461         end += 4
03462         (length,) = _struct_I.unpack(str[start:end])
03463         start = end
03464         end += length
03465         if python3:
03466           val1.name = str[start:end].decode('utf-8')
03467         else:
03468           val1.name = str[start:end]
03469         _x = val1
03470         start = end
03471         end += 9
03472         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
03473         self.target.region.cloud.fields.append(val1)
03474       _x = self
03475       start = end
03476       end += 9
03477       (_x.target.region.cloud.is_bigendian, _x.target.region.cloud.point_step, _x.target.region.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
03478       self.target.region.cloud.is_bigendian = bool(self.target.region.cloud.is_bigendian)
03479       start = end
03480       end += 4
03481       (length,) = _struct_I.unpack(str[start:end])
03482       start = end
03483       end += length
03484       if python3:
03485         self.target.region.cloud.data = str[start:end].decode('utf-8')
03486       else:
03487         self.target.region.cloud.data = str[start:end]
03488       start = end
03489       end += 1
03490       (self.target.region.cloud.is_dense,) = _struct_B.unpack(str[start:end])
03491       self.target.region.cloud.is_dense = bool(self.target.region.cloud.is_dense)
03492       start = end
03493       end += 4
03494       (length,) = _struct_I.unpack(str[start:end])
03495       pattern = '<%si'%length
03496       start = end
03497       end += struct.calcsize(pattern)
03498       self.target.region.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
03499       _x = self
03500       start = end
03501       end += 12
03502       (_x.target.region.image.header.seq, _x.target.region.image.header.stamp.secs, _x.target.region.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03503       start = end
03504       end += 4
03505       (length,) = _struct_I.unpack(str[start:end])
03506       start = end
03507       end += length
03508       if python3:
03509         self.target.region.image.header.frame_id = str[start:end].decode('utf-8')
03510       else:
03511         self.target.region.image.header.frame_id = str[start:end]
03512       _x = self
03513       start = end
03514       end += 8
03515       (_x.target.region.image.height, _x.target.region.image.width,) = _struct_2I.unpack(str[start:end])
03516       start = end
03517       end += 4
03518       (length,) = _struct_I.unpack(str[start:end])
03519       start = end
03520       end += length
03521       if python3:
03522         self.target.region.image.encoding = str[start:end].decode('utf-8')
03523       else:
03524         self.target.region.image.encoding = str[start:end]
03525       _x = self
03526       start = end
03527       end += 5
03528       (_x.target.region.image.is_bigendian, _x.target.region.image.step,) = _struct_BI.unpack(str[start:end])
03529       start = end
03530       end += 4
03531       (length,) = _struct_I.unpack(str[start:end])
03532       start = end
03533       end += length
03534       if python3:
03535         self.target.region.image.data = str[start:end].decode('utf-8')
03536       else:
03537         self.target.region.image.data = str[start:end]
03538       _x = self
03539       start = end
03540       end += 12
03541       (_x.target.region.disparity_image.header.seq, _x.target.region.disparity_image.header.stamp.secs, _x.target.region.disparity_image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03542       start = end
03543       end += 4
03544       (length,) = _struct_I.unpack(str[start:end])
03545       start = end
03546       end += length
03547       if python3:
03548         self.target.region.disparity_image.header.frame_id = str[start:end].decode('utf-8')
03549       else:
03550         self.target.region.disparity_image.header.frame_id = str[start:end]
03551       _x = self
03552       start = end
03553       end += 8
03554       (_x.target.region.disparity_image.height, _x.target.region.disparity_image.width,) = _struct_2I.unpack(str[start:end])
03555       start = end
03556       end += 4
03557       (length,) = _struct_I.unpack(str[start:end])
03558       start = end
03559       end += length
03560       if python3:
03561         self.target.region.disparity_image.encoding = str[start:end].decode('utf-8')
03562       else:
03563         self.target.region.disparity_image.encoding = str[start:end]
03564       _x = self
03565       start = end
03566       end += 5
03567       (_x.target.region.disparity_image.is_bigendian, _x.target.region.disparity_image.step,) = _struct_BI.unpack(str[start:end])
03568       start = end
03569       end += 4
03570       (length,) = _struct_I.unpack(str[start:end])
03571       start = end
03572       end += length
03573       if python3:
03574         self.target.region.disparity_image.data = str[start:end].decode('utf-8')
03575       else:
03576         self.target.region.disparity_image.data = str[start:end]
03577       _x = self
03578       start = end
03579       end += 12
03580       (_x.target.region.cam_info.header.seq, _x.target.region.cam_info.header.stamp.secs, _x.target.region.cam_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03581       start = end
03582       end += 4
03583       (length,) = _struct_I.unpack(str[start:end])
03584       start = end
03585       end += length
03586       if python3:
03587         self.target.region.cam_info.header.frame_id = str[start:end].decode('utf-8')
03588       else:
03589         self.target.region.cam_info.header.frame_id = str[start:end]
03590       _x = self
03591       start = end
03592       end += 8
03593       (_x.target.region.cam_info.height, _x.target.region.cam_info.width,) = _struct_2I.unpack(str[start:end])
03594       start = end
03595       end += 4
03596       (length,) = _struct_I.unpack(str[start:end])
03597       start = end
03598       end += length
03599       if python3:
03600         self.target.region.cam_info.distortion_model = str[start:end].decode('utf-8')
03601       else:
03602         self.target.region.cam_info.distortion_model = str[start:end]
03603       start = end
03604       end += 4
03605       (length,) = _struct_I.unpack(str[start:end])
03606       pattern = '<%sd'%length
03607       start = end
03608       end += struct.calcsize(pattern)
03609       self.target.region.cam_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03610       start = end
03611       end += 72
03612       self.target.region.cam_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
03613       start = end
03614       end += 72
03615       self.target.region.cam_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
03616       start = end
03617       end += 96
03618       self.target.region.cam_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
03619       _x = self
03620       start = end
03621       end += 37
03622       (_x.target.region.cam_info.binning_x, _x.target.region.cam_info.binning_y, _x.target.region.cam_info.roi.x_offset, _x.target.region.cam_info.roi.y_offset, _x.target.region.cam_info.roi.height, _x.target.region.cam_info.roi.width, _x.target.region.cam_info.roi.do_rectify, _x.target.region.roi_box_pose.header.seq, _x.target.region.roi_box_pose.header.stamp.secs, _x.target.region.roi_box_pose.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
03623       self.target.region.cam_info.roi.do_rectify = bool(self.target.region.cam_info.roi.do_rectify)
03624       start = end
03625       end += 4
03626       (length,) = _struct_I.unpack(str[start:end])
03627       start = end
03628       end += length
03629       if python3:
03630         self.target.region.roi_box_pose.header.frame_id = str[start:end].decode('utf-8')
03631       else:
03632         self.target.region.roi_box_pose.header.frame_id = str[start:end]
03633       _x = self
03634       start = end
03635       end += 80
03636       (_x.target.region.roi_box_pose.pose.position.x, _x.target.region.roi_box_pose.pose.position.y, _x.target.region.roi_box_pose.pose.position.z, _x.target.region.roi_box_pose.pose.orientation.x, _x.target.region.roi_box_pose.pose.orientation.y, _x.target.region.roi_box_pose.pose.orientation.z, _x.target.region.roi_box_pose.pose.orientation.w, _x.target.region.roi_box_dims.x, _x.target.region.roi_box_dims.y, _x.target.region.roi_box_dims.z,) = _struct_10d.unpack(str[start:end])
03637       start = end
03638       end += 4
03639       (length,) = _struct_I.unpack(str[start:end])
03640       start = end
03641       end += length
03642       if python3:
03643         self.target.collision_name = str[start:end].decode('utf-8')
03644       else:
03645         self.target.collision_name = str[start:end]
03646       start = end
03647       end += 4
03648       (length,) = _struct_I.unpack(str[start:end])
03649       start = end
03650       end += length
03651       if python3:
03652         self.collision_object_name = str[start:end].decode('utf-8')
03653       else:
03654         self.collision_object_name = str[start:end]
03655       start = end
03656       end += 4
03657       (length,) = _struct_I.unpack(str[start:end])
03658       start = end
03659       end += length
03660       if python3:
03661         self.collision_support_surface_name = str[start:end].decode('utf-8')
03662       else:
03663         self.collision_support_surface_name = str[start:end]
03664       start = end
03665       end += 4
03666       (length,) = _struct_I.unpack(str[start:end])
03667       self.grasps_to_evaluate = []
03668       for i in range(0, length):
03669         val1 = object_manipulation_msgs.msg.Grasp()
03670         _v232 = val1.pre_grasp_posture
03671         _v233 = _v232.header
03672         start = end
03673         end += 4
03674         (_v233.seq,) = _struct_I.unpack(str[start:end])
03675         _v234 = _v233.stamp
03676         _x = _v234
03677         start = end
03678         end += 8
03679         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03680         start = end
03681         end += 4
03682         (length,) = _struct_I.unpack(str[start:end])
03683         start = end
03684         end += length
03685         if python3:
03686           _v233.frame_id = str[start:end].decode('utf-8')
03687         else:
03688           _v233.frame_id = str[start:end]
03689         start = end
03690         end += 4
03691         (length,) = _struct_I.unpack(str[start:end])
03692         _v232.name = []
03693         for i in range(0, length):
03694           start = end
03695           end += 4
03696           (length,) = _struct_I.unpack(str[start:end])
03697           start = end
03698           end += length
03699           if python3:
03700             val3 = str[start:end].decode('utf-8')
03701           else:
03702             val3 = str[start:end]
03703           _v232.name.append(val3)
03704         start = end
03705         end += 4
03706         (length,) = _struct_I.unpack(str[start:end])
03707         pattern = '<%sd'%length
03708         start = end
03709         end += struct.calcsize(pattern)
03710         _v232.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03711         start = end
03712         end += 4
03713         (length,) = _struct_I.unpack(str[start:end])
03714         pattern = '<%sd'%length
03715         start = end
03716         end += struct.calcsize(pattern)
03717         _v232.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03718         start = end
03719         end += 4
03720         (length,) = _struct_I.unpack(str[start:end])
03721         pattern = '<%sd'%length
03722         start = end
03723         end += struct.calcsize(pattern)
03724         _v232.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03725         _v235 = val1.grasp_posture
03726         _v236 = _v235.header
03727         start = end
03728         end += 4
03729         (_v236.seq,) = _struct_I.unpack(str[start:end])
03730         _v237 = _v236.stamp
03731         _x = _v237
03732         start = end
03733         end += 8
03734         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03735         start = end
03736         end += 4
03737         (length,) = _struct_I.unpack(str[start:end])
03738         start = end
03739         end += length
03740         if python3:
03741           _v236.frame_id = str[start:end].decode('utf-8')
03742         else:
03743           _v236.frame_id = str[start:end]
03744         start = end
03745         end += 4
03746         (length,) = _struct_I.unpack(str[start:end])
03747         _v235.name = []
03748         for i in range(0, length):
03749           start = end
03750           end += 4
03751           (length,) = _struct_I.unpack(str[start:end])
03752           start = end
03753           end += length
03754           if python3:
03755             val3 = str[start:end].decode('utf-8')
03756           else:
03757             val3 = str[start:end]
03758           _v235.name.append(val3)
03759         start = end
03760         end += 4
03761         (length,) = _struct_I.unpack(str[start:end])
03762         pattern = '<%sd'%length
03763         start = end
03764         end += struct.calcsize(pattern)
03765         _v235.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03766         start = end
03767         end += 4
03768         (length,) = _struct_I.unpack(str[start:end])
03769         pattern = '<%sd'%length
03770         start = end
03771         end += struct.calcsize(pattern)
03772         _v235.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03773         start = end
03774         end += 4
03775         (length,) = _struct_I.unpack(str[start:end])
03776         pattern = '<%sd'%length
03777         start = end
03778         end += struct.calcsize(pattern)
03779         _v235.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03780         _v238 = val1.grasp_pose
03781         _v239 = _v238.position
03782         _x = _v239
03783         start = end
03784         end += 24
03785         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03786         _v240 = _v238.orientation
03787         _x = _v240
03788         start = end
03789         end += 32
03790         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03791         _x = val1
03792         start = end
03793         end += 17
03794         (_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance,) = _struct_dB2f.unpack(str[start:end])
03795         val1.cluster_rep = bool(val1.cluster_rep)
03796         start = end
03797         end += 4
03798         (length,) = _struct_I.unpack(str[start:end])
03799         val1.moved_obstacles = []
03800         for i in range(0, length):
03801           val2 = object_manipulation_msgs.msg.GraspableObject()
03802           start = end
03803           end += 4
03804           (length,) = _struct_I.unpack(str[start:end])
03805           start = end
03806           end += length
03807           if python3:
03808             val2.reference_frame_id = str[start:end].decode('utf-8')
03809           else:
03810             val2.reference_frame_id = str[start:end]
03811           start = end
03812           end += 4
03813           (length,) = _struct_I.unpack(str[start:end])
03814           val2.potential_models = []
03815           for i in range(0, length):
03816             val3 = household_objects_database_msgs.msg.DatabaseModelPose()
03817             start = end
03818             end += 4
03819             (val3.model_id,) = _struct_i.unpack(str[start:end])
03820             _v241 = val3.pose
03821             _v242 = _v241.header
03822             start = end
03823             end += 4
03824             (_v242.seq,) = _struct_I.unpack(str[start:end])
03825             _v243 = _v242.stamp
03826             _x = _v243
03827             start = end
03828             end += 8
03829             (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03830             start = end
03831             end += 4
03832             (length,) = _struct_I.unpack(str[start:end])
03833             start = end
03834             end += length
03835             if python3:
03836               _v242.frame_id = str[start:end].decode('utf-8')
03837             else:
03838               _v242.frame_id = str[start:end]
03839             _v244 = _v241.pose
03840             _v245 = _v244.position
03841             _x = _v245
03842             start = end
03843             end += 24
03844             (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03845             _v246 = _v244.orientation
03846             _x = _v246
03847             start = end
03848             end += 32
03849             (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03850             start = end
03851             end += 4
03852             (val3.confidence,) = _struct_f.unpack(str[start:end])
03853             start = end
03854             end += 4
03855             (length,) = _struct_I.unpack(str[start:end])
03856             start = end
03857             end += length
03858             if python3:
03859               val3.detector_name = str[start:end].decode('utf-8')
03860             else:
03861               val3.detector_name = str[start:end]
03862             val2.potential_models.append(val3)
03863           _v247 = val2.cluster
03864           _v248 = _v247.header
03865           start = end
03866           end += 4
03867           (_v248.seq,) = _struct_I.unpack(str[start:end])
03868           _v249 = _v248.stamp
03869           _x = _v249
03870           start = end
03871           end += 8
03872           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03873           start = end
03874           end += 4
03875           (length,) = _struct_I.unpack(str[start:end])
03876           start = end
03877           end += length
03878           if python3:
03879             _v248.frame_id = str[start:end].decode('utf-8')
03880           else:
03881             _v248.frame_id = str[start:end]
03882           start = end
03883           end += 4
03884           (length,) = _struct_I.unpack(str[start:end])
03885           _v247.points = []
03886           for i in range(0, length):
03887             val4 = geometry_msgs.msg.Point32()
03888             _x = val4
03889             start = end
03890             end += 12
03891             (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
03892             _v247.points.append(val4)
03893           start = end
03894           end += 4
03895           (length,) = _struct_I.unpack(str[start:end])
03896           _v247.channels = []
03897           for i in range(0, length):
03898             val4 = sensor_msgs.msg.ChannelFloat32()
03899             start = end
03900             end += 4
03901             (length,) = _struct_I.unpack(str[start:end])
03902             start = end
03903             end += length
03904             if python3:
03905               val4.name = str[start:end].decode('utf-8')
03906             else:
03907               val4.name = str[start:end]
03908             start = end
03909             end += 4
03910             (length,) = _struct_I.unpack(str[start:end])
03911             pattern = '<%sf'%length
03912             start = end
03913             end += struct.calcsize(pattern)
03914             val4.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
03915             _v247.channels.append(val4)
03916           _v250 = val2.region
03917           _v251 = _v250.cloud
03918           _v252 = _v251.header
03919           start = end
03920           end += 4
03921           (_v252.seq,) = _struct_I.unpack(str[start:end])
03922           _v253 = _v252.stamp
03923           _x = _v253
03924           start = end
03925           end += 8
03926           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03927           start = end
03928           end += 4
03929           (length,) = _struct_I.unpack(str[start:end])
03930           start = end
03931           end += length
03932           if python3:
03933             _v252.frame_id = str[start:end].decode('utf-8')
03934           else:
03935             _v252.frame_id = str[start:end]
03936           _x = _v251
03937           start = end
03938           end += 8
03939           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
03940           start = end
03941           end += 4
03942           (length,) = _struct_I.unpack(str[start:end])
03943           _v251.fields = []
03944           for i in range(0, length):
03945             val5 = sensor_msgs.msg.PointField()
03946             start = end
03947             end += 4
03948             (length,) = _struct_I.unpack(str[start:end])
03949             start = end
03950             end += length
03951             if python3:
03952               val5.name = str[start:end].decode('utf-8')
03953             else:
03954               val5.name = str[start:end]
03955             _x = val5
03956             start = end
03957             end += 9
03958             (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
03959             _v251.fields.append(val5)
03960           _x = _v251
03961           start = end
03962           end += 9
03963           (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
03964           _v251.is_bigendian = bool(_v251.is_bigendian)
03965           start = end
03966           end += 4
03967           (length,) = _struct_I.unpack(str[start:end])
03968           start = end
03969           end += length
03970           if python3:
03971             _v251.data = str[start:end].decode('utf-8')
03972           else:
03973             _v251.data = str[start:end]
03974           start = end
03975           end += 1
03976           (_v251.is_dense,) = _struct_B.unpack(str[start:end])
03977           _v251.is_dense = bool(_v251.is_dense)
03978           start = end
03979           end += 4
03980           (length,) = _struct_I.unpack(str[start:end])
03981           pattern = '<%si'%length
03982           start = end
03983           end += struct.calcsize(pattern)
03984           _v250.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
03985           _v254 = _v250.image
03986           _v255 = _v254.header
03987           start = end
03988           end += 4
03989           (_v255.seq,) = _struct_I.unpack(str[start:end])
03990           _v256 = _v255.stamp
03991           _x = _v256
03992           start = end
03993           end += 8
03994           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03995           start = end
03996           end += 4
03997           (length,) = _struct_I.unpack(str[start:end])
03998           start = end
03999           end += length
04000           if python3:
04001             _v255.frame_id = str[start:end].decode('utf-8')
04002           else:
04003             _v255.frame_id = str[start:end]
04004           _x = _v254
04005           start = end
04006           end += 8
04007           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04008           start = end
04009           end += 4
04010           (length,) = _struct_I.unpack(str[start:end])
04011           start = end
04012           end += length
04013           if python3:
04014             _v254.encoding = str[start:end].decode('utf-8')
04015           else:
04016             _v254.encoding = str[start:end]
04017           _x = _v254
04018           start = end
04019           end += 5
04020           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
04021           start = end
04022           end += 4
04023           (length,) = _struct_I.unpack(str[start:end])
04024           start = end
04025           end += length
04026           if python3:
04027             _v254.data = str[start:end].decode('utf-8')
04028           else:
04029             _v254.data = str[start:end]
04030           _v257 = _v250.disparity_image
04031           _v258 = _v257.header
04032           start = end
04033           end += 4
04034           (_v258.seq,) = _struct_I.unpack(str[start:end])
04035           _v259 = _v258.stamp
04036           _x = _v259
04037           start = end
04038           end += 8
04039           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04040           start = end
04041           end += 4
04042           (length,) = _struct_I.unpack(str[start:end])
04043           start = end
04044           end += length
04045           if python3:
04046             _v258.frame_id = str[start:end].decode('utf-8')
04047           else:
04048             _v258.frame_id = str[start:end]
04049           _x = _v257
04050           start = end
04051           end += 8
04052           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04053           start = end
04054           end += 4
04055           (length,) = _struct_I.unpack(str[start:end])
04056           start = end
04057           end += length
04058           if python3:
04059             _v257.encoding = str[start:end].decode('utf-8')
04060           else:
04061             _v257.encoding = str[start:end]
04062           _x = _v257
04063           start = end
04064           end += 5
04065           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
04066           start = end
04067           end += 4
04068           (length,) = _struct_I.unpack(str[start:end])
04069           start = end
04070           end += length
04071           if python3:
04072             _v257.data = str[start:end].decode('utf-8')
04073           else:
04074             _v257.data = str[start:end]
04075           _v260 = _v250.cam_info
04076           _v261 = _v260.header
04077           start = end
04078           end += 4
04079           (_v261.seq,) = _struct_I.unpack(str[start:end])
04080           _v262 = _v261.stamp
04081           _x = _v262
04082           start = end
04083           end += 8
04084           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04085           start = end
04086           end += 4
04087           (length,) = _struct_I.unpack(str[start:end])
04088           start = end
04089           end += length
04090           if python3:
04091             _v261.frame_id = str[start:end].decode('utf-8')
04092           else:
04093             _v261.frame_id = str[start:end]
04094           _x = _v260
04095           start = end
04096           end += 8
04097           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04098           start = end
04099           end += 4
04100           (length,) = _struct_I.unpack(str[start:end])
04101           start = end
04102           end += length
04103           if python3:
04104             _v260.distortion_model = str[start:end].decode('utf-8')
04105           else:
04106             _v260.distortion_model = str[start:end]
04107           start = end
04108           end += 4
04109           (length,) = _struct_I.unpack(str[start:end])
04110           pattern = '<%sd'%length
04111           start = end
04112           end += struct.calcsize(pattern)
04113           _v260.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
04114           start = end
04115           end += 72
04116           _v260.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
04117           start = end
04118           end += 72
04119           _v260.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
04120           start = end
04121           end += 96
04122           _v260.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
04123           _x = _v260
04124           start = end
04125           end += 8
04126           (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
04127           _v263 = _v260.roi
04128           _x = _v263
04129           start = end
04130           end += 17
04131           (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
04132           _v263.do_rectify = bool(_v263.do_rectify)
04133           _v264 = _v250.roi_box_pose
04134           _v265 = _v264.header
04135           start = end
04136           end += 4
04137           (_v265.seq,) = _struct_I.unpack(str[start:end])
04138           _v266 = _v265.stamp
04139           _x = _v266
04140           start = end
04141           end += 8
04142           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04143           start = end
04144           end += 4
04145           (length,) = _struct_I.unpack(str[start:end])
04146           start = end
04147           end += length
04148           if python3:
04149             _v265.frame_id = str[start:end].decode('utf-8')
04150           else:
04151             _v265.frame_id = str[start:end]
04152           _v267 = _v264.pose
04153           _v268 = _v267.position
04154           _x = _v268
04155           start = end
04156           end += 24
04157           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04158           _v269 = _v267.orientation
04159           _x = _v269
04160           start = end
04161           end += 32
04162           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04163           _v270 = _v250.roi_box_dims
04164           _x = _v270
04165           start = end
04166           end += 24
04167           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04168           start = end
04169           end += 4
04170           (length,) = _struct_I.unpack(str[start:end])
04171           start = end
04172           end += length
04173           if python3:
04174             val2.collision_name = str[start:end].decode('utf-8')
04175           else:
04176             val2.collision_name = str[start:end]
04177           val1.moved_obstacles.append(val2)
04178         self.grasps_to_evaluate.append(val1)
04179       start = end
04180       end += 4
04181       (length,) = _struct_I.unpack(str[start:end])
04182       self.movable_obstacles = []
04183       for i in range(0, length):
04184         val1 = object_manipulation_msgs.msg.GraspableObject()
04185         start = end
04186         end += 4
04187         (length,) = _struct_I.unpack(str[start:end])
04188         start = end
04189         end += length
04190         if python3:
04191           val1.reference_frame_id = str[start:end].decode('utf-8')
04192         else:
04193           val1.reference_frame_id = str[start:end]
04194         start = end
04195         end += 4
04196         (length,) = _struct_I.unpack(str[start:end])
04197         val1.potential_models = []
04198         for i in range(0, length):
04199           val2 = household_objects_database_msgs.msg.DatabaseModelPose()
04200           start = end
04201           end += 4
04202           (val2.model_id,) = _struct_i.unpack(str[start:end])
04203           _v271 = val2.pose
04204           _v272 = _v271.header
04205           start = end
04206           end += 4
04207           (_v272.seq,) = _struct_I.unpack(str[start:end])
04208           _v273 = _v272.stamp
04209           _x = _v273
04210           start = end
04211           end += 8
04212           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04213           start = end
04214           end += 4
04215           (length,) = _struct_I.unpack(str[start:end])
04216           start = end
04217           end += length
04218           if python3:
04219             _v272.frame_id = str[start:end].decode('utf-8')
04220           else:
04221             _v272.frame_id = str[start:end]
04222           _v274 = _v271.pose
04223           _v275 = _v274.position
04224           _x = _v275
04225           start = end
04226           end += 24
04227           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04228           _v276 = _v274.orientation
04229           _x = _v276
04230           start = end
04231           end += 32
04232           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04233           start = end
04234           end += 4
04235           (val2.confidence,) = _struct_f.unpack(str[start:end])
04236           start = end
04237           end += 4
04238           (length,) = _struct_I.unpack(str[start:end])
04239           start = end
04240           end += length
04241           if python3:
04242             val2.detector_name = str[start:end].decode('utf-8')
04243           else:
04244             val2.detector_name = str[start:end]
04245           val1.potential_models.append(val2)
04246         _v277 = val1.cluster
04247         _v278 = _v277.header
04248         start = end
04249         end += 4
04250         (_v278.seq,) = _struct_I.unpack(str[start:end])
04251         _v279 = _v278.stamp
04252         _x = _v279
04253         start = end
04254         end += 8
04255         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04256         start = end
04257         end += 4
04258         (length,) = _struct_I.unpack(str[start:end])
04259         start = end
04260         end += length
04261         if python3:
04262           _v278.frame_id = str[start:end].decode('utf-8')
04263         else:
04264           _v278.frame_id = str[start:end]
04265         start = end
04266         end += 4
04267         (length,) = _struct_I.unpack(str[start:end])
04268         _v277.points = []
04269         for i in range(0, length):
04270           val3 = geometry_msgs.msg.Point32()
04271           _x = val3
04272           start = end
04273           end += 12
04274           (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
04275           _v277.points.append(val3)
04276         start = end
04277         end += 4
04278         (length,) = _struct_I.unpack(str[start:end])
04279         _v277.channels = []
04280         for i in range(0, length):
04281           val3 = sensor_msgs.msg.ChannelFloat32()
04282           start = end
04283           end += 4
04284           (length,) = _struct_I.unpack(str[start:end])
04285           start = end
04286           end += length
04287           if python3:
04288             val3.name = str[start:end].decode('utf-8')
04289           else:
04290             val3.name = str[start:end]
04291           start = end
04292           end += 4
04293           (length,) = _struct_I.unpack(str[start:end])
04294           pattern = '<%sf'%length
04295           start = end
04296           end += struct.calcsize(pattern)
04297           val3.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
04298           _v277.channels.append(val3)
04299         _v280 = val1.region
04300         _v281 = _v280.cloud
04301         _v282 = _v281.header
04302         start = end
04303         end += 4
04304         (_v282.seq,) = _struct_I.unpack(str[start:end])
04305         _v283 = _v282.stamp
04306         _x = _v283
04307         start = end
04308         end += 8
04309         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04310         start = end
04311         end += 4
04312         (length,) = _struct_I.unpack(str[start:end])
04313         start = end
04314         end += length
04315         if python3:
04316           _v282.frame_id = str[start:end].decode('utf-8')
04317         else:
04318           _v282.frame_id = str[start:end]
04319         _x = _v281
04320         start = end
04321         end += 8
04322         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04323         start = end
04324         end += 4
04325         (length,) = _struct_I.unpack(str[start:end])
04326         _v281.fields = []
04327         for i in range(0, length):
04328           val4 = sensor_msgs.msg.PointField()
04329           start = end
04330           end += 4
04331           (length,) = _struct_I.unpack(str[start:end])
04332           start = end
04333           end += length
04334           if python3:
04335             val4.name = str[start:end].decode('utf-8')
04336           else:
04337             val4.name = str[start:end]
04338           _x = val4
04339           start = end
04340           end += 9
04341           (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
04342           _v281.fields.append(val4)
04343         _x = _v281
04344         start = end
04345         end += 9
04346         (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
04347         _v281.is_bigendian = bool(_v281.is_bigendian)
04348         start = end
04349         end += 4
04350         (length,) = _struct_I.unpack(str[start:end])
04351         start = end
04352         end += length
04353         if python3:
04354           _v281.data = str[start:end].decode('utf-8')
04355         else:
04356           _v281.data = str[start:end]
04357         start = end
04358         end += 1
04359         (_v281.is_dense,) = _struct_B.unpack(str[start:end])
04360         _v281.is_dense = bool(_v281.is_dense)
04361         start = end
04362         end += 4
04363         (length,) = _struct_I.unpack(str[start:end])
04364         pattern = '<%si'%length
04365         start = end
04366         end += struct.calcsize(pattern)
04367         _v280.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
04368         _v284 = _v280.image
04369         _v285 = _v284.header
04370         start = end
04371         end += 4
04372         (_v285.seq,) = _struct_I.unpack(str[start:end])
04373         _v286 = _v285.stamp
04374         _x = _v286
04375         start = end
04376         end += 8
04377         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04378         start = end
04379         end += 4
04380         (length,) = _struct_I.unpack(str[start:end])
04381         start = end
04382         end += length
04383         if python3:
04384           _v285.frame_id = str[start:end].decode('utf-8')
04385         else:
04386           _v285.frame_id = str[start:end]
04387         _x = _v284
04388         start = end
04389         end += 8
04390         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04391         start = end
04392         end += 4
04393         (length,) = _struct_I.unpack(str[start:end])
04394         start = end
04395         end += length
04396         if python3:
04397           _v284.encoding = str[start:end].decode('utf-8')
04398         else:
04399           _v284.encoding = str[start:end]
04400         _x = _v284
04401         start = end
04402         end += 5
04403         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
04404         start = end
04405         end += 4
04406         (length,) = _struct_I.unpack(str[start:end])
04407         start = end
04408         end += length
04409         if python3:
04410           _v284.data = str[start:end].decode('utf-8')
04411         else:
04412           _v284.data = str[start:end]
04413         _v287 = _v280.disparity_image
04414         _v288 = _v287.header
04415         start = end
04416         end += 4
04417         (_v288.seq,) = _struct_I.unpack(str[start:end])
04418         _v289 = _v288.stamp
04419         _x = _v289
04420         start = end
04421         end += 8
04422         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04423         start = end
04424         end += 4
04425         (length,) = _struct_I.unpack(str[start:end])
04426         start = end
04427         end += length
04428         if python3:
04429           _v288.frame_id = str[start:end].decode('utf-8')
04430         else:
04431           _v288.frame_id = str[start:end]
04432         _x = _v287
04433         start = end
04434         end += 8
04435         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04436         start = end
04437         end += 4
04438         (length,) = _struct_I.unpack(str[start:end])
04439         start = end
04440         end += length
04441         if python3:
04442           _v287.encoding = str[start:end].decode('utf-8')
04443         else:
04444           _v287.encoding = str[start:end]
04445         _x = _v287
04446         start = end
04447         end += 5
04448         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
04449         start = end
04450         end += 4
04451         (length,) = _struct_I.unpack(str[start:end])
04452         start = end
04453         end += length
04454         if python3:
04455           _v287.data = str[start:end].decode('utf-8')
04456         else:
04457           _v287.data = str[start:end]
04458         _v290 = _v280.cam_info
04459         _v291 = _v290.header
04460         start = end
04461         end += 4
04462         (_v291.seq,) = _struct_I.unpack(str[start:end])
04463         _v292 = _v291.stamp
04464         _x = _v292
04465         start = end
04466         end += 8
04467         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04468         start = end
04469         end += 4
04470         (length,) = _struct_I.unpack(str[start:end])
04471         start = end
04472         end += length
04473         if python3:
04474           _v291.frame_id = str[start:end].decode('utf-8')
04475         else:
04476           _v291.frame_id = str[start:end]
04477         _x = _v290
04478         start = end
04479         end += 8
04480         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04481         start = end
04482         end += 4
04483         (length,) = _struct_I.unpack(str[start:end])
04484         start = end
04485         end += length
04486         if python3:
04487           _v290.distortion_model = str[start:end].decode('utf-8')
04488         else:
04489           _v290.distortion_model = str[start:end]
04490         start = end
04491         end += 4
04492         (length,) = _struct_I.unpack(str[start:end])
04493         pattern = '<%sd'%length
04494         start = end
04495         end += struct.calcsize(pattern)
04496         _v290.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
04497         start = end
04498         end += 72
04499         _v290.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
04500         start = end
04501         end += 72
04502         _v290.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
04503         start = end
04504         end += 96
04505         _v290.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
04506         _x = _v290
04507         start = end
04508         end += 8
04509         (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
04510         _v293 = _v290.roi
04511         _x = _v293
04512         start = end
04513         end += 17
04514         (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
04515         _v293.do_rectify = bool(_v293.do_rectify)
04516         _v294 = _v280.roi_box_pose
04517         _v295 = _v294.header
04518         start = end
04519         end += 4
04520         (_v295.seq,) = _struct_I.unpack(str[start:end])
04521         _v296 = _v295.stamp
04522         _x = _v296
04523         start = end
04524         end += 8
04525         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04526         start = end
04527         end += 4
04528         (length,) = _struct_I.unpack(str[start:end])
04529         start = end
04530         end += length
04531         if python3:
04532           _v295.frame_id = str[start:end].decode('utf-8')
04533         else:
04534           _v295.frame_id = str[start:end]
04535         _v297 = _v294.pose
04536         _v298 = _v297.position
04537         _x = _v298
04538         start = end
04539         end += 24
04540         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04541         _v299 = _v297.orientation
04542         _x = _v299
04543         start = end
04544         end += 32
04545         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04546         _v300 = _v280.roi_box_dims
04547         _x = _v300
04548         start = end
04549         end += 24
04550         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04551         start = end
04552         end += 4
04553         (length,) = _struct_I.unpack(str[start:end])
04554         start = end
04555         end += length
04556         if python3:
04557           val1.collision_name = str[start:end].decode('utf-8')
04558         else:
04559           val1.collision_name = str[start:end]
04560         self.movable_obstacles.append(val1)
04561       return self
04562     except struct.error as e:
04563       raise genpy.DeserializationError(e) #most likely buffer underfill
04564 
04565 _struct_I = genpy.struct_I
04566 _struct_IBI = struct.Struct("<IBI")
04567 _struct_6IB3I = struct.Struct("<6IB3I")
04568 _struct_B = struct.Struct("<B")
04569 _struct_12d = struct.Struct("<12d")
04570 _struct_f = struct.Struct("<f")
04571 _struct_i = struct.Struct("<i")
04572 _struct_dB2f = struct.Struct("<dB2f")
04573 _struct_BI = struct.Struct("<BI")
04574 _struct_10d = struct.Struct("<10d")
04575 _struct_3f = struct.Struct("<3f")
04576 _struct_3I = struct.Struct("<3I")
04577 _struct_9d = struct.Struct("<9d")
04578 _struct_B2I = struct.Struct("<B2I")
04579 _struct_4d = struct.Struct("<4d")
04580 _struct_2I = struct.Struct("<2I")
04581 _struct_4IB = struct.Struct("<4IB")
04582 _struct_3d = struct.Struct("<3d")
04583 """autogenerated by genpy from object_manipulation_msgs/GraspPlanningResponse.msg. Do not edit."""
04584 import sys
04585 python3 = True if sys.hexversion > 0x03000000 else False
04586 import genpy
04587 import struct
04588 
04589 import geometry_msgs.msg
04590 import std_msgs.msg
04591 import object_manipulation_msgs.msg
04592 import household_objects_database_msgs.msg
04593 import sensor_msgs.msg
04594 
04595 class GraspPlanningResponse(genpy.Message):
04596   _md5sum = "998e3d06c509abfc46d7fdf96fe1c188"
04597   _type = "object_manipulation_msgs/GraspPlanningResponse"
04598   _has_header = False #flag to mark the presence of a Header object
04599   _full_text = """
04600 
04601 Grasp[] grasps
04602 
04603 
04604 GraspPlanningErrorCode error_code
04605 
04606 
04607 ================================================================================
04608 MSG: object_manipulation_msgs/Grasp
04609 
04610 # The internal posture of the hand for the pre-grasp
04611 # only positions are used
04612 sensor_msgs/JointState pre_grasp_posture
04613 
04614 # The internal posture of the hand for the grasp
04615 # positions and efforts are used
04616 sensor_msgs/JointState grasp_posture
04617 
04618 # The position of the end-effector for the grasp relative to a reference frame 
04619 # (that is always specified elsewhere, not in this message)
04620 geometry_msgs/Pose grasp_pose
04621 
04622 # The estimated probability of success for this grasp
04623 float64 success_probability
04624 
04625 # Debug flag to indicate that this grasp would be the best in its cluster
04626 bool cluster_rep
04627 
04628 # how far the pre-grasp should ideally be away from the grasp
04629 float32 desired_approach_distance
04630 
04631 # how much distance between pre-grasp and grasp must actually be feasible 
04632 # for the grasp not to be rejected
04633 float32 min_approach_distance
04634 
04635 # an optional list of obstacles that we have semantic information about
04636 # and that we expect might move in the course of executing this grasp
04637 # the grasp planner is expected to make sure they move in an OK way; during
04638 # execution, grasp executors will not check for collisions against these objects
04639 GraspableObject[] moved_obstacles
04640 
04641 ================================================================================
04642 MSG: sensor_msgs/JointState
04643 # This is a message that holds data to describe the state of a set of torque controlled joints. 
04644 #
04645 # The state of each joint (revolute or prismatic) is defined by:
04646 #  * the position of the joint (rad or m),
04647 #  * the velocity of the joint (rad/s or m/s) and 
04648 #  * the effort that is applied in the joint (Nm or N).
04649 #
04650 # Each joint is uniquely identified by its name
04651 # The header specifies the time at which the joint states were recorded. All the joint states
04652 # in one message have to be recorded at the same time.
04653 #
04654 # This message consists of a multiple arrays, one for each part of the joint state. 
04655 # The goal is to make each of the fields optional. When e.g. your joints have no
04656 # effort associated with them, you can leave the effort array empty. 
04657 #
04658 # All arrays in this message should have the same size, or be empty.
04659 # This is the only way to uniquely associate the joint name with the correct
04660 # states.
04661 
04662 
04663 Header header
04664 
04665 string[] name
04666 float64[] position
04667 float64[] velocity
04668 float64[] effort
04669 
04670 ================================================================================
04671 MSG: std_msgs/Header
04672 # Standard metadata for higher-level stamped data types.
04673 # This is generally used to communicate timestamped data 
04674 # in a particular coordinate frame.
04675 # 
04676 # sequence ID: consecutively increasing ID 
04677 uint32 seq
04678 #Two-integer timestamp that is expressed as:
04679 # * stamp.secs: seconds (stamp_secs) since epoch
04680 # * stamp.nsecs: nanoseconds since stamp_secs
04681 # time-handling sugar is provided by the client library
04682 time stamp
04683 #Frame this data is associated with
04684 # 0: no frame
04685 # 1: global frame
04686 string frame_id
04687 
04688 ================================================================================
04689 MSG: geometry_msgs/Pose
04690 # A representation of pose in free space, composed of postion and orientation. 
04691 Point position
04692 Quaternion orientation
04693 
04694 ================================================================================
04695 MSG: geometry_msgs/Point
04696 # This contains the position of a point in free space
04697 float64 x
04698 float64 y
04699 float64 z
04700 
04701 ================================================================================
04702 MSG: geometry_msgs/Quaternion
04703 # This represents an orientation in free space in quaternion form.
04704 
04705 float64 x
04706 float64 y
04707 float64 z
04708 float64 w
04709 
04710 ================================================================================
04711 MSG: object_manipulation_msgs/GraspableObject
04712 # an object that the object_manipulator can work on
04713 
04714 # a graspable object can be represented in multiple ways. This message
04715 # can contain all of them. Which one is actually used is up to the receiver
04716 # of this message. When adding new representations, one must be careful that
04717 # they have reasonable lightweight defaults indicating that that particular
04718 # representation is not available.
04719 
04720 # the tf frame to be used as a reference frame when combining information from
04721 # the different representations below
04722 string reference_frame_id
04723 
04724 # potential recognition results from a database of models
04725 # all poses are relative to the object reference pose
04726 household_objects_database_msgs/DatabaseModelPose[] potential_models
04727 
04728 # the point cloud itself
04729 sensor_msgs/PointCloud cluster
04730 
04731 # a region of a PointCloud2 of interest
04732 object_manipulation_msgs/SceneRegion region
04733 
04734 # the name that this object has in the collision environment
04735 string collision_name
04736 ================================================================================
04737 MSG: household_objects_database_msgs/DatabaseModelPose
04738 # Informs that a specific model from the Model Database has been 
04739 # identified at a certain location
04740 
04741 # the database id of the model
04742 int32 model_id
04743 
04744 # the pose that it can be found in
04745 geometry_msgs/PoseStamped pose
04746 
04747 # a measure of the confidence level in this detection result
04748 float32 confidence
04749 
04750 # the name of the object detector that generated this detection result
04751 string detector_name
04752 
04753 ================================================================================
04754 MSG: geometry_msgs/PoseStamped
04755 # A Pose with reference coordinate frame and timestamp
04756 Header header
04757 Pose pose
04758 
04759 ================================================================================
04760 MSG: sensor_msgs/PointCloud
04761 # This message holds a collection of 3d points, plus optional additional
04762 # information about each point.
04763 
04764 # Time of sensor data acquisition, coordinate frame ID.
04765 Header header
04766 
04767 # Array of 3d points. Each Point32 should be interpreted as a 3d point
04768 # in the frame given in the header.
04769 geometry_msgs/Point32[] points
04770 
04771 # Each channel should have the same number of elements as points array,
04772 # and the data in each channel should correspond 1:1 with each point.
04773 # Channel names in common practice are listed in ChannelFloat32.msg.
04774 ChannelFloat32[] channels
04775 
04776 ================================================================================
04777 MSG: geometry_msgs/Point32
04778 # This contains the position of a point in free space(with 32 bits of precision).
04779 # It is recommeded to use Point wherever possible instead of Point32.  
04780 # 
04781 # This recommendation is to promote interoperability.  
04782 #
04783 # This message is designed to take up less space when sending
04784 # lots of points at once, as in the case of a PointCloud.  
04785 
04786 float32 x
04787 float32 y
04788 float32 z
04789 ================================================================================
04790 MSG: sensor_msgs/ChannelFloat32
04791 # This message is used by the PointCloud message to hold optional data
04792 # associated with each point in the cloud. The length of the values
04793 # array should be the same as the length of the points array in the
04794 # PointCloud, and each value should be associated with the corresponding
04795 # point.
04796 
04797 # Channel names in existing practice include:
04798 #   "u", "v" - row and column (respectively) in the left stereo image.
04799 #              This is opposite to usual conventions but remains for
04800 #              historical reasons. The newer PointCloud2 message has no
04801 #              such problem.
04802 #   "rgb" - For point clouds produced by color stereo cameras. uint8
04803 #           (R,G,B) values packed into the least significant 24 bits,
04804 #           in order.
04805 #   "intensity" - laser or pixel intensity.
04806 #   "distance"
04807 
04808 # The channel name should give semantics of the channel (e.g.
04809 # "intensity" instead of "value").
04810 string name
04811 
04812 # The values array should be 1-1 with the elements of the associated
04813 # PointCloud.
04814 float32[] values
04815 
04816 ================================================================================
04817 MSG: object_manipulation_msgs/SceneRegion
04818 # Point cloud
04819 sensor_msgs/PointCloud2 cloud
04820 
04821 # Indices for the region of interest
04822 int32[] mask
04823 
04824 # One of the corresponding 2D images, if applicable
04825 sensor_msgs/Image image
04826 
04827 # The disparity image, if applicable
04828 sensor_msgs/Image disparity_image
04829 
04830 # Camera info for the camera that took the image
04831 sensor_msgs/CameraInfo cam_info
04832 
04833 # a 3D region of interest for grasp planning
04834 geometry_msgs/PoseStamped  roi_box_pose
04835 geometry_msgs/Vector3      roi_box_dims
04836 
04837 ================================================================================
04838 MSG: sensor_msgs/PointCloud2
04839 # This message holds a collection of N-dimensional points, which may
04840 # contain additional information such as normals, intensity, etc. The
04841 # point data is stored as a binary blob, its layout described by the
04842 # contents of the "fields" array.
04843 
04844 # The point cloud data may be organized 2d (image-like) or 1d
04845 # (unordered). Point clouds organized as 2d images may be produced by
04846 # camera depth sensors such as stereo or time-of-flight.
04847 
04848 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
04849 # points).
04850 Header header
04851 
04852 # 2D structure of the point cloud. If the cloud is unordered, height is
04853 # 1 and width is the length of the point cloud.
04854 uint32 height
04855 uint32 width
04856 
04857 # Describes the channels and their layout in the binary data blob.
04858 PointField[] fields
04859 
04860 bool    is_bigendian # Is this data bigendian?
04861 uint32  point_step   # Length of a point in bytes
04862 uint32  row_step     # Length of a row in bytes
04863 uint8[] data         # Actual point data, size is (row_step*height)
04864 
04865 bool is_dense        # True if there are no invalid points
04866 
04867 ================================================================================
04868 MSG: sensor_msgs/PointField
04869 # This message holds the description of one point entry in the
04870 # PointCloud2 message format.
04871 uint8 INT8    = 1
04872 uint8 UINT8   = 2
04873 uint8 INT16   = 3
04874 uint8 UINT16  = 4
04875 uint8 INT32   = 5
04876 uint8 UINT32  = 6
04877 uint8 FLOAT32 = 7
04878 uint8 FLOAT64 = 8
04879 
04880 string name      # Name of field
04881 uint32 offset    # Offset from start of point struct
04882 uint8  datatype  # Datatype enumeration, see above
04883 uint32 count     # How many elements in the field
04884 
04885 ================================================================================
04886 MSG: sensor_msgs/Image
04887 # This message contains an uncompressed image
04888 # (0, 0) is at top-left corner of image
04889 #
04890 
04891 Header header        # Header timestamp should be acquisition time of image
04892                      # Header frame_id should be optical frame of camera
04893                      # origin of frame should be optical center of cameara
04894                      # +x should point to the right in the image
04895                      # +y should point down in the image
04896                      # +z should point into to plane of the image
04897                      # If the frame_id here and the frame_id of the CameraInfo
04898                      # message associated with the image conflict
04899                      # the behavior is undefined
04900 
04901 uint32 height         # image height, that is, number of rows
04902 uint32 width          # image width, that is, number of columns
04903 
04904 # The legal values for encoding are in file src/image_encodings.cpp
04905 # If you want to standardize a new string format, join
04906 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
04907 
04908 string encoding       # Encoding of pixels -- channel meaning, ordering, size
04909                       # taken from the list of strings in src/image_encodings.cpp
04910 
04911 uint8 is_bigendian    # is this data bigendian?
04912 uint32 step           # Full row length in bytes
04913 uint8[] data          # actual matrix data, size is (step * rows)
04914 
04915 ================================================================================
04916 MSG: sensor_msgs/CameraInfo
04917 # This message defines meta information for a camera. It should be in a
04918 # camera namespace on topic "camera_info" and accompanied by up to five
04919 # image topics named:
04920 #
04921 #   image_raw - raw data from the camera driver, possibly Bayer encoded
04922 #   image            - monochrome, distorted
04923 #   image_color      - color, distorted
04924 #   image_rect       - monochrome, rectified
04925 #   image_rect_color - color, rectified
04926 #
04927 # The image_pipeline contains packages (image_proc, stereo_image_proc)
04928 # for producing the four processed image topics from image_raw and
04929 # camera_info. The meaning of the camera parameters are described in
04930 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
04931 #
04932 # The image_geometry package provides a user-friendly interface to
04933 # common operations using this meta information. If you want to, e.g.,
04934 # project a 3d point into image coordinates, we strongly recommend
04935 # using image_geometry.
04936 #
04937 # If the camera is uncalibrated, the matrices D, K, R, P should be left
04938 # zeroed out. In particular, clients may assume that K[0] == 0.0
04939 # indicates an uncalibrated camera.
04940 
04941 #######################################################################
04942 #                     Image acquisition info                          #
04943 #######################################################################
04944 
04945 # Time of image acquisition, camera coordinate frame ID
04946 Header header    # Header timestamp should be acquisition time of image
04947                  # Header frame_id should be optical frame of camera
04948                  # origin of frame should be optical center of camera
04949                  # +x should point to the right in the image
04950                  # +y should point down in the image
04951                  # +z should point into the plane of the image
04952 
04953 
04954 #######################################################################
04955 #                      Calibration Parameters                         #
04956 #######################################################################
04957 # These are fixed during camera calibration. Their values will be the #
04958 # same in all messages until the camera is recalibrated. Note that    #
04959 # self-calibrating systems may "recalibrate" frequently.              #
04960 #                                                                     #
04961 # The internal parameters can be used to warp a raw (distorted) image #
04962 # to:                                                                 #
04963 #   1. An undistorted image (requires D and K)                        #
04964 #   2. A rectified image (requires D, K, R)                           #
04965 # The projection matrix P projects 3D points into the rectified image.#
04966 #######################################################################
04967 
04968 # The image dimensions with which the camera was calibrated. Normally
04969 # this will be the full camera resolution in pixels.
04970 uint32 height
04971 uint32 width
04972 
04973 # The distortion model used. Supported models are listed in
04974 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
04975 # simple model of radial and tangential distortion - is sufficent.
04976 string distortion_model
04977 
04978 # The distortion parameters, size depending on the distortion model.
04979 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
04980 float64[] D
04981 
04982 # Intrinsic camera matrix for the raw (distorted) images.
04983 #     [fx  0 cx]
04984 # K = [ 0 fy cy]
04985 #     [ 0  0  1]
04986 # Projects 3D points in the camera coordinate frame to 2D pixel
04987 # coordinates using the focal lengths (fx, fy) and principal point
04988 # (cx, cy).
04989 float64[9]  K # 3x3 row-major matrix
04990 
04991 # Rectification matrix (stereo cameras only)
04992 # A rotation matrix aligning the camera coordinate system to the ideal
04993 # stereo image plane so that epipolar lines in both stereo images are
04994 # parallel.
04995 float64[9]  R # 3x3 row-major matrix
04996 
04997 # Projection/camera matrix
04998 #     [fx'  0  cx' Tx]
04999 # P = [ 0  fy' cy' Ty]
05000 #     [ 0   0   1   0]
05001 # By convention, this matrix specifies the intrinsic (camera) matrix
05002 #  of the processed (rectified) image. That is, the left 3x3 portion
05003 #  is the normal camera intrinsic matrix for the rectified image.
05004 # It projects 3D points in the camera coordinate frame to 2D pixel
05005 #  coordinates using the focal lengths (fx', fy') and principal point
05006 #  (cx', cy') - these may differ from the values in K.
05007 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
05008 #  also have R = the identity and P[1:3,1:3] = K.
05009 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
05010 #  position of the optical center of the second camera in the first
05011 #  camera's frame. We assume Tz = 0 so both cameras are in the same
05012 #  stereo image plane. The first camera always has Tx = Ty = 0. For
05013 #  the right (second) camera of a horizontal stereo pair, Ty = 0 and
05014 #  Tx = -fx' * B, where B is the baseline between the cameras.
05015 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
05016 #  the rectified image is given by:
05017 #  [u v w]' = P * [X Y Z 1]'
05018 #         x = u / w
05019 #         y = v / w
05020 #  This holds for both images of a stereo pair.
05021 float64[12] P # 3x4 row-major matrix
05022 
05023 
05024 #######################################################################
05025 #                      Operational Parameters                         #
05026 #######################################################################
05027 # These define the image region actually captured by the camera       #
05028 # driver. Although they affect the geometry of the output image, they #
05029 # may be changed freely without recalibrating the camera.             #
05030 #######################################################################
05031 
05032 # Binning refers here to any camera setting which combines rectangular
05033 #  neighborhoods of pixels into larger "super-pixels." It reduces the
05034 #  resolution of the output image to
05035 #  (width / binning_x) x (height / binning_y).
05036 # The default values binning_x = binning_y = 0 is considered the same
05037 #  as binning_x = binning_y = 1 (no subsampling).
05038 uint32 binning_x
05039 uint32 binning_y
05040 
05041 # Region of interest (subwindow of full camera resolution), given in
05042 #  full resolution (unbinned) image coordinates. A particular ROI
05043 #  always denotes the same window of pixels on the camera sensor,
05044 #  regardless of binning settings.
05045 # The default setting of roi (all values 0) is considered the same as
05046 #  full resolution (roi.width = width, roi.height = height).
05047 RegionOfInterest roi
05048 
05049 ================================================================================
05050 MSG: sensor_msgs/RegionOfInterest
05051 # This message is used to specify a region of interest within an image.
05052 #
05053 # When used to specify the ROI setting of the camera when the image was
05054 # taken, the height and width fields should either match the height and
05055 # width fields for the associated image; or height = width = 0
05056 # indicates that the full resolution image was captured.
05057 
05058 uint32 x_offset  # Leftmost pixel of the ROI
05059                  # (0 if the ROI includes the left edge of the image)
05060 uint32 y_offset  # Topmost pixel of the ROI
05061                  # (0 if the ROI includes the top edge of the image)
05062 uint32 height    # Height of ROI
05063 uint32 width     # Width of ROI
05064 
05065 # True if a distinct rectified ROI should be calculated from the "raw"
05066 # ROI in this message. Typically this should be False if the full image
05067 # is captured (ROI not used), and True if a subwindow is captured (ROI
05068 # used).
05069 bool do_rectify
05070 
05071 ================================================================================
05072 MSG: geometry_msgs/Vector3
05073 # This represents a vector in free space. 
05074 
05075 float64 x
05076 float64 y
05077 float64 z
05078 ================================================================================
05079 MSG: object_manipulation_msgs/GraspPlanningErrorCode
05080 # Error codes for grasp and place planning
05081 
05082 # plan completed as expected
05083 int32 SUCCESS = 0
05084 
05085 # tf error encountered while transforming
05086 int32 TF_ERROR = 1 
05087 
05088 # some other error
05089 int32 OTHER_ERROR = 2
05090 
05091 # the actual value of this error code
05092 int32 value
05093 """
05094   __slots__ = ['grasps','error_code']
05095   _slot_types = ['object_manipulation_msgs/Grasp[]','object_manipulation_msgs/GraspPlanningErrorCode']
05096 
05097   def __init__(self, *args, **kwds):
05098     """
05099     Constructor. Any message fields that are implicitly/explicitly
05100     set to None will be assigned a default value. The recommend
05101     use is keyword arguments as this is more robust to future message
05102     changes.  You cannot mix in-order arguments and keyword arguments.
05103 
05104     The available fields are:
05105        grasps,error_code
05106 
05107     :param args: complete set of field values, in .msg order
05108     :param kwds: use keyword arguments corresponding to message field names
05109     to set specific fields.
05110     """
05111     if args or kwds:
05112       super(GraspPlanningResponse, self).__init__(*args, **kwds)
05113       #message fields cannot be None, assign default values for those that are
05114       if self.grasps is None:
05115         self.grasps = []
05116       if self.error_code is None:
05117         self.error_code = object_manipulation_msgs.msg.GraspPlanningErrorCode()
05118     else:
05119       self.grasps = []
05120       self.error_code = object_manipulation_msgs.msg.GraspPlanningErrorCode()
05121 
05122   def _get_types(self):
05123     """
05124     internal API method
05125     """
05126     return self._slot_types
05127 
05128   def serialize(self, buff):
05129     """
05130     serialize message into buffer
05131     :param buff: buffer, ``StringIO``
05132     """
05133     try:
05134       length = len(self.grasps)
05135       buff.write(_struct_I.pack(length))
05136       for val1 in self.grasps:
05137         _v301 = val1.pre_grasp_posture
05138         _v302 = _v301.header
05139         buff.write(_struct_I.pack(_v302.seq))
05140         _v303 = _v302.stamp
05141         _x = _v303
05142         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05143         _x = _v302.frame_id
05144         length = len(_x)
05145         if python3 or type(_x) == unicode:
05146           _x = _x.encode('utf-8')
05147           length = len(_x)
05148         buff.write(struct.pack('<I%ss'%length, length, _x))
05149         length = len(_v301.name)
05150         buff.write(_struct_I.pack(length))
05151         for val3 in _v301.name:
05152           length = len(val3)
05153           if python3 or type(val3) == unicode:
05154             val3 = val3.encode('utf-8')
05155             length = len(val3)
05156           buff.write(struct.pack('<I%ss'%length, length, val3))
05157         length = len(_v301.position)
05158         buff.write(_struct_I.pack(length))
05159         pattern = '<%sd'%length
05160         buff.write(struct.pack(pattern, *_v301.position))
05161         length = len(_v301.velocity)
05162         buff.write(_struct_I.pack(length))
05163         pattern = '<%sd'%length
05164         buff.write(struct.pack(pattern, *_v301.velocity))
05165         length = len(_v301.effort)
05166         buff.write(_struct_I.pack(length))
05167         pattern = '<%sd'%length
05168         buff.write(struct.pack(pattern, *_v301.effort))
05169         _v304 = val1.grasp_posture
05170         _v305 = _v304.header
05171         buff.write(_struct_I.pack(_v305.seq))
05172         _v306 = _v305.stamp
05173         _x = _v306
05174         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05175         _x = _v305.frame_id
05176         length = len(_x)
05177         if python3 or type(_x) == unicode:
05178           _x = _x.encode('utf-8')
05179           length = len(_x)
05180         buff.write(struct.pack('<I%ss'%length, length, _x))
05181         length = len(_v304.name)
05182         buff.write(_struct_I.pack(length))
05183         for val3 in _v304.name:
05184           length = len(val3)
05185           if python3 or type(val3) == unicode:
05186             val3 = val3.encode('utf-8')
05187             length = len(val3)
05188           buff.write(struct.pack('<I%ss'%length, length, val3))
05189         length = len(_v304.position)
05190         buff.write(_struct_I.pack(length))
05191         pattern = '<%sd'%length
05192         buff.write(struct.pack(pattern, *_v304.position))
05193         length = len(_v304.velocity)
05194         buff.write(_struct_I.pack(length))
05195         pattern = '<%sd'%length
05196         buff.write(struct.pack(pattern, *_v304.velocity))
05197         length = len(_v304.effort)
05198         buff.write(_struct_I.pack(length))
05199         pattern = '<%sd'%length
05200         buff.write(struct.pack(pattern, *_v304.effort))
05201         _v307 = val1.grasp_pose
05202         _v308 = _v307.position
05203         _x = _v308
05204         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
05205         _v309 = _v307.orientation
05206         _x = _v309
05207         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
05208         _x = val1
05209         buff.write(_struct_dB2f.pack(_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance))
05210         length = len(val1.moved_obstacles)
05211         buff.write(_struct_I.pack(length))
05212         for val2 in val1.moved_obstacles:
05213           _x = val2.reference_frame_id
05214           length = len(_x)
05215           if python3 or type(_x) == unicode:
05216             _x = _x.encode('utf-8')
05217             length = len(_x)
05218           buff.write(struct.pack('<I%ss'%length, length, _x))
05219           length = len(val2.potential_models)
05220           buff.write(_struct_I.pack(length))
05221           for val3 in val2.potential_models:
05222             buff.write(_struct_i.pack(val3.model_id))
05223             _v310 = val3.pose
05224             _v311 = _v310.header
05225             buff.write(_struct_I.pack(_v311.seq))
05226             _v312 = _v311.stamp
05227             _x = _v312
05228             buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05229             _x = _v311.frame_id
05230             length = len(_x)
05231             if python3 or type(_x) == unicode:
05232               _x = _x.encode('utf-8')
05233               length = len(_x)
05234             buff.write(struct.pack('<I%ss'%length, length, _x))
05235             _v313 = _v310.pose
05236             _v314 = _v313.position
05237             _x = _v314
05238             buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
05239             _v315 = _v313.orientation
05240             _x = _v315
05241             buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
05242             buff.write(_struct_f.pack(val3.confidence))
05243             _x = val3.detector_name
05244             length = len(_x)
05245             if python3 or type(_x) == unicode:
05246               _x = _x.encode('utf-8')
05247               length = len(_x)
05248             buff.write(struct.pack('<I%ss'%length, length, _x))
05249           _v316 = val2.cluster
05250           _v317 = _v316.header
05251           buff.write(_struct_I.pack(_v317.seq))
05252           _v318 = _v317.stamp
05253           _x = _v318
05254           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05255           _x = _v317.frame_id
05256           length = len(_x)
05257           if python3 or type(_x) == unicode:
05258             _x = _x.encode('utf-8')
05259             length = len(_x)
05260           buff.write(struct.pack('<I%ss'%length, length, _x))
05261           length = len(_v316.points)
05262           buff.write(_struct_I.pack(length))
05263           for val4 in _v316.points:
05264             _x = val4
05265             buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
05266           length = len(_v316.channels)
05267           buff.write(_struct_I.pack(length))
05268           for val4 in _v316.channels:
05269             _x = val4.name
05270             length = len(_x)
05271             if python3 or type(_x) == unicode:
05272               _x = _x.encode('utf-8')
05273               length = len(_x)
05274             buff.write(struct.pack('<I%ss'%length, length, _x))
05275             length = len(val4.values)
05276             buff.write(_struct_I.pack(length))
05277             pattern = '<%sf'%length
05278             buff.write(struct.pack(pattern, *val4.values))
05279           _v319 = val2.region
05280           _v320 = _v319.cloud
05281           _v321 = _v320.header
05282           buff.write(_struct_I.pack(_v321.seq))
05283           _v322 = _v321.stamp
05284           _x = _v322
05285           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05286           _x = _v321.frame_id
05287           length = len(_x)
05288           if python3 or type(_x) == unicode:
05289             _x = _x.encode('utf-8')
05290             length = len(_x)
05291           buff.write(struct.pack('<I%ss'%length, length, _x))
05292           _x = _v320
05293           buff.write(_struct_2I.pack(_x.height, _x.width))
05294           length = len(_v320.fields)
05295           buff.write(_struct_I.pack(length))
05296           for val5 in _v320.fields:
05297             _x = val5.name
05298             length = len(_x)
05299             if python3 or type(_x) == unicode:
05300               _x = _x.encode('utf-8')
05301               length = len(_x)
05302             buff.write(struct.pack('<I%ss'%length, length, _x))
05303             _x = val5
05304             buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
05305           _x = _v320
05306           buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
05307           _x = _v320.data
05308           length = len(_x)
05309           # - if encoded as a list instead, serialize as bytes instead of string
05310           if type(_x) in [list, tuple]:
05311             buff.write(struct.pack('<I%sB'%length, length, *_x))
05312           else:
05313             buff.write(struct.pack('<I%ss'%length, length, _x))
05314           buff.write(_struct_B.pack(_v320.is_dense))
05315           length = len(_v319.mask)
05316           buff.write(_struct_I.pack(length))
05317           pattern = '<%si'%length
05318           buff.write(struct.pack(pattern, *_v319.mask))
05319           _v323 = _v319.image
05320           _v324 = _v323.header
05321           buff.write(_struct_I.pack(_v324.seq))
05322           _v325 = _v324.stamp
05323           _x = _v325
05324           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05325           _x = _v324.frame_id
05326           length = len(_x)
05327           if python3 or type(_x) == unicode:
05328             _x = _x.encode('utf-8')
05329             length = len(_x)
05330           buff.write(struct.pack('<I%ss'%length, length, _x))
05331           _x = _v323
05332           buff.write(_struct_2I.pack(_x.height, _x.width))
05333           _x = _v323.encoding
05334           length = len(_x)
05335           if python3 or type(_x) == unicode:
05336             _x = _x.encode('utf-8')
05337             length = len(_x)
05338           buff.write(struct.pack('<I%ss'%length, length, _x))
05339           _x = _v323
05340           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
05341           _x = _v323.data
05342           length = len(_x)
05343           # - if encoded as a list instead, serialize as bytes instead of string
05344           if type(_x) in [list, tuple]:
05345             buff.write(struct.pack('<I%sB'%length, length, *_x))
05346           else:
05347             buff.write(struct.pack('<I%ss'%length, length, _x))
05348           _v326 = _v319.disparity_image
05349           _v327 = _v326.header
05350           buff.write(_struct_I.pack(_v327.seq))
05351           _v328 = _v327.stamp
05352           _x = _v328
05353           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05354           _x = _v327.frame_id
05355           length = len(_x)
05356           if python3 or type(_x) == unicode:
05357             _x = _x.encode('utf-8')
05358             length = len(_x)
05359           buff.write(struct.pack('<I%ss'%length, length, _x))
05360           _x = _v326
05361           buff.write(_struct_2I.pack(_x.height, _x.width))
05362           _x = _v326.encoding
05363           length = len(_x)
05364           if python3 or type(_x) == unicode:
05365             _x = _x.encode('utf-8')
05366             length = len(_x)
05367           buff.write(struct.pack('<I%ss'%length, length, _x))
05368           _x = _v326
05369           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
05370           _x = _v326.data
05371           length = len(_x)
05372           # - if encoded as a list instead, serialize as bytes instead of string
05373           if type(_x) in [list, tuple]:
05374             buff.write(struct.pack('<I%sB'%length, length, *_x))
05375           else:
05376             buff.write(struct.pack('<I%ss'%length, length, _x))
05377           _v329 = _v319.cam_info
05378           _v330 = _v329.header
05379           buff.write(_struct_I.pack(_v330.seq))
05380           _v331 = _v330.stamp
05381           _x = _v331
05382           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05383           _x = _v330.frame_id
05384           length = len(_x)
05385           if python3 or type(_x) == unicode:
05386             _x = _x.encode('utf-8')
05387             length = len(_x)
05388           buff.write(struct.pack('<I%ss'%length, length, _x))
05389           _x = _v329
05390           buff.write(_struct_2I.pack(_x.height, _x.width))
05391           _x = _v329.distortion_model
05392           length = len(_x)
05393           if python3 or type(_x) == unicode:
05394             _x = _x.encode('utf-8')
05395             length = len(_x)
05396           buff.write(struct.pack('<I%ss'%length, length, _x))
05397           length = len(_v329.D)
05398           buff.write(_struct_I.pack(length))
05399           pattern = '<%sd'%length
05400           buff.write(struct.pack(pattern, *_v329.D))
05401           buff.write(_struct_9d.pack(*_v329.K))
05402           buff.write(_struct_9d.pack(*_v329.R))
05403           buff.write(_struct_12d.pack(*_v329.P))
05404           _x = _v329
05405           buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
05406           _v332 = _v329.roi
05407           _x = _v332
05408           buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
05409           _v333 = _v319.roi_box_pose
05410           _v334 = _v333.header
05411           buff.write(_struct_I.pack(_v334.seq))
05412           _v335 = _v334.stamp
05413           _x = _v335
05414           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05415           _x = _v334.frame_id
05416           length = len(_x)
05417           if python3 or type(_x) == unicode:
05418             _x = _x.encode('utf-8')
05419             length = len(_x)
05420           buff.write(struct.pack('<I%ss'%length, length, _x))
05421           _v336 = _v333.pose
05422           _v337 = _v336.position
05423           _x = _v337
05424           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
05425           _v338 = _v336.orientation
05426           _x = _v338
05427           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
05428           _v339 = _v319.roi_box_dims
05429           _x = _v339
05430           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
05431           _x = val2.collision_name
05432           length = len(_x)
05433           if python3 or type(_x) == unicode:
05434             _x = _x.encode('utf-8')
05435             length = len(_x)
05436           buff.write(struct.pack('<I%ss'%length, length, _x))
05437       buff.write(_struct_i.pack(self.error_code.value))
05438     except struct.error as se: self._check_types(se)
05439     except TypeError as te: self._check_types(te)
05440 
05441   def deserialize(self, str):
05442     """
05443     unpack serialized message in str into this message instance
05444     :param str: byte array of serialized message, ``str``
05445     """
05446     try:
05447       if self.grasps is None:
05448         self.grasps = None
05449       if self.error_code is None:
05450         self.error_code = object_manipulation_msgs.msg.GraspPlanningErrorCode()
05451       end = 0
05452       start = end
05453       end += 4
05454       (length,) = _struct_I.unpack(str[start:end])
05455       self.grasps = []
05456       for i in range(0, length):
05457         val1 = object_manipulation_msgs.msg.Grasp()
05458         _v340 = val1.pre_grasp_posture
05459         _v341 = _v340.header
05460         start = end
05461         end += 4
05462         (_v341.seq,) = _struct_I.unpack(str[start:end])
05463         _v342 = _v341.stamp
05464         _x = _v342
05465         start = end
05466         end += 8
05467         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
05468         start = end
05469         end += 4
05470         (length,) = _struct_I.unpack(str[start:end])
05471         start = end
05472         end += length
05473         if python3:
05474           _v341.frame_id = str[start:end].decode('utf-8')
05475         else:
05476           _v341.frame_id = str[start:end]
05477         start = end
05478         end += 4
05479         (length,) = _struct_I.unpack(str[start:end])
05480         _v340.name = []
05481         for i in range(0, length):
05482           start = end
05483           end += 4
05484           (length,) = _struct_I.unpack(str[start:end])
05485           start = end
05486           end += length
05487           if python3:
05488             val3 = str[start:end].decode('utf-8')
05489           else:
05490             val3 = str[start:end]
05491           _v340.name.append(val3)
05492         start = end
05493         end += 4
05494         (length,) = _struct_I.unpack(str[start:end])
05495         pattern = '<%sd'%length
05496         start = end
05497         end += struct.calcsize(pattern)
05498         _v340.position = struct.unpack(pattern, str[start:end])
05499         start = end
05500         end += 4
05501         (length,) = _struct_I.unpack(str[start:end])
05502         pattern = '<%sd'%length
05503         start = end
05504         end += struct.calcsize(pattern)
05505         _v340.velocity = struct.unpack(pattern, str[start:end])
05506         start = end
05507         end += 4
05508         (length,) = _struct_I.unpack(str[start:end])
05509         pattern = '<%sd'%length
05510         start = end
05511         end += struct.calcsize(pattern)
05512         _v340.effort = struct.unpack(pattern, str[start:end])
05513         _v343 = val1.grasp_posture
05514         _v344 = _v343.header
05515         start = end
05516         end += 4
05517         (_v344.seq,) = _struct_I.unpack(str[start:end])
05518         _v345 = _v344.stamp
05519         _x = _v345
05520         start = end
05521         end += 8
05522         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
05523         start = end
05524         end += 4
05525         (length,) = _struct_I.unpack(str[start:end])
05526         start = end
05527         end += length
05528         if python3:
05529           _v344.frame_id = str[start:end].decode('utf-8')
05530         else:
05531           _v344.frame_id = str[start:end]
05532         start = end
05533         end += 4
05534         (length,) = _struct_I.unpack(str[start:end])
05535         _v343.name = []
05536         for i in range(0, length):
05537           start = end
05538           end += 4
05539           (length,) = _struct_I.unpack(str[start:end])
05540           start = end
05541           end += length
05542           if python3:
05543             val3 = str[start:end].decode('utf-8')
05544           else:
05545             val3 = str[start:end]
05546           _v343.name.append(val3)
05547         start = end
05548         end += 4
05549         (length,) = _struct_I.unpack(str[start:end])
05550         pattern = '<%sd'%length
05551         start = end
05552         end += struct.calcsize(pattern)
05553         _v343.position = struct.unpack(pattern, str[start:end])
05554         start = end
05555         end += 4
05556         (length,) = _struct_I.unpack(str[start:end])
05557         pattern = '<%sd'%length
05558         start = end
05559         end += struct.calcsize(pattern)
05560         _v343.velocity = struct.unpack(pattern, str[start:end])
05561         start = end
05562         end += 4
05563         (length,) = _struct_I.unpack(str[start:end])
05564         pattern = '<%sd'%length
05565         start = end
05566         end += struct.calcsize(pattern)
05567         _v343.effort = struct.unpack(pattern, str[start:end])
05568         _v346 = val1.grasp_pose
05569         _v347 = _v346.position
05570         _x = _v347
05571         start = end
05572         end += 24
05573         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
05574         _v348 = _v346.orientation
05575         _x = _v348
05576         start = end
05577         end += 32
05578         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
05579         _x = val1
05580         start = end
05581         end += 17
05582         (_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance,) = _struct_dB2f.unpack(str[start:end])
05583         val1.cluster_rep = bool(val1.cluster_rep)
05584         start = end
05585         end += 4
05586         (length,) = _struct_I.unpack(str[start:end])
05587         val1.moved_obstacles = []
05588         for i in range(0, length):
05589           val2 = object_manipulation_msgs.msg.GraspableObject()
05590           start = end
05591           end += 4
05592           (length,) = _struct_I.unpack(str[start:end])
05593           start = end
05594           end += length
05595           if python3:
05596             val2.reference_frame_id = str[start:end].decode('utf-8')
05597           else:
05598             val2.reference_frame_id = str[start:end]
05599           start = end
05600           end += 4
05601           (length,) = _struct_I.unpack(str[start:end])
05602           val2.potential_models = []
05603           for i in range(0, length):
05604             val3 = household_objects_database_msgs.msg.DatabaseModelPose()
05605             start = end
05606             end += 4
05607             (val3.model_id,) = _struct_i.unpack(str[start:end])
05608             _v349 = val3.pose
05609             _v350 = _v349.header
05610             start = end
05611             end += 4
05612             (_v350.seq,) = _struct_I.unpack(str[start:end])
05613             _v351 = _v350.stamp
05614             _x = _v351
05615             start = end
05616             end += 8
05617             (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
05618             start = end
05619             end += 4
05620             (length,) = _struct_I.unpack(str[start:end])
05621             start = end
05622             end += length
05623             if python3:
05624               _v350.frame_id = str[start:end].decode('utf-8')
05625             else:
05626               _v350.frame_id = str[start:end]
05627             _v352 = _v349.pose
05628             _v353 = _v352.position
05629             _x = _v353
05630             start = end
05631             end += 24
05632             (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
05633             _v354 = _v352.orientation
05634             _x = _v354
05635             start = end
05636             end += 32
05637             (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
05638             start = end
05639             end += 4
05640             (val3.confidence,) = _struct_f.unpack(str[start:end])
05641             start = end
05642             end += 4
05643             (length,) = _struct_I.unpack(str[start:end])
05644             start = end
05645             end += length
05646             if python3:
05647               val3.detector_name = str[start:end].decode('utf-8')
05648             else:
05649               val3.detector_name = str[start:end]
05650             val2.potential_models.append(val3)
05651           _v355 = val2.cluster
05652           _v356 = _v355.header
05653           start = end
05654           end += 4
05655           (_v356.seq,) = _struct_I.unpack(str[start:end])
05656           _v357 = _v356.stamp
05657           _x = _v357
05658           start = end
05659           end += 8
05660           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
05661           start = end
05662           end += 4
05663           (length,) = _struct_I.unpack(str[start:end])
05664           start = end
05665           end += length
05666           if python3:
05667             _v356.frame_id = str[start:end].decode('utf-8')
05668           else:
05669             _v356.frame_id = str[start:end]
05670           start = end
05671           end += 4
05672           (length,) = _struct_I.unpack(str[start:end])
05673           _v355.points = []
05674           for i in range(0, length):
05675             val4 = geometry_msgs.msg.Point32()
05676             _x = val4
05677             start = end
05678             end += 12
05679             (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
05680             _v355.points.append(val4)
05681           start = end
05682           end += 4
05683           (length,) = _struct_I.unpack(str[start:end])
05684           _v355.channels = []
05685           for i in range(0, length):
05686             val4 = sensor_msgs.msg.ChannelFloat32()
05687             start = end
05688             end += 4
05689             (length,) = _struct_I.unpack(str[start:end])
05690             start = end
05691             end += length
05692             if python3:
05693               val4.name = str[start:end].decode('utf-8')
05694             else:
05695               val4.name = str[start:end]
05696             start = end
05697             end += 4
05698             (length,) = _struct_I.unpack(str[start:end])
05699             pattern = '<%sf'%length
05700             start = end
05701             end += struct.calcsize(pattern)
05702             val4.values = struct.unpack(pattern, str[start:end])
05703             _v355.channels.append(val4)
05704           _v358 = val2.region
05705           _v359 = _v358.cloud
05706           _v360 = _v359.header
05707           start = end
05708           end += 4
05709           (_v360.seq,) = _struct_I.unpack(str[start:end])
05710           _v361 = _v360.stamp
05711           _x = _v361
05712           start = end
05713           end += 8
05714           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
05715           start = end
05716           end += 4
05717           (length,) = _struct_I.unpack(str[start:end])
05718           start = end
05719           end += length
05720           if python3:
05721             _v360.frame_id = str[start:end].decode('utf-8')
05722           else:
05723             _v360.frame_id = str[start:end]
05724           _x = _v359
05725           start = end
05726           end += 8
05727           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
05728           start = end
05729           end += 4
05730           (length,) = _struct_I.unpack(str[start:end])
05731           _v359.fields = []
05732           for i in range(0, length):
05733             val5 = sensor_msgs.msg.PointField()
05734             start = end
05735             end += 4
05736             (length,) = _struct_I.unpack(str[start:end])
05737             start = end
05738             end += length
05739             if python3:
05740               val5.name = str[start:end].decode('utf-8')
05741             else:
05742               val5.name = str[start:end]
05743             _x = val5
05744             start = end
05745             end += 9
05746             (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
05747             _v359.fields.append(val5)
05748           _x = _v359
05749           start = end
05750           end += 9
05751           (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
05752           _v359.is_bigendian = bool(_v359.is_bigendian)
05753           start = end
05754           end += 4
05755           (length,) = _struct_I.unpack(str[start:end])
05756           start = end
05757           end += length
05758           if python3:
05759             _v359.data = str[start:end].decode('utf-8')
05760           else:
05761             _v359.data = str[start:end]
05762           start = end
05763           end += 1
05764           (_v359.is_dense,) = _struct_B.unpack(str[start:end])
05765           _v359.is_dense = bool(_v359.is_dense)
05766           start = end
05767           end += 4
05768           (length,) = _struct_I.unpack(str[start:end])
05769           pattern = '<%si'%length
05770           start = end
05771           end += struct.calcsize(pattern)
05772           _v358.mask = struct.unpack(pattern, str[start:end])
05773           _v362 = _v358.image
05774           _v363 = _v362.header
05775           start = end
05776           end += 4
05777           (_v363.seq,) = _struct_I.unpack(str[start:end])
05778           _v364 = _v363.stamp
05779           _x = _v364
05780           start = end
05781           end += 8
05782           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
05783           start = end
05784           end += 4
05785           (length,) = _struct_I.unpack(str[start:end])
05786           start = end
05787           end += length
05788           if python3:
05789             _v363.frame_id = str[start:end].decode('utf-8')
05790           else:
05791             _v363.frame_id = str[start:end]
05792           _x = _v362
05793           start = end
05794           end += 8
05795           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
05796           start = end
05797           end += 4
05798           (length,) = _struct_I.unpack(str[start:end])
05799           start = end
05800           end += length
05801           if python3:
05802             _v362.encoding = str[start:end].decode('utf-8')
05803           else:
05804             _v362.encoding = str[start:end]
05805           _x = _v362
05806           start = end
05807           end += 5
05808           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
05809           start = end
05810           end += 4
05811           (length,) = _struct_I.unpack(str[start:end])
05812           start = end
05813           end += length
05814           if python3:
05815             _v362.data = str[start:end].decode('utf-8')
05816           else:
05817             _v362.data = str[start:end]
05818           _v365 = _v358.disparity_image
05819           _v366 = _v365.header
05820           start = end
05821           end += 4
05822           (_v366.seq,) = _struct_I.unpack(str[start:end])
05823           _v367 = _v366.stamp
05824           _x = _v367
05825           start = end
05826           end += 8
05827           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
05828           start = end
05829           end += 4
05830           (length,) = _struct_I.unpack(str[start:end])
05831           start = end
05832           end += length
05833           if python3:
05834             _v366.frame_id = str[start:end].decode('utf-8')
05835           else:
05836             _v366.frame_id = str[start:end]
05837           _x = _v365
05838           start = end
05839           end += 8
05840           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
05841           start = end
05842           end += 4
05843           (length,) = _struct_I.unpack(str[start:end])
05844           start = end
05845           end += length
05846           if python3:
05847             _v365.encoding = str[start:end].decode('utf-8')
05848           else:
05849             _v365.encoding = str[start:end]
05850           _x = _v365
05851           start = end
05852           end += 5
05853           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
05854           start = end
05855           end += 4
05856           (length,) = _struct_I.unpack(str[start:end])
05857           start = end
05858           end += length
05859           if python3:
05860             _v365.data = str[start:end].decode('utf-8')
05861           else:
05862             _v365.data = str[start:end]
05863           _v368 = _v358.cam_info
05864           _v369 = _v368.header
05865           start = end
05866           end += 4
05867           (_v369.seq,) = _struct_I.unpack(str[start:end])
05868           _v370 = _v369.stamp
05869           _x = _v370
05870           start = end
05871           end += 8
05872           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
05873           start = end
05874           end += 4
05875           (length,) = _struct_I.unpack(str[start:end])
05876           start = end
05877           end += length
05878           if python3:
05879             _v369.frame_id = str[start:end].decode('utf-8')
05880           else:
05881             _v369.frame_id = str[start:end]
05882           _x = _v368
05883           start = end
05884           end += 8
05885           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
05886           start = end
05887           end += 4
05888           (length,) = _struct_I.unpack(str[start:end])
05889           start = end
05890           end += length
05891           if python3:
05892             _v368.distortion_model = str[start:end].decode('utf-8')
05893           else:
05894             _v368.distortion_model = str[start:end]
05895           start = end
05896           end += 4
05897           (length,) = _struct_I.unpack(str[start:end])
05898           pattern = '<%sd'%length
05899           start = end
05900           end += struct.calcsize(pattern)
05901           _v368.D = struct.unpack(pattern, str[start:end])
05902           start = end
05903           end += 72
05904           _v368.K = _struct_9d.unpack(str[start:end])
05905           start = end
05906           end += 72
05907           _v368.R = _struct_9d.unpack(str[start:end])
05908           start = end
05909           end += 96
05910           _v368.P = _struct_12d.unpack(str[start:end])
05911           _x = _v368
05912           start = end
05913           end += 8
05914           (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
05915           _v371 = _v368.roi
05916           _x = _v371
05917           start = end
05918           end += 17
05919           (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
05920           _v371.do_rectify = bool(_v371.do_rectify)
05921           _v372 = _v358.roi_box_pose
05922           _v373 = _v372.header
05923           start = end
05924           end += 4
05925           (_v373.seq,) = _struct_I.unpack(str[start:end])
05926           _v374 = _v373.stamp
05927           _x = _v374
05928           start = end
05929           end += 8
05930           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
05931           start = end
05932           end += 4
05933           (length,) = _struct_I.unpack(str[start:end])
05934           start = end
05935           end += length
05936           if python3:
05937             _v373.frame_id = str[start:end].decode('utf-8')
05938           else:
05939             _v373.frame_id = str[start:end]
05940           _v375 = _v372.pose
05941           _v376 = _v375.position
05942           _x = _v376
05943           start = end
05944           end += 24
05945           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
05946           _v377 = _v375.orientation
05947           _x = _v377
05948           start = end
05949           end += 32
05950           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
05951           _v378 = _v358.roi_box_dims
05952           _x = _v378
05953           start = end
05954           end += 24
05955           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
05956           start = end
05957           end += 4
05958           (length,) = _struct_I.unpack(str[start:end])
05959           start = end
05960           end += length
05961           if python3:
05962             val2.collision_name = str[start:end].decode('utf-8')
05963           else:
05964             val2.collision_name = str[start:end]
05965           val1.moved_obstacles.append(val2)
05966         self.grasps.append(val1)
05967       start = end
05968       end += 4
05969       (self.error_code.value,) = _struct_i.unpack(str[start:end])
05970       return self
05971     except struct.error as e:
05972       raise genpy.DeserializationError(e) #most likely buffer underfill
05973 
05974 
05975   def serialize_numpy(self, buff, numpy):
05976     """
05977     serialize message with numpy array types into buffer
05978     :param buff: buffer, ``StringIO``
05979     :param numpy: numpy python module
05980     """
05981     try:
05982       length = len(self.grasps)
05983       buff.write(_struct_I.pack(length))
05984       for val1 in self.grasps:
05985         _v379 = val1.pre_grasp_posture
05986         _v380 = _v379.header
05987         buff.write(_struct_I.pack(_v380.seq))
05988         _v381 = _v380.stamp
05989         _x = _v381
05990         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05991         _x = _v380.frame_id
05992         length = len(_x)
05993         if python3 or type(_x) == unicode:
05994           _x = _x.encode('utf-8')
05995           length = len(_x)
05996         buff.write(struct.pack('<I%ss'%length, length, _x))
05997         length = len(_v379.name)
05998         buff.write(_struct_I.pack(length))
05999         for val3 in _v379.name:
06000           length = len(val3)
06001           if python3 or type(val3) == unicode:
06002             val3 = val3.encode('utf-8')
06003             length = len(val3)
06004           buff.write(struct.pack('<I%ss'%length, length, val3))
06005         length = len(_v379.position)
06006         buff.write(_struct_I.pack(length))
06007         pattern = '<%sd'%length
06008         buff.write(_v379.position.tostring())
06009         length = len(_v379.velocity)
06010         buff.write(_struct_I.pack(length))
06011         pattern = '<%sd'%length
06012         buff.write(_v379.velocity.tostring())
06013         length = len(_v379.effort)
06014         buff.write(_struct_I.pack(length))
06015         pattern = '<%sd'%length
06016         buff.write(_v379.effort.tostring())
06017         _v382 = val1.grasp_posture
06018         _v383 = _v382.header
06019         buff.write(_struct_I.pack(_v383.seq))
06020         _v384 = _v383.stamp
06021         _x = _v384
06022         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06023         _x = _v383.frame_id
06024         length = len(_x)
06025         if python3 or type(_x) == unicode:
06026           _x = _x.encode('utf-8')
06027           length = len(_x)
06028         buff.write(struct.pack('<I%ss'%length, length, _x))
06029         length = len(_v382.name)
06030         buff.write(_struct_I.pack(length))
06031         for val3 in _v382.name:
06032           length = len(val3)
06033           if python3 or type(val3) == unicode:
06034             val3 = val3.encode('utf-8')
06035             length = len(val3)
06036           buff.write(struct.pack('<I%ss'%length, length, val3))
06037         length = len(_v382.position)
06038         buff.write(_struct_I.pack(length))
06039         pattern = '<%sd'%length
06040         buff.write(_v382.position.tostring())
06041         length = len(_v382.velocity)
06042         buff.write(_struct_I.pack(length))
06043         pattern = '<%sd'%length
06044         buff.write(_v382.velocity.tostring())
06045         length = len(_v382.effort)
06046         buff.write(_struct_I.pack(length))
06047         pattern = '<%sd'%length
06048         buff.write(_v382.effort.tostring())
06049         _v385 = val1.grasp_pose
06050         _v386 = _v385.position
06051         _x = _v386
06052         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
06053         _v387 = _v385.orientation
06054         _x = _v387
06055         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
06056         _x = val1
06057         buff.write(_struct_dB2f.pack(_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance))
06058         length = len(val1.moved_obstacles)
06059         buff.write(_struct_I.pack(length))
06060         for val2 in val1.moved_obstacles:
06061           _x = val2.reference_frame_id
06062           length = len(_x)
06063           if python3 or type(_x) == unicode:
06064             _x = _x.encode('utf-8')
06065             length = len(_x)
06066           buff.write(struct.pack('<I%ss'%length, length, _x))
06067           length = len(val2.potential_models)
06068           buff.write(_struct_I.pack(length))
06069           for val3 in val2.potential_models:
06070             buff.write(_struct_i.pack(val3.model_id))
06071             _v388 = val3.pose
06072             _v389 = _v388.header
06073             buff.write(_struct_I.pack(_v389.seq))
06074             _v390 = _v389.stamp
06075             _x = _v390
06076             buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06077             _x = _v389.frame_id
06078             length = len(_x)
06079             if python3 or type(_x) == unicode:
06080               _x = _x.encode('utf-8')
06081               length = len(_x)
06082             buff.write(struct.pack('<I%ss'%length, length, _x))
06083             _v391 = _v388.pose
06084             _v392 = _v391.position
06085             _x = _v392
06086             buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
06087             _v393 = _v391.orientation
06088             _x = _v393
06089             buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
06090             buff.write(_struct_f.pack(val3.confidence))
06091             _x = val3.detector_name
06092             length = len(_x)
06093             if python3 or type(_x) == unicode:
06094               _x = _x.encode('utf-8')
06095               length = len(_x)
06096             buff.write(struct.pack('<I%ss'%length, length, _x))
06097           _v394 = val2.cluster
06098           _v395 = _v394.header
06099           buff.write(_struct_I.pack(_v395.seq))
06100           _v396 = _v395.stamp
06101           _x = _v396
06102           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06103           _x = _v395.frame_id
06104           length = len(_x)
06105           if python3 or type(_x) == unicode:
06106             _x = _x.encode('utf-8')
06107             length = len(_x)
06108           buff.write(struct.pack('<I%ss'%length, length, _x))
06109           length = len(_v394.points)
06110           buff.write(_struct_I.pack(length))
06111           for val4 in _v394.points:
06112             _x = val4
06113             buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
06114           length = len(_v394.channels)
06115           buff.write(_struct_I.pack(length))
06116           for val4 in _v394.channels:
06117             _x = val4.name
06118             length = len(_x)
06119             if python3 or type(_x) == unicode:
06120               _x = _x.encode('utf-8')
06121               length = len(_x)
06122             buff.write(struct.pack('<I%ss'%length, length, _x))
06123             length = len(val4.values)
06124             buff.write(_struct_I.pack(length))
06125             pattern = '<%sf'%length
06126             buff.write(val4.values.tostring())
06127           _v397 = val2.region
06128           _v398 = _v397.cloud
06129           _v399 = _v398.header
06130           buff.write(_struct_I.pack(_v399.seq))
06131           _v400 = _v399.stamp
06132           _x = _v400
06133           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06134           _x = _v399.frame_id
06135           length = len(_x)
06136           if python3 or type(_x) == unicode:
06137             _x = _x.encode('utf-8')
06138             length = len(_x)
06139           buff.write(struct.pack('<I%ss'%length, length, _x))
06140           _x = _v398
06141           buff.write(_struct_2I.pack(_x.height, _x.width))
06142           length = len(_v398.fields)
06143           buff.write(_struct_I.pack(length))
06144           for val5 in _v398.fields:
06145             _x = val5.name
06146             length = len(_x)
06147             if python3 or type(_x) == unicode:
06148               _x = _x.encode('utf-8')
06149               length = len(_x)
06150             buff.write(struct.pack('<I%ss'%length, length, _x))
06151             _x = val5
06152             buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
06153           _x = _v398
06154           buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
06155           _x = _v398.data
06156           length = len(_x)
06157           # - if encoded as a list instead, serialize as bytes instead of string
06158           if type(_x) in [list, tuple]:
06159             buff.write(struct.pack('<I%sB'%length, length, *_x))
06160           else:
06161             buff.write(struct.pack('<I%ss'%length, length, _x))
06162           buff.write(_struct_B.pack(_v398.is_dense))
06163           length = len(_v397.mask)
06164           buff.write(_struct_I.pack(length))
06165           pattern = '<%si'%length
06166           buff.write(_v397.mask.tostring())
06167           _v401 = _v397.image
06168           _v402 = _v401.header
06169           buff.write(_struct_I.pack(_v402.seq))
06170           _v403 = _v402.stamp
06171           _x = _v403
06172           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06173           _x = _v402.frame_id
06174           length = len(_x)
06175           if python3 or type(_x) == unicode:
06176             _x = _x.encode('utf-8')
06177             length = len(_x)
06178           buff.write(struct.pack('<I%ss'%length, length, _x))
06179           _x = _v401
06180           buff.write(_struct_2I.pack(_x.height, _x.width))
06181           _x = _v401.encoding
06182           length = len(_x)
06183           if python3 or type(_x) == unicode:
06184             _x = _x.encode('utf-8')
06185             length = len(_x)
06186           buff.write(struct.pack('<I%ss'%length, length, _x))
06187           _x = _v401
06188           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
06189           _x = _v401.data
06190           length = len(_x)
06191           # - if encoded as a list instead, serialize as bytes instead of string
06192           if type(_x) in [list, tuple]:
06193             buff.write(struct.pack('<I%sB'%length, length, *_x))
06194           else:
06195             buff.write(struct.pack('<I%ss'%length, length, _x))
06196           _v404 = _v397.disparity_image
06197           _v405 = _v404.header
06198           buff.write(_struct_I.pack(_v405.seq))
06199           _v406 = _v405.stamp
06200           _x = _v406
06201           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06202           _x = _v405.frame_id
06203           length = len(_x)
06204           if python3 or type(_x) == unicode:
06205             _x = _x.encode('utf-8')
06206             length = len(_x)
06207           buff.write(struct.pack('<I%ss'%length, length, _x))
06208           _x = _v404
06209           buff.write(_struct_2I.pack(_x.height, _x.width))
06210           _x = _v404.encoding
06211           length = len(_x)
06212           if python3 or type(_x) == unicode:
06213             _x = _x.encode('utf-8')
06214             length = len(_x)
06215           buff.write(struct.pack('<I%ss'%length, length, _x))
06216           _x = _v404
06217           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
06218           _x = _v404.data
06219           length = len(_x)
06220           # - if encoded as a list instead, serialize as bytes instead of string
06221           if type(_x) in [list, tuple]:
06222             buff.write(struct.pack('<I%sB'%length, length, *_x))
06223           else:
06224             buff.write(struct.pack('<I%ss'%length, length, _x))
06225           _v407 = _v397.cam_info
06226           _v408 = _v407.header
06227           buff.write(_struct_I.pack(_v408.seq))
06228           _v409 = _v408.stamp
06229           _x = _v409
06230           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06231           _x = _v408.frame_id
06232           length = len(_x)
06233           if python3 or type(_x) == unicode:
06234             _x = _x.encode('utf-8')
06235             length = len(_x)
06236           buff.write(struct.pack('<I%ss'%length, length, _x))
06237           _x = _v407
06238           buff.write(_struct_2I.pack(_x.height, _x.width))
06239           _x = _v407.distortion_model
06240           length = len(_x)
06241           if python3 or type(_x) == unicode:
06242             _x = _x.encode('utf-8')
06243             length = len(_x)
06244           buff.write(struct.pack('<I%ss'%length, length, _x))
06245           length = len(_v407.D)
06246           buff.write(_struct_I.pack(length))
06247           pattern = '<%sd'%length
06248           buff.write(_v407.D.tostring())
06249           buff.write(_v407.K.tostring())
06250           buff.write(_v407.R.tostring())
06251           buff.write(_v407.P.tostring())
06252           _x = _v407
06253           buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
06254           _v410 = _v407.roi
06255           _x = _v410
06256           buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
06257           _v411 = _v397.roi_box_pose
06258           _v412 = _v411.header
06259           buff.write(_struct_I.pack(_v412.seq))
06260           _v413 = _v412.stamp
06261           _x = _v413
06262           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06263           _x = _v412.frame_id
06264           length = len(_x)
06265           if python3 or type(_x) == unicode:
06266             _x = _x.encode('utf-8')
06267             length = len(_x)
06268           buff.write(struct.pack('<I%ss'%length, length, _x))
06269           _v414 = _v411.pose
06270           _v415 = _v414.position
06271           _x = _v415
06272           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
06273           _v416 = _v414.orientation
06274           _x = _v416
06275           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
06276           _v417 = _v397.roi_box_dims
06277           _x = _v417
06278           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
06279           _x = val2.collision_name
06280           length = len(_x)
06281           if python3 or type(_x) == unicode:
06282             _x = _x.encode('utf-8')
06283             length = len(_x)
06284           buff.write(struct.pack('<I%ss'%length, length, _x))
06285       buff.write(_struct_i.pack(self.error_code.value))
06286     except struct.error as se: self._check_types(se)
06287     except TypeError as te: self._check_types(te)
06288 
06289   def deserialize_numpy(self, str, numpy):
06290     """
06291     unpack serialized message in str into this message instance using numpy for array types
06292     :param str: byte array of serialized message, ``str``
06293     :param numpy: numpy python module
06294     """
06295     try:
06296       if self.grasps is None:
06297         self.grasps = None
06298       if self.error_code is None:
06299         self.error_code = object_manipulation_msgs.msg.GraspPlanningErrorCode()
06300       end = 0
06301       start = end
06302       end += 4
06303       (length,) = _struct_I.unpack(str[start:end])
06304       self.grasps = []
06305       for i in range(0, length):
06306         val1 = object_manipulation_msgs.msg.Grasp()
06307         _v418 = val1.pre_grasp_posture
06308         _v419 = _v418.header
06309         start = end
06310         end += 4
06311         (_v419.seq,) = _struct_I.unpack(str[start:end])
06312         _v420 = _v419.stamp
06313         _x = _v420
06314         start = end
06315         end += 8
06316         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
06317         start = end
06318         end += 4
06319         (length,) = _struct_I.unpack(str[start:end])
06320         start = end
06321         end += length
06322         if python3:
06323           _v419.frame_id = str[start:end].decode('utf-8')
06324         else:
06325           _v419.frame_id = str[start:end]
06326         start = end
06327         end += 4
06328         (length,) = _struct_I.unpack(str[start:end])
06329         _v418.name = []
06330         for i in range(0, length):
06331           start = end
06332           end += 4
06333           (length,) = _struct_I.unpack(str[start:end])
06334           start = end
06335           end += length
06336           if python3:
06337             val3 = str[start:end].decode('utf-8')
06338           else:
06339             val3 = str[start:end]
06340           _v418.name.append(val3)
06341         start = end
06342         end += 4
06343         (length,) = _struct_I.unpack(str[start:end])
06344         pattern = '<%sd'%length
06345         start = end
06346         end += struct.calcsize(pattern)
06347         _v418.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
06348         start = end
06349         end += 4
06350         (length,) = _struct_I.unpack(str[start:end])
06351         pattern = '<%sd'%length
06352         start = end
06353         end += struct.calcsize(pattern)
06354         _v418.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
06355         start = end
06356         end += 4
06357         (length,) = _struct_I.unpack(str[start:end])
06358         pattern = '<%sd'%length
06359         start = end
06360         end += struct.calcsize(pattern)
06361         _v418.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
06362         _v421 = val1.grasp_posture
06363         _v422 = _v421.header
06364         start = end
06365         end += 4
06366         (_v422.seq,) = _struct_I.unpack(str[start:end])
06367         _v423 = _v422.stamp
06368         _x = _v423
06369         start = end
06370         end += 8
06371         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
06372         start = end
06373         end += 4
06374         (length,) = _struct_I.unpack(str[start:end])
06375         start = end
06376         end += length
06377         if python3:
06378           _v422.frame_id = str[start:end].decode('utf-8')
06379         else:
06380           _v422.frame_id = str[start:end]
06381         start = end
06382         end += 4
06383         (length,) = _struct_I.unpack(str[start:end])
06384         _v421.name = []
06385         for i in range(0, length):
06386           start = end
06387           end += 4
06388           (length,) = _struct_I.unpack(str[start:end])
06389           start = end
06390           end += length
06391           if python3:
06392             val3 = str[start:end].decode('utf-8')
06393           else:
06394             val3 = str[start:end]
06395           _v421.name.append(val3)
06396         start = end
06397         end += 4
06398         (length,) = _struct_I.unpack(str[start:end])
06399         pattern = '<%sd'%length
06400         start = end
06401         end += struct.calcsize(pattern)
06402         _v421.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
06403         start = end
06404         end += 4
06405         (length,) = _struct_I.unpack(str[start:end])
06406         pattern = '<%sd'%length
06407         start = end
06408         end += struct.calcsize(pattern)
06409         _v421.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
06410         start = end
06411         end += 4
06412         (length,) = _struct_I.unpack(str[start:end])
06413         pattern = '<%sd'%length
06414         start = end
06415         end += struct.calcsize(pattern)
06416         _v421.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
06417         _v424 = val1.grasp_pose
06418         _v425 = _v424.position
06419         _x = _v425
06420         start = end
06421         end += 24
06422         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
06423         _v426 = _v424.orientation
06424         _x = _v426
06425         start = end
06426         end += 32
06427         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
06428         _x = val1
06429         start = end
06430         end += 17
06431         (_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance,) = _struct_dB2f.unpack(str[start:end])
06432         val1.cluster_rep = bool(val1.cluster_rep)
06433         start = end
06434         end += 4
06435         (length,) = _struct_I.unpack(str[start:end])
06436         val1.moved_obstacles = []
06437         for i in range(0, length):
06438           val2 = object_manipulation_msgs.msg.GraspableObject()
06439           start = end
06440           end += 4
06441           (length,) = _struct_I.unpack(str[start:end])
06442           start = end
06443           end += length
06444           if python3:
06445             val2.reference_frame_id = str[start:end].decode('utf-8')
06446           else:
06447             val2.reference_frame_id = str[start:end]
06448           start = end
06449           end += 4
06450           (length,) = _struct_I.unpack(str[start:end])
06451           val2.potential_models = []
06452           for i in range(0, length):
06453             val3 = household_objects_database_msgs.msg.DatabaseModelPose()
06454             start = end
06455             end += 4
06456             (val3.model_id,) = _struct_i.unpack(str[start:end])
06457             _v427 = val3.pose
06458             _v428 = _v427.header
06459             start = end
06460             end += 4
06461             (_v428.seq,) = _struct_I.unpack(str[start:end])
06462             _v429 = _v428.stamp
06463             _x = _v429
06464             start = end
06465             end += 8
06466             (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
06467             start = end
06468             end += 4
06469             (length,) = _struct_I.unpack(str[start:end])
06470             start = end
06471             end += length
06472             if python3:
06473               _v428.frame_id = str[start:end].decode('utf-8')
06474             else:
06475               _v428.frame_id = str[start:end]
06476             _v430 = _v427.pose
06477             _v431 = _v430.position
06478             _x = _v431
06479             start = end
06480             end += 24
06481             (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
06482             _v432 = _v430.orientation
06483             _x = _v432
06484             start = end
06485             end += 32
06486             (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
06487             start = end
06488             end += 4
06489             (val3.confidence,) = _struct_f.unpack(str[start:end])
06490             start = end
06491             end += 4
06492             (length,) = _struct_I.unpack(str[start:end])
06493             start = end
06494             end += length
06495             if python3:
06496               val3.detector_name = str[start:end].decode('utf-8')
06497             else:
06498               val3.detector_name = str[start:end]
06499             val2.potential_models.append(val3)
06500           _v433 = val2.cluster
06501           _v434 = _v433.header
06502           start = end
06503           end += 4
06504           (_v434.seq,) = _struct_I.unpack(str[start:end])
06505           _v435 = _v434.stamp
06506           _x = _v435
06507           start = end
06508           end += 8
06509           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
06510           start = end
06511           end += 4
06512           (length,) = _struct_I.unpack(str[start:end])
06513           start = end
06514           end += length
06515           if python3:
06516             _v434.frame_id = str[start:end].decode('utf-8')
06517           else:
06518             _v434.frame_id = str[start:end]
06519           start = end
06520           end += 4
06521           (length,) = _struct_I.unpack(str[start:end])
06522           _v433.points = []
06523           for i in range(0, length):
06524             val4 = geometry_msgs.msg.Point32()
06525             _x = val4
06526             start = end
06527             end += 12
06528             (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
06529             _v433.points.append(val4)
06530           start = end
06531           end += 4
06532           (length,) = _struct_I.unpack(str[start:end])
06533           _v433.channels = []
06534           for i in range(0, length):
06535             val4 = sensor_msgs.msg.ChannelFloat32()
06536             start = end
06537             end += 4
06538             (length,) = _struct_I.unpack(str[start:end])
06539             start = end
06540             end += length
06541             if python3:
06542               val4.name = str[start:end].decode('utf-8')
06543             else:
06544               val4.name = str[start:end]
06545             start = end
06546             end += 4
06547             (length,) = _struct_I.unpack(str[start:end])
06548             pattern = '<%sf'%length
06549             start = end
06550             end += struct.calcsize(pattern)
06551             val4.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
06552             _v433.channels.append(val4)
06553           _v436 = val2.region
06554           _v437 = _v436.cloud
06555           _v438 = _v437.header
06556           start = end
06557           end += 4
06558           (_v438.seq,) = _struct_I.unpack(str[start:end])
06559           _v439 = _v438.stamp
06560           _x = _v439
06561           start = end
06562           end += 8
06563           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
06564           start = end
06565           end += 4
06566           (length,) = _struct_I.unpack(str[start:end])
06567           start = end
06568           end += length
06569           if python3:
06570             _v438.frame_id = str[start:end].decode('utf-8')
06571           else:
06572             _v438.frame_id = str[start:end]
06573           _x = _v437
06574           start = end
06575           end += 8
06576           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
06577           start = end
06578           end += 4
06579           (length,) = _struct_I.unpack(str[start:end])
06580           _v437.fields = []
06581           for i in range(0, length):
06582             val5 = sensor_msgs.msg.PointField()
06583             start = end
06584             end += 4
06585             (length,) = _struct_I.unpack(str[start:end])
06586             start = end
06587             end += length
06588             if python3:
06589               val5.name = str[start:end].decode('utf-8')
06590             else:
06591               val5.name = str[start:end]
06592             _x = val5
06593             start = end
06594             end += 9
06595             (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
06596             _v437.fields.append(val5)
06597           _x = _v437
06598           start = end
06599           end += 9
06600           (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
06601           _v437.is_bigendian = bool(_v437.is_bigendian)
06602           start = end
06603           end += 4
06604           (length,) = _struct_I.unpack(str[start:end])
06605           start = end
06606           end += length
06607           if python3:
06608             _v437.data = str[start:end].decode('utf-8')
06609           else:
06610             _v437.data = str[start:end]
06611           start = end
06612           end += 1
06613           (_v437.is_dense,) = _struct_B.unpack(str[start:end])
06614           _v437.is_dense = bool(_v437.is_dense)
06615           start = end
06616           end += 4
06617           (length,) = _struct_I.unpack(str[start:end])
06618           pattern = '<%si'%length
06619           start = end
06620           end += struct.calcsize(pattern)
06621           _v436.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
06622           _v440 = _v436.image
06623           _v441 = _v440.header
06624           start = end
06625           end += 4
06626           (_v441.seq,) = _struct_I.unpack(str[start:end])
06627           _v442 = _v441.stamp
06628           _x = _v442
06629           start = end
06630           end += 8
06631           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
06632           start = end
06633           end += 4
06634           (length,) = _struct_I.unpack(str[start:end])
06635           start = end
06636           end += length
06637           if python3:
06638             _v441.frame_id = str[start:end].decode('utf-8')
06639           else:
06640             _v441.frame_id = str[start:end]
06641           _x = _v440
06642           start = end
06643           end += 8
06644           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
06645           start = end
06646           end += 4
06647           (length,) = _struct_I.unpack(str[start:end])
06648           start = end
06649           end += length
06650           if python3:
06651             _v440.encoding = str[start:end].decode('utf-8')
06652           else:
06653             _v440.encoding = str[start:end]
06654           _x = _v440
06655           start = end
06656           end += 5
06657           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
06658           start = end
06659           end += 4
06660           (length,) = _struct_I.unpack(str[start:end])
06661           start = end
06662           end += length
06663           if python3:
06664             _v440.data = str[start:end].decode('utf-8')
06665           else:
06666             _v440.data = str[start:end]
06667           _v443 = _v436.disparity_image
06668           _v444 = _v443.header
06669           start = end
06670           end += 4
06671           (_v444.seq,) = _struct_I.unpack(str[start:end])
06672           _v445 = _v444.stamp
06673           _x = _v445
06674           start = end
06675           end += 8
06676           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
06677           start = end
06678           end += 4
06679           (length,) = _struct_I.unpack(str[start:end])
06680           start = end
06681           end += length
06682           if python3:
06683             _v444.frame_id = str[start:end].decode('utf-8')
06684           else:
06685             _v444.frame_id = str[start:end]
06686           _x = _v443
06687           start = end
06688           end += 8
06689           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
06690           start = end
06691           end += 4
06692           (length,) = _struct_I.unpack(str[start:end])
06693           start = end
06694           end += length
06695           if python3:
06696             _v443.encoding = str[start:end].decode('utf-8')
06697           else:
06698             _v443.encoding = str[start:end]
06699           _x = _v443
06700           start = end
06701           end += 5
06702           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
06703           start = end
06704           end += 4
06705           (length,) = _struct_I.unpack(str[start:end])
06706           start = end
06707           end += length
06708           if python3:
06709             _v443.data = str[start:end].decode('utf-8')
06710           else:
06711             _v443.data = str[start:end]
06712           _v446 = _v436.cam_info
06713           _v447 = _v446.header
06714           start = end
06715           end += 4
06716           (_v447.seq,) = _struct_I.unpack(str[start:end])
06717           _v448 = _v447.stamp
06718           _x = _v448
06719           start = end
06720           end += 8
06721           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
06722           start = end
06723           end += 4
06724           (length,) = _struct_I.unpack(str[start:end])
06725           start = end
06726           end += length
06727           if python3:
06728             _v447.frame_id = str[start:end].decode('utf-8')
06729           else:
06730             _v447.frame_id = str[start:end]
06731           _x = _v446
06732           start = end
06733           end += 8
06734           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
06735           start = end
06736           end += 4
06737           (length,) = _struct_I.unpack(str[start:end])
06738           start = end
06739           end += length
06740           if python3:
06741             _v446.distortion_model = str[start:end].decode('utf-8')
06742           else:
06743             _v446.distortion_model = str[start:end]
06744           start = end
06745           end += 4
06746           (length,) = _struct_I.unpack(str[start:end])
06747           pattern = '<%sd'%length
06748           start = end
06749           end += struct.calcsize(pattern)
06750           _v446.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
06751           start = end
06752           end += 72
06753           _v446.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
06754           start = end
06755           end += 72
06756           _v446.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
06757           start = end
06758           end += 96
06759           _v446.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
06760           _x = _v446
06761           start = end
06762           end += 8
06763           (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
06764           _v449 = _v446.roi
06765           _x = _v449
06766           start = end
06767           end += 17
06768           (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
06769           _v449.do_rectify = bool(_v449.do_rectify)
06770           _v450 = _v436.roi_box_pose
06771           _v451 = _v450.header
06772           start = end
06773           end += 4
06774           (_v451.seq,) = _struct_I.unpack(str[start:end])
06775           _v452 = _v451.stamp
06776           _x = _v452
06777           start = end
06778           end += 8
06779           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
06780           start = end
06781           end += 4
06782           (length,) = _struct_I.unpack(str[start:end])
06783           start = end
06784           end += length
06785           if python3:
06786             _v451.frame_id = str[start:end].decode('utf-8')
06787           else:
06788             _v451.frame_id = str[start:end]
06789           _v453 = _v450.pose
06790           _v454 = _v453.position
06791           _x = _v454
06792           start = end
06793           end += 24
06794           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
06795           _v455 = _v453.orientation
06796           _x = _v455
06797           start = end
06798           end += 32
06799           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
06800           _v456 = _v436.roi_box_dims
06801           _x = _v456
06802           start = end
06803           end += 24
06804           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
06805           start = end
06806           end += 4
06807           (length,) = _struct_I.unpack(str[start:end])
06808           start = end
06809           end += length
06810           if python3:
06811             val2.collision_name = str[start:end].decode('utf-8')
06812           else:
06813             val2.collision_name = str[start:end]
06814           val1.moved_obstacles.append(val2)
06815         self.grasps.append(val1)
06816       start = end
06817       end += 4
06818       (self.error_code.value,) = _struct_i.unpack(str[start:end])
06819       return self
06820     except struct.error as e:
06821       raise genpy.DeserializationError(e) #most likely buffer underfill
06822 
06823 _struct_I = genpy.struct_I
06824 _struct_IBI = struct.Struct("<IBI")
06825 _struct_B = struct.Struct("<B")
06826 _struct_12d = struct.Struct("<12d")
06827 _struct_f = struct.Struct("<f")
06828 _struct_dB2f = struct.Struct("<dB2f")
06829 _struct_BI = struct.Struct("<BI")
06830 _struct_3f = struct.Struct("<3f")
06831 _struct_i = struct.Struct("<i")
06832 _struct_9d = struct.Struct("<9d")
06833 _struct_B2I = struct.Struct("<B2I")
06834 _struct_4d = struct.Struct("<4d")
06835 _struct_2I = struct.Struct("<2I")
06836 _struct_4IB = struct.Struct("<4IB")
06837 _struct_3d = struct.Struct("<3d")
06838 class GraspPlanning(object):
06839   _type          = 'object_manipulation_msgs/GraspPlanning'
06840   _md5sum = '01a11c1cdea613dd8705f368e1dc93dc'
06841   _request_class  = GraspPlanningRequest
06842   _response_class = GraspPlanningResponse


object_manipulation_msgs
Author(s): Matei Ciocarlie
autogenerated on Thu Jan 2 2014 11:38:11