_PickupAction.py
Go to the documentation of this file.
00001 """autogenerated by genpy from object_manipulation_msgs/PickupAction.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 arm_navigation_msgs.msg
00008 import object_manipulation_msgs.msg
00009 import actionlib_msgs.msg
00010 import geometry_msgs.msg
00011 import sensor_msgs.msg
00012 import std_msgs.msg
00013 import genpy
00014 import household_objects_database_msgs.msg
00015 
00016 class PickupAction(genpy.Message):
00017   _md5sum = "09990218855ede96047d48c436f6201d"
00018   _type = "object_manipulation_msgs/PickupAction"
00019   _has_header = False #flag to mark the presence of a Header object
00020   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00021 
00022 PickupActionGoal action_goal
00023 PickupActionResult action_result
00024 PickupActionFeedback action_feedback
00025 
00026 ================================================================================
00027 MSG: object_manipulation_msgs/PickupActionGoal
00028 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00029 
00030 Header header
00031 actionlib_msgs/GoalID goal_id
00032 PickupGoal goal
00033 
00034 ================================================================================
00035 MSG: std_msgs/Header
00036 # Standard metadata for higher-level stamped data types.
00037 # This is generally used to communicate timestamped data 
00038 # in a particular coordinate frame.
00039 # 
00040 # sequence ID: consecutively increasing ID 
00041 uint32 seq
00042 #Two-integer timestamp that is expressed as:
00043 # * stamp.secs: seconds (stamp_secs) since epoch
00044 # * stamp.nsecs: nanoseconds since stamp_secs
00045 # time-handling sugar is provided by the client library
00046 time stamp
00047 #Frame this data is associated with
00048 # 0: no frame
00049 # 1: global frame
00050 string frame_id
00051 
00052 ================================================================================
00053 MSG: actionlib_msgs/GoalID
00054 # The stamp should store the time at which this goal was requested.
00055 # It is used by an action server when it tries to preempt all
00056 # goals that were requested before a certain time
00057 time stamp
00058 
00059 # The id provides a way to associate feedback and
00060 # result message with specific goal requests. The id
00061 # specified must be unique.
00062 string id
00063 
00064 
00065 ================================================================================
00066 MSG: object_manipulation_msgs/PickupGoal
00067 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00068 # An action for picking up an object
00069 
00070 # which arm to be used for grasping
00071 string arm_name
00072 
00073 # the object to be grasped
00074 GraspableObject target
00075 
00076 # a list of grasps to be used
00077 # if empty, the grasp executive will call one of its own planners
00078 Grasp[] desired_grasps
00079 
00080 # how the object should be lifted after the grasp
00081 # the frame_id that this lift is specified in MUST be either the robot_frame 
00082 # or the gripper_frame specified in your hand description file
00083 GripperTranslation lift
00084 
00085 # the name that the target object has in the collision map
00086 # can be left empty if no name is available
00087 string collision_object_name
00088 
00089 # the name that the support surface (e.g. table) has in the collision map
00090 # can be left empty if no name is available
00091 string collision_support_surface_name
00092 
00093 # whether collisions between the gripper and the support surface should be acceptable
00094 # during move from pre-grasp to grasp and during lift. Collisions when moving to the
00095 # pre-grasp location are still not allowed even if this is set to true.
00096 bool allow_gripper_support_collision
00097 
00098 # whether reactive grasp execution using tactile sensors should be used
00099 bool use_reactive_execution
00100 
00101 # whether reactive object lifting based on tactile sensors should be used
00102 bool use_reactive_lift
00103 
00104 # set this to true if you only want to query the manipulation pipeline as to what 
00105 # grasps it thinks are feasible, without actually executing them. If this is set to 
00106 # true, the atempted_grasp_results field of the result will be populated, but no arm 
00107 # movement will be attempted
00108 bool only_perform_feasibility_test
00109 
00110 # set this to true if you want to ignore all collisions throughout the pickup 
00111 # and also move directly to the pre-grasp using Cartesian controllers
00112 bool ignore_collisions
00113 
00114 # OPTIONAL (These will not have to be filled out most of the time)
00115 # constraints to be imposed on every point in the motion of the arm
00116 arm_navigation_msgs/Constraints path_constraints
00117 
00118 # OPTIONAL (These will not have to be filled out most of the time)
00119 # additional collision operations to be used for every arm movement performed
00120 # during grasping. Note that these will be added on top of (and thus overide) other 
00121 # collision operations that the grasping pipeline deems necessary. Should be used
00122 # with care and only if special behaviors are desired
00123 arm_navigation_msgs/OrderedCollisionOperations additional_collision_operations
00124 
00125 # OPTIONAL (These will not have to be filled out most of the time)
00126 # additional link paddings to be used for every arm movement performed
00127 # during grasping. Note that these will be added on top of (and thus overide) other 
00128 # link paddings that the grasping pipeline deems necessary. Should be used
00129 # with care and only if special behaviors are desired
00130 arm_navigation_msgs/LinkPadding[] additional_link_padding
00131 
00132 # an optional list of obstacles that we have semantic information about
00133 # and that can be moved in the course of grasping
00134 GraspableObject[] movable_obstacles
00135 
00136 # the maximum contact force to use while grasping (<=0 to disable)
00137 float32 max_contact_force
00138 
00139 
00140 ================================================================================
00141 MSG: object_manipulation_msgs/GraspableObject
00142 # an object that the object_manipulator can work on
00143 
00144 # a graspable object can be represented in multiple ways. This message
00145 # can contain all of them. Which one is actually used is up to the receiver
00146 # of this message. When adding new representations, one must be careful that
00147 # they have reasonable lightweight defaults indicating that that particular
00148 # representation is not available.
00149 
00150 # the tf frame to be used as a reference frame when combining information from
00151 # the different representations below
00152 string reference_frame_id
00153 
00154 # potential recognition results from a database of models
00155 # all poses are relative to the object reference pose
00156 household_objects_database_msgs/DatabaseModelPose[] potential_models
00157 
00158 # the point cloud itself
00159 sensor_msgs/PointCloud cluster
00160 
00161 # a region of a PointCloud2 of interest
00162 object_manipulation_msgs/SceneRegion region
00163 
00164 # the name that this object has in the collision environment
00165 string collision_name
00166 ================================================================================
00167 MSG: household_objects_database_msgs/DatabaseModelPose
00168 # Informs that a specific model from the Model Database has been 
00169 # identified at a certain location
00170 
00171 # the database id of the model
00172 int32 model_id
00173 
00174 # the pose that it can be found in
00175 geometry_msgs/PoseStamped pose
00176 
00177 # a measure of the confidence level in this detection result
00178 float32 confidence
00179 
00180 # the name of the object detector that generated this detection result
00181 string detector_name
00182 
00183 ================================================================================
00184 MSG: geometry_msgs/PoseStamped
00185 # A Pose with reference coordinate frame and timestamp
00186 Header header
00187 Pose pose
00188 
00189 ================================================================================
00190 MSG: geometry_msgs/Pose
00191 # A representation of pose in free space, composed of postion and orientation. 
00192 Point position
00193 Quaternion orientation
00194 
00195 ================================================================================
00196 MSG: geometry_msgs/Point
00197 # This contains the position of a point in free space
00198 float64 x
00199 float64 y
00200 float64 z
00201 
00202 ================================================================================
00203 MSG: geometry_msgs/Quaternion
00204 # This represents an orientation in free space in quaternion form.
00205 
00206 float64 x
00207 float64 y
00208 float64 z
00209 float64 w
00210 
00211 ================================================================================
00212 MSG: sensor_msgs/PointCloud
00213 # This message holds a collection of 3d points, plus optional additional
00214 # information about each point.
00215 
00216 # Time of sensor data acquisition, coordinate frame ID.
00217 Header header
00218 
00219 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00220 # in the frame given in the header.
00221 geometry_msgs/Point32[] points
00222 
00223 # Each channel should have the same number of elements as points array,
00224 # and the data in each channel should correspond 1:1 with each point.
00225 # Channel names in common practice are listed in ChannelFloat32.msg.
00226 ChannelFloat32[] channels
00227 
00228 ================================================================================
00229 MSG: geometry_msgs/Point32
00230 # This contains the position of a point in free space(with 32 bits of precision).
00231 # It is recommeded to use Point wherever possible instead of Point32.  
00232 # 
00233 # This recommendation is to promote interoperability.  
00234 #
00235 # This message is designed to take up less space when sending
00236 # lots of points at once, as in the case of a PointCloud.  
00237 
00238 float32 x
00239 float32 y
00240 float32 z
00241 ================================================================================
00242 MSG: sensor_msgs/ChannelFloat32
00243 # This message is used by the PointCloud message to hold optional data
00244 # associated with each point in the cloud. The length of the values
00245 # array should be the same as the length of the points array in the
00246 # PointCloud, and each value should be associated with the corresponding
00247 # point.
00248 
00249 # Channel names in existing practice include:
00250 #   "u", "v" - row and column (respectively) in the left stereo image.
00251 #              This is opposite to usual conventions but remains for
00252 #              historical reasons. The newer PointCloud2 message has no
00253 #              such problem.
00254 #   "rgb" - For point clouds produced by color stereo cameras. uint8
00255 #           (R,G,B) values packed into the least significant 24 bits,
00256 #           in order.
00257 #   "intensity" - laser or pixel intensity.
00258 #   "distance"
00259 
00260 # The channel name should give semantics of the channel (e.g.
00261 # "intensity" instead of "value").
00262 string name
00263 
00264 # The values array should be 1-1 with the elements of the associated
00265 # PointCloud.
00266 float32[] values
00267 
00268 ================================================================================
00269 MSG: object_manipulation_msgs/SceneRegion
00270 # Point cloud
00271 sensor_msgs/PointCloud2 cloud
00272 
00273 # Indices for the region of interest
00274 int32[] mask
00275 
00276 # One of the corresponding 2D images, if applicable
00277 sensor_msgs/Image image
00278 
00279 # The disparity image, if applicable
00280 sensor_msgs/Image disparity_image
00281 
00282 # Camera info for the camera that took the image
00283 sensor_msgs/CameraInfo cam_info
00284 
00285 # a 3D region of interest for grasp planning
00286 geometry_msgs/PoseStamped  roi_box_pose
00287 geometry_msgs/Vector3      roi_box_dims
00288 
00289 ================================================================================
00290 MSG: sensor_msgs/PointCloud2
00291 # This message holds a collection of N-dimensional points, which may
00292 # contain additional information such as normals, intensity, etc. The
00293 # point data is stored as a binary blob, its layout described by the
00294 # contents of the "fields" array.
00295 
00296 # The point cloud data may be organized 2d (image-like) or 1d
00297 # (unordered). Point clouds organized as 2d images may be produced by
00298 # camera depth sensors such as stereo or time-of-flight.
00299 
00300 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00301 # points).
00302 Header header
00303 
00304 # 2D structure of the point cloud. If the cloud is unordered, height is
00305 # 1 and width is the length of the point cloud.
00306 uint32 height
00307 uint32 width
00308 
00309 # Describes the channels and their layout in the binary data blob.
00310 PointField[] fields
00311 
00312 bool    is_bigendian # Is this data bigendian?
00313 uint32  point_step   # Length of a point in bytes
00314 uint32  row_step     # Length of a row in bytes
00315 uint8[] data         # Actual point data, size is (row_step*height)
00316 
00317 bool is_dense        # True if there are no invalid points
00318 
00319 ================================================================================
00320 MSG: sensor_msgs/PointField
00321 # This message holds the description of one point entry in the
00322 # PointCloud2 message format.
00323 uint8 INT8    = 1
00324 uint8 UINT8   = 2
00325 uint8 INT16   = 3
00326 uint8 UINT16  = 4
00327 uint8 INT32   = 5
00328 uint8 UINT32  = 6
00329 uint8 FLOAT32 = 7
00330 uint8 FLOAT64 = 8
00331 
00332 string name      # Name of field
00333 uint32 offset    # Offset from start of point struct
00334 uint8  datatype  # Datatype enumeration, see above
00335 uint32 count     # How many elements in the field
00336 
00337 ================================================================================
00338 MSG: sensor_msgs/Image
00339 # This message contains an uncompressed image
00340 # (0, 0) is at top-left corner of image
00341 #
00342 
00343 Header header        # Header timestamp should be acquisition time of image
00344                      # Header frame_id should be optical frame of camera
00345                      # origin of frame should be optical center of cameara
00346                      # +x should point to the right in the image
00347                      # +y should point down in the image
00348                      # +z should point into to plane of the image
00349                      # If the frame_id here and the frame_id of the CameraInfo
00350                      # message associated with the image conflict
00351                      # the behavior is undefined
00352 
00353 uint32 height         # image height, that is, number of rows
00354 uint32 width          # image width, that is, number of columns
00355 
00356 # The legal values for encoding are in file src/image_encodings.cpp
00357 # If you want to standardize a new string format, join
00358 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00359 
00360 string encoding       # Encoding of pixels -- channel meaning, ordering, size
00361                       # taken from the list of strings in src/image_encodings.cpp
00362 
00363 uint8 is_bigendian    # is this data bigendian?
00364 uint32 step           # Full row length in bytes
00365 uint8[] data          # actual matrix data, size is (step * rows)
00366 
00367 ================================================================================
00368 MSG: sensor_msgs/CameraInfo
00369 # This message defines meta information for a camera. It should be in a
00370 # camera namespace on topic "camera_info" and accompanied by up to five
00371 # image topics named:
00372 #
00373 #   image_raw - raw data from the camera driver, possibly Bayer encoded
00374 #   image            - monochrome, distorted
00375 #   image_color      - color, distorted
00376 #   image_rect       - monochrome, rectified
00377 #   image_rect_color - color, rectified
00378 #
00379 # The image_pipeline contains packages (image_proc, stereo_image_proc)
00380 # for producing the four processed image topics from image_raw and
00381 # camera_info. The meaning of the camera parameters are described in
00382 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
00383 #
00384 # The image_geometry package provides a user-friendly interface to
00385 # common operations using this meta information. If you want to, e.g.,
00386 # project a 3d point into image coordinates, we strongly recommend
00387 # using image_geometry.
00388 #
00389 # If the camera is uncalibrated, the matrices D, K, R, P should be left
00390 # zeroed out. In particular, clients may assume that K[0] == 0.0
00391 # indicates an uncalibrated camera.
00392 
00393 #######################################################################
00394 #                     Image acquisition info                          #
00395 #######################################################################
00396 
00397 # Time of image acquisition, camera coordinate frame ID
00398 Header header    # Header timestamp should be acquisition time of image
00399                  # Header frame_id should be optical frame of camera
00400                  # origin of frame should be optical center of camera
00401                  # +x should point to the right in the image
00402                  # +y should point down in the image
00403                  # +z should point into the plane of the image
00404 
00405 
00406 #######################################################################
00407 #                      Calibration Parameters                         #
00408 #######################################################################
00409 # These are fixed during camera calibration. Their values will be the #
00410 # same in all messages until the camera is recalibrated. Note that    #
00411 # self-calibrating systems may "recalibrate" frequently.              #
00412 #                                                                     #
00413 # The internal parameters can be used to warp a raw (distorted) image #
00414 # to:                                                                 #
00415 #   1. An undistorted image (requires D and K)                        #
00416 #   2. A rectified image (requires D, K, R)                           #
00417 # The projection matrix P projects 3D points into the rectified image.#
00418 #######################################################################
00419 
00420 # The image dimensions with which the camera was calibrated. Normally
00421 # this will be the full camera resolution in pixels.
00422 uint32 height
00423 uint32 width
00424 
00425 # The distortion model used. Supported models are listed in
00426 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
00427 # simple model of radial and tangential distortion - is sufficent.
00428 string distortion_model
00429 
00430 # The distortion parameters, size depending on the distortion model.
00431 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
00432 float64[] D
00433 
00434 # Intrinsic camera matrix for the raw (distorted) images.
00435 #     [fx  0 cx]
00436 # K = [ 0 fy cy]
00437 #     [ 0  0  1]
00438 # Projects 3D points in the camera coordinate frame to 2D pixel
00439 # coordinates using the focal lengths (fx, fy) and principal point
00440 # (cx, cy).
00441 float64[9]  K # 3x3 row-major matrix
00442 
00443 # Rectification matrix (stereo cameras only)
00444 # A rotation matrix aligning the camera coordinate system to the ideal
00445 # stereo image plane so that epipolar lines in both stereo images are
00446 # parallel.
00447 float64[9]  R # 3x3 row-major matrix
00448 
00449 # Projection/camera matrix
00450 #     [fx'  0  cx' Tx]
00451 # P = [ 0  fy' cy' Ty]
00452 #     [ 0   0   1   0]
00453 # By convention, this matrix specifies the intrinsic (camera) matrix
00454 #  of the processed (rectified) image. That is, the left 3x3 portion
00455 #  is the normal camera intrinsic matrix for the rectified image.
00456 # It projects 3D points in the camera coordinate frame to 2D pixel
00457 #  coordinates using the focal lengths (fx', fy') and principal point
00458 #  (cx', cy') - these may differ from the values in K.
00459 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
00460 #  also have R = the identity and P[1:3,1:3] = K.
00461 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
00462 #  position of the optical center of the second camera in the first
00463 #  camera's frame. We assume Tz = 0 so both cameras are in the same
00464 #  stereo image plane. The first camera always has Tx = Ty = 0. For
00465 #  the right (second) camera of a horizontal stereo pair, Ty = 0 and
00466 #  Tx = -fx' * B, where B is the baseline between the cameras.
00467 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
00468 #  the rectified image is given by:
00469 #  [u v w]' = P * [X Y Z 1]'
00470 #         x = u / w
00471 #         y = v / w
00472 #  This holds for both images of a stereo pair.
00473 float64[12] P # 3x4 row-major matrix
00474 
00475 
00476 #######################################################################
00477 #                      Operational Parameters                         #
00478 #######################################################################
00479 # These define the image region actually captured by the camera       #
00480 # driver. Although they affect the geometry of the output image, they #
00481 # may be changed freely without recalibrating the camera.             #
00482 #######################################################################
00483 
00484 # Binning refers here to any camera setting which combines rectangular
00485 #  neighborhoods of pixels into larger "super-pixels." It reduces the
00486 #  resolution of the output image to
00487 #  (width / binning_x) x (height / binning_y).
00488 # The default values binning_x = binning_y = 0 is considered the same
00489 #  as binning_x = binning_y = 1 (no subsampling).
00490 uint32 binning_x
00491 uint32 binning_y
00492 
00493 # Region of interest (subwindow of full camera resolution), given in
00494 #  full resolution (unbinned) image coordinates. A particular ROI
00495 #  always denotes the same window of pixels on the camera sensor,
00496 #  regardless of binning settings.
00497 # The default setting of roi (all values 0) is considered the same as
00498 #  full resolution (roi.width = width, roi.height = height).
00499 RegionOfInterest roi
00500 
00501 ================================================================================
00502 MSG: sensor_msgs/RegionOfInterest
00503 # This message is used to specify a region of interest within an image.
00504 #
00505 # When used to specify the ROI setting of the camera when the image was
00506 # taken, the height and width fields should either match the height and
00507 # width fields for the associated image; or height = width = 0
00508 # indicates that the full resolution image was captured.
00509 
00510 uint32 x_offset  # Leftmost pixel of the ROI
00511                  # (0 if the ROI includes the left edge of the image)
00512 uint32 y_offset  # Topmost pixel of the ROI
00513                  # (0 if the ROI includes the top edge of the image)
00514 uint32 height    # Height of ROI
00515 uint32 width     # Width of ROI
00516 
00517 # True if a distinct rectified ROI should be calculated from the "raw"
00518 # ROI in this message. Typically this should be False if the full image
00519 # is captured (ROI not used), and True if a subwindow is captured (ROI
00520 # used).
00521 bool do_rectify
00522 
00523 ================================================================================
00524 MSG: geometry_msgs/Vector3
00525 # This represents a vector in free space. 
00526 
00527 float64 x
00528 float64 y
00529 float64 z
00530 ================================================================================
00531 MSG: object_manipulation_msgs/Grasp
00532 
00533 # The internal posture of the hand for the pre-grasp
00534 # only positions are used
00535 sensor_msgs/JointState pre_grasp_posture
00536 
00537 # The internal posture of the hand for the grasp
00538 # positions and efforts are used
00539 sensor_msgs/JointState grasp_posture
00540 
00541 # The position of the end-effector for the grasp relative to a reference frame 
00542 # (that is always specified elsewhere, not in this message)
00543 geometry_msgs/Pose grasp_pose
00544 
00545 # The estimated probability of success for this grasp
00546 float64 success_probability
00547 
00548 # Debug flag to indicate that this grasp would be the best in its cluster
00549 bool cluster_rep
00550 
00551 # how far the pre-grasp should ideally be away from the grasp
00552 float32 desired_approach_distance
00553 
00554 # how much distance between pre-grasp and grasp must actually be feasible 
00555 # for the grasp not to be rejected
00556 float32 min_approach_distance
00557 
00558 # an optional list of obstacles that we have semantic information about
00559 # and that we expect might move in the course of executing this grasp
00560 # the grasp planner is expected to make sure they move in an OK way; during
00561 # execution, grasp executors will not check for collisions against these objects
00562 GraspableObject[] moved_obstacles
00563 
00564 ================================================================================
00565 MSG: sensor_msgs/JointState
00566 # This is a message that holds data to describe the state of a set of torque controlled joints. 
00567 #
00568 # The state of each joint (revolute or prismatic) is defined by:
00569 #  * the position of the joint (rad or m),
00570 #  * the velocity of the joint (rad/s or m/s) and 
00571 #  * the effort that is applied in the joint (Nm or N).
00572 #
00573 # Each joint is uniquely identified by its name
00574 # The header specifies the time at which the joint states were recorded. All the joint states
00575 # in one message have to be recorded at the same time.
00576 #
00577 # This message consists of a multiple arrays, one for each part of the joint state. 
00578 # The goal is to make each of the fields optional. When e.g. your joints have no
00579 # effort associated with them, you can leave the effort array empty. 
00580 #
00581 # All arrays in this message should have the same size, or be empty.
00582 # This is the only way to uniquely associate the joint name with the correct
00583 # states.
00584 
00585 
00586 Header header
00587 
00588 string[] name
00589 float64[] position
00590 float64[] velocity
00591 float64[] effort
00592 
00593 ================================================================================
00594 MSG: object_manipulation_msgs/GripperTranslation
00595 # defines a translation for the gripper, used in pickup or place tasks
00596 # for example for lifting an object off a table or approaching the table for placing
00597 
00598 # the direction of the translation
00599 geometry_msgs/Vector3Stamped direction
00600 
00601 # the desired translation distance
00602 float32 desired_distance
00603 
00604 # the min distance that must be considered feasible before the
00605 # grasp is even attempted
00606 float32 min_distance
00607 ================================================================================
00608 MSG: geometry_msgs/Vector3Stamped
00609 # This represents a Vector3 with reference coordinate frame and timestamp
00610 Header header
00611 Vector3 vector
00612 
00613 ================================================================================
00614 MSG: arm_navigation_msgs/Constraints
00615 # This message contains a list of motion planning constraints.
00616 
00617 arm_navigation_msgs/JointConstraint[] joint_constraints
00618 arm_navigation_msgs/PositionConstraint[] position_constraints
00619 arm_navigation_msgs/OrientationConstraint[] orientation_constraints
00620 arm_navigation_msgs/VisibilityConstraint[] visibility_constraints
00621 
00622 ================================================================================
00623 MSG: arm_navigation_msgs/JointConstraint
00624 # Constrain the position of a joint to be within a certain bound
00625 string joint_name
00626 
00627 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]
00628 float64 position
00629 float64 tolerance_above
00630 float64 tolerance_below
00631 
00632 # A weighting factor for this constraint
00633 float64 weight
00634 ================================================================================
00635 MSG: arm_navigation_msgs/PositionConstraint
00636 # This message contains the definition of a position constraint.
00637 Header header
00638 
00639 # The robot link this constraint refers to
00640 string link_name
00641 
00642 # The offset (in the link frame) for the target point on the link we are planning for
00643 geometry_msgs/Point target_point_offset
00644 
00645 # The nominal/target position for the point we are planning for
00646 geometry_msgs/Point position
00647 
00648 # The shape of the bounded region that constrains the position of the end-effector
00649 # This region is always centered at the position defined above
00650 arm_navigation_msgs/Shape constraint_region_shape
00651 
00652 # The orientation of the bounded region that constrains the position of the end-effector. 
00653 # This allows the specification of non-axis aligned constraints
00654 geometry_msgs/Quaternion constraint_region_orientation
00655 
00656 # Constraint weighting factor - a weight for this constraint
00657 float64 weight
00658 
00659 ================================================================================
00660 MSG: arm_navigation_msgs/Shape
00661 byte SPHERE=0
00662 byte BOX=1
00663 byte CYLINDER=2
00664 byte MESH=3
00665 
00666 byte type
00667 
00668 
00669 #### define sphere, box, cylinder ####
00670 # the origin of each shape is considered at the shape's center
00671 
00672 # for sphere
00673 # radius := dimensions[0]
00674 
00675 # for cylinder
00676 # radius := dimensions[0]
00677 # length := dimensions[1]
00678 # the length is along the Z axis
00679 
00680 # for box
00681 # size_x := dimensions[0]
00682 # size_y := dimensions[1]
00683 # size_z := dimensions[2]
00684 float64[] dimensions
00685 
00686 
00687 #### define mesh ####
00688 
00689 # list of triangles; triangle k is defined by tre vertices located
00690 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00691 int32[] triangles
00692 geometry_msgs/Point[] vertices
00693 
00694 ================================================================================
00695 MSG: arm_navigation_msgs/OrientationConstraint
00696 # This message contains the definition of an orientation constraint.
00697 Header header
00698 
00699 # The robot link this constraint refers to
00700 string link_name
00701 
00702 # The type of the constraint
00703 int32 type
00704 int32 LINK_FRAME=0
00705 int32 HEADER_FRAME=1
00706 
00707 # The desired orientation of the robot link specified as a quaternion
00708 geometry_msgs/Quaternion orientation
00709 
00710 # optional RPY error tolerances specified if 
00711 float64 absolute_roll_tolerance
00712 float64 absolute_pitch_tolerance
00713 float64 absolute_yaw_tolerance
00714 
00715 # Constraint weighting factor - a weight for this constraint
00716 float64 weight
00717 
00718 ================================================================================
00719 MSG: arm_navigation_msgs/VisibilityConstraint
00720 # This message contains the definition of a visibility constraint.
00721 Header header
00722 
00723 # The point stamped target that needs to be kept within view of the sensor
00724 geometry_msgs/PointStamped target
00725 
00726 # The local pose of the frame in which visibility is to be maintained
00727 # The frame id should represent the robot link to which the sensor is attached
00728 # The visual axis of the sensor is assumed to be along the X axis of this frame
00729 geometry_msgs/PoseStamped sensor_pose
00730 
00731 # The deviation (in radians) that will be tolerated
00732 # Constraint error will be measured as the solid angle between the 
00733 # X axis of the frame defined above and the vector between the origin 
00734 # of the frame defined above and the target location
00735 float64 absolute_tolerance
00736 
00737 
00738 ================================================================================
00739 MSG: geometry_msgs/PointStamped
00740 # This represents a Point with reference coordinate frame and timestamp
00741 Header header
00742 Point point
00743 
00744 ================================================================================
00745 MSG: arm_navigation_msgs/OrderedCollisionOperations
00746 # A set of collision operations that will be performed in the order they are specified
00747 CollisionOperation[] collision_operations
00748 ================================================================================
00749 MSG: arm_navigation_msgs/CollisionOperation
00750 # A definition of a collision operation
00751 # E.g. ("gripper",COLLISION_SET_ALL,ENABLE) will enable collisions 
00752 # between the gripper and all objects in the collision space
00753 
00754 string object1
00755 string object2
00756 string COLLISION_SET_ALL="all"
00757 string COLLISION_SET_OBJECTS="objects"
00758 string COLLISION_SET_ATTACHED_OBJECTS="attached"
00759 
00760 # The penetration distance to which collisions are allowed. This is 0.0 by default.
00761 float64 penetration_distance
00762 
00763 # Flag that determines whether collisions will be enabled or disabled for the pair of objects specified above
00764 int32 operation
00765 int32 DISABLE=0
00766 int32 ENABLE=1
00767 
00768 ================================================================================
00769 MSG: arm_navigation_msgs/LinkPadding
00770 #name for the link
00771 string link_name
00772 
00773 # padding to apply to the link
00774 float64 padding
00775 
00776 ================================================================================
00777 MSG: object_manipulation_msgs/PickupActionResult
00778 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00779 
00780 Header header
00781 actionlib_msgs/GoalStatus status
00782 PickupResult result
00783 
00784 ================================================================================
00785 MSG: actionlib_msgs/GoalStatus
00786 GoalID goal_id
00787 uint8 status
00788 uint8 PENDING         = 0   # The goal has yet to be processed by the action server
00789 uint8 ACTIVE          = 1   # The goal is currently being processed by the action server
00790 uint8 PREEMPTED       = 2   # The goal received a cancel request after it started executing
00791                             #   and has since completed its execution (Terminal State)
00792 uint8 SUCCEEDED       = 3   # The goal was achieved successfully by the action server (Terminal State)
00793 uint8 ABORTED         = 4   # The goal was aborted during execution by the action server due
00794                             #    to some failure (Terminal State)
00795 uint8 REJECTED        = 5   # The goal was rejected by the action server without being processed,
00796                             #    because the goal was unattainable or invalid (Terminal State)
00797 uint8 PREEMPTING      = 6   # The goal received a cancel request after it started executing
00798                             #    and has not yet completed execution
00799 uint8 RECALLING       = 7   # The goal received a cancel request before it started executing,
00800                             #    but the action server has not yet confirmed that the goal is canceled
00801 uint8 RECALLED        = 8   # The goal received a cancel request before it started executing
00802                             #    and was successfully cancelled (Terminal State)
00803 uint8 LOST            = 9   # An action client can determine that a goal is LOST. This should not be
00804                             #    sent over the wire by an action server
00805 
00806 #Allow for the user to associate a string with GoalStatus for debugging
00807 string text
00808 
00809 
00810 ================================================================================
00811 MSG: object_manipulation_msgs/PickupResult
00812 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00813 
00814 # The overall result of the pickup attempt
00815 ManipulationResult manipulation_result
00816 
00817 # The performed grasp, if attempt was successful
00818 Grasp grasp
00819 
00820 # the complete list of attempted grasp, in the order in which they have been attempted
00821 # the successful one should be the last one in this list
00822 Grasp[] attempted_grasps
00823 
00824 # the outcomes of the attempted grasps, in the same order as attempted_grasps
00825 GraspResult[] attempted_grasp_results
00826 
00827 
00828 ================================================================================
00829 MSG: object_manipulation_msgs/ManipulationResult
00830 # Result codes for manipulation tasks
00831 
00832 # task completed as expected
00833 # generally means you can proceed as planned
00834 int32 SUCCESS = 1
00835 
00836 # task not possible (e.g. out of reach or obstacles in the way)
00837 # generally means that the world was not disturbed, so you can try another task
00838 int32 UNFEASIBLE = -1
00839 
00840 # task was thought possible, but failed due to unexpected events during execution
00841 # it is likely that the world was disturbed, so you are encouraged to refresh
00842 # your sensed world model before proceeding to another task
00843 int32 FAILED = -2
00844 
00845 # a lower level error prevented task completion (e.g. joint controller not responding)
00846 # generally requires human attention
00847 int32 ERROR = -3
00848 
00849 # means that at some point during execution we ended up in a state that the collision-aware
00850 # arm navigation module will not move out of. The world was likely not disturbed, but you 
00851 # probably need a new collision map to move the arm out of the stuck position
00852 int32 ARM_MOVEMENT_PREVENTED = -4
00853 
00854 # specific to grasp actions
00855 # the object was grasped successfully, but the lift attempt could not achieve the minimum lift distance requested
00856 # it is likely that the collision environment will see collisions between the hand/object and the support surface
00857 int32 LIFT_FAILED = -5
00858 
00859 # specific to place actions
00860 # the object was placed successfully, but the retreat attempt could not achieve the minimum retreat distance requested
00861 # it is likely that the collision environment will see collisions between the hand and the object
00862 int32 RETREAT_FAILED = -6
00863 
00864 # indicates that somewhere along the line a human said "wait, stop, this is bad, go back and do something else"
00865 int32 CANCELLED = -7
00866 
00867 # the actual value of this error code
00868 int32 value
00869 
00870 ================================================================================
00871 MSG: object_manipulation_msgs/GraspResult
00872 int32 SUCCESS = 1
00873 int32 GRASP_OUT_OF_REACH = 2
00874 int32 GRASP_IN_COLLISION = 3
00875 int32 GRASP_UNFEASIBLE = 4
00876 int32 PREGRASP_OUT_OF_REACH = 5
00877 int32 PREGRASP_IN_COLLISION = 6
00878 int32 PREGRASP_UNFEASIBLE = 7
00879 int32 LIFT_OUT_OF_REACH = 8
00880 int32 LIFT_IN_COLLISION = 9
00881 int32 LIFT_UNFEASIBLE = 10
00882 int32 MOVE_ARM_FAILED = 11
00883 int32 GRASP_FAILED = 12
00884 int32 LIFT_FAILED = 13
00885 int32 RETREAT_FAILED = 14
00886 int32 result_code
00887 
00888 # whether the state of the world was disturbed by this attempt. generally, this flag
00889 # shows if another task can be attempted, or a new sensed world model is recommeded
00890 # before proceeding
00891 bool continuation_possible
00892 
00893 ================================================================================
00894 MSG: object_manipulation_msgs/PickupActionFeedback
00895 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00896 
00897 Header header
00898 actionlib_msgs/GoalStatus status
00899 PickupFeedback feedback
00900 
00901 ================================================================================
00902 MSG: object_manipulation_msgs/PickupFeedback
00903 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00904 
00905 # The number of the grasp currently being attempted
00906 int32 current_grasp
00907 
00908 # The total number of grasps that will be attempted
00909 int32 total_grasps
00910 
00911 
00912 """
00913   __slots__ = ['action_goal','action_result','action_feedback']
00914   _slot_types = ['object_manipulation_msgs/PickupActionGoal','object_manipulation_msgs/PickupActionResult','object_manipulation_msgs/PickupActionFeedback']
00915 
00916   def __init__(self, *args, **kwds):
00917     """
00918     Constructor. Any message fields that are implicitly/explicitly
00919     set to None will be assigned a default value. The recommend
00920     use is keyword arguments as this is more robust to future message
00921     changes.  You cannot mix in-order arguments and keyword arguments.
00922 
00923     The available fields are:
00924        action_goal,action_result,action_feedback
00925 
00926     :param args: complete set of field values, in .msg order
00927     :param kwds: use keyword arguments corresponding to message field names
00928     to set specific fields.
00929     """
00930     if args or kwds:
00931       super(PickupAction, self).__init__(*args, **kwds)
00932       #message fields cannot be None, assign default values for those that are
00933       if self.action_goal is None:
00934         self.action_goal = object_manipulation_msgs.msg.PickupActionGoal()
00935       if self.action_result is None:
00936         self.action_result = object_manipulation_msgs.msg.PickupActionResult()
00937       if self.action_feedback is None:
00938         self.action_feedback = object_manipulation_msgs.msg.PickupActionFeedback()
00939     else:
00940       self.action_goal = object_manipulation_msgs.msg.PickupActionGoal()
00941       self.action_result = object_manipulation_msgs.msg.PickupActionResult()
00942       self.action_feedback = object_manipulation_msgs.msg.PickupActionFeedback()
00943 
00944   def _get_types(self):
00945     """
00946     internal API method
00947     """
00948     return self._slot_types
00949 
00950   def serialize(self, buff):
00951     """
00952     serialize message into buffer
00953     :param buff: buffer, ``StringIO``
00954     """
00955     try:
00956       _x = self
00957       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00958       _x = self.action_goal.header.frame_id
00959       length = len(_x)
00960       if python3 or type(_x) == unicode:
00961         _x = _x.encode('utf-8')
00962         length = len(_x)
00963       buff.write(struct.pack('<I%ss'%length, length, _x))
00964       _x = self
00965       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00966       _x = self.action_goal.goal_id.id
00967       length = len(_x)
00968       if python3 or type(_x) == unicode:
00969         _x = _x.encode('utf-8')
00970         length = len(_x)
00971       buff.write(struct.pack('<I%ss'%length, length, _x))
00972       _x = self.action_goal.goal.arm_name
00973       length = len(_x)
00974       if python3 or type(_x) == unicode:
00975         _x = _x.encode('utf-8')
00976         length = len(_x)
00977       buff.write(struct.pack('<I%ss'%length, length, _x))
00978       _x = self.action_goal.goal.target.reference_frame_id
00979       length = len(_x)
00980       if python3 or type(_x) == unicode:
00981         _x = _x.encode('utf-8')
00982         length = len(_x)
00983       buff.write(struct.pack('<I%ss'%length, length, _x))
00984       length = len(self.action_goal.goal.target.potential_models)
00985       buff.write(_struct_I.pack(length))
00986       for val1 in self.action_goal.goal.target.potential_models:
00987         buff.write(_struct_i.pack(val1.model_id))
00988         _v1 = val1.pose
00989         _v2 = _v1.header
00990         buff.write(_struct_I.pack(_v2.seq))
00991         _v3 = _v2.stamp
00992         _x = _v3
00993         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00994         _x = _v2.frame_id
00995         length = len(_x)
00996         if python3 or type(_x) == unicode:
00997           _x = _x.encode('utf-8')
00998           length = len(_x)
00999         buff.write(struct.pack('<I%ss'%length, length, _x))
01000         _v4 = _v1.pose
01001         _v5 = _v4.position
01002         _x = _v5
01003         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01004         _v6 = _v4.orientation
01005         _x = _v6
01006         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01007         buff.write(_struct_f.pack(val1.confidence))
01008         _x = val1.detector_name
01009         length = len(_x)
01010         if python3 or type(_x) == unicode:
01011           _x = _x.encode('utf-8')
01012           length = len(_x)
01013         buff.write(struct.pack('<I%ss'%length, length, _x))
01014       _x = self
01015       buff.write(_struct_3I.pack(_x.action_goal.goal.target.cluster.header.seq, _x.action_goal.goal.target.cluster.header.stamp.secs, _x.action_goal.goal.target.cluster.header.stamp.nsecs))
01016       _x = self.action_goal.goal.target.cluster.header.frame_id
01017       length = len(_x)
01018       if python3 or type(_x) == unicode:
01019         _x = _x.encode('utf-8')
01020         length = len(_x)
01021       buff.write(struct.pack('<I%ss'%length, length, _x))
01022       length = len(self.action_goal.goal.target.cluster.points)
01023       buff.write(_struct_I.pack(length))
01024       for val1 in self.action_goal.goal.target.cluster.points:
01025         _x = val1
01026         buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
01027       length = len(self.action_goal.goal.target.cluster.channels)
01028       buff.write(_struct_I.pack(length))
01029       for val1 in self.action_goal.goal.target.cluster.channels:
01030         _x = val1.name
01031         length = len(_x)
01032         if python3 or type(_x) == unicode:
01033           _x = _x.encode('utf-8')
01034           length = len(_x)
01035         buff.write(struct.pack('<I%ss'%length, length, _x))
01036         length = len(val1.values)
01037         buff.write(_struct_I.pack(length))
01038         pattern = '<%sf'%length
01039         buff.write(struct.pack(pattern, *val1.values))
01040       _x = self
01041       buff.write(_struct_3I.pack(_x.action_goal.goal.target.region.cloud.header.seq, _x.action_goal.goal.target.region.cloud.header.stamp.secs, _x.action_goal.goal.target.region.cloud.header.stamp.nsecs))
01042       _x = self.action_goal.goal.target.region.cloud.header.frame_id
01043       length = len(_x)
01044       if python3 or type(_x) == unicode:
01045         _x = _x.encode('utf-8')
01046         length = len(_x)
01047       buff.write(struct.pack('<I%ss'%length, length, _x))
01048       _x = self
01049       buff.write(_struct_2I.pack(_x.action_goal.goal.target.region.cloud.height, _x.action_goal.goal.target.region.cloud.width))
01050       length = len(self.action_goal.goal.target.region.cloud.fields)
01051       buff.write(_struct_I.pack(length))
01052       for val1 in self.action_goal.goal.target.region.cloud.fields:
01053         _x = val1.name
01054         length = len(_x)
01055         if python3 or type(_x) == unicode:
01056           _x = _x.encode('utf-8')
01057           length = len(_x)
01058         buff.write(struct.pack('<I%ss'%length, length, _x))
01059         _x = val1
01060         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
01061       _x = self
01062       buff.write(_struct_B2I.pack(_x.action_goal.goal.target.region.cloud.is_bigendian, _x.action_goal.goal.target.region.cloud.point_step, _x.action_goal.goal.target.region.cloud.row_step))
01063       _x = self.action_goal.goal.target.region.cloud.data
01064       length = len(_x)
01065       # - if encoded as a list instead, serialize as bytes instead of string
01066       if type(_x) in [list, tuple]:
01067         buff.write(struct.pack('<I%sB'%length, length, *_x))
01068       else:
01069         buff.write(struct.pack('<I%ss'%length, length, _x))
01070       buff.write(_struct_B.pack(self.action_goal.goal.target.region.cloud.is_dense))
01071       length = len(self.action_goal.goal.target.region.mask)
01072       buff.write(_struct_I.pack(length))
01073       pattern = '<%si'%length
01074       buff.write(struct.pack(pattern, *self.action_goal.goal.target.region.mask))
01075       _x = self
01076       buff.write(_struct_3I.pack(_x.action_goal.goal.target.region.image.header.seq, _x.action_goal.goal.target.region.image.header.stamp.secs, _x.action_goal.goal.target.region.image.header.stamp.nsecs))
01077       _x = self.action_goal.goal.target.region.image.header.frame_id
01078       length = len(_x)
01079       if python3 or type(_x) == unicode:
01080         _x = _x.encode('utf-8')
01081         length = len(_x)
01082       buff.write(struct.pack('<I%ss'%length, length, _x))
01083       _x = self
01084       buff.write(_struct_2I.pack(_x.action_goal.goal.target.region.image.height, _x.action_goal.goal.target.region.image.width))
01085       _x = self.action_goal.goal.target.region.image.encoding
01086       length = len(_x)
01087       if python3 or type(_x) == unicode:
01088         _x = _x.encode('utf-8')
01089         length = len(_x)
01090       buff.write(struct.pack('<I%ss'%length, length, _x))
01091       _x = self
01092       buff.write(_struct_BI.pack(_x.action_goal.goal.target.region.image.is_bigendian, _x.action_goal.goal.target.region.image.step))
01093       _x = self.action_goal.goal.target.region.image.data
01094       length = len(_x)
01095       # - if encoded as a list instead, serialize as bytes instead of string
01096       if type(_x) in [list, tuple]:
01097         buff.write(struct.pack('<I%sB'%length, length, *_x))
01098       else:
01099         buff.write(struct.pack('<I%ss'%length, length, _x))
01100       _x = self
01101       buff.write(_struct_3I.pack(_x.action_goal.goal.target.region.disparity_image.header.seq, _x.action_goal.goal.target.region.disparity_image.header.stamp.secs, _x.action_goal.goal.target.region.disparity_image.header.stamp.nsecs))
01102       _x = self.action_goal.goal.target.region.disparity_image.header.frame_id
01103       length = len(_x)
01104       if python3 or type(_x) == unicode:
01105         _x = _x.encode('utf-8')
01106         length = len(_x)
01107       buff.write(struct.pack('<I%ss'%length, length, _x))
01108       _x = self
01109       buff.write(_struct_2I.pack(_x.action_goal.goal.target.region.disparity_image.height, _x.action_goal.goal.target.region.disparity_image.width))
01110       _x = self.action_goal.goal.target.region.disparity_image.encoding
01111       length = len(_x)
01112       if python3 or type(_x) == unicode:
01113         _x = _x.encode('utf-8')
01114         length = len(_x)
01115       buff.write(struct.pack('<I%ss'%length, length, _x))
01116       _x = self
01117       buff.write(_struct_BI.pack(_x.action_goal.goal.target.region.disparity_image.is_bigendian, _x.action_goal.goal.target.region.disparity_image.step))
01118       _x = self.action_goal.goal.target.region.disparity_image.data
01119       length = len(_x)
01120       # - if encoded as a list instead, serialize as bytes instead of string
01121       if type(_x) in [list, tuple]:
01122         buff.write(struct.pack('<I%sB'%length, length, *_x))
01123       else:
01124         buff.write(struct.pack('<I%ss'%length, length, _x))
01125       _x = self
01126       buff.write(_struct_3I.pack(_x.action_goal.goal.target.region.cam_info.header.seq, _x.action_goal.goal.target.region.cam_info.header.stamp.secs, _x.action_goal.goal.target.region.cam_info.header.stamp.nsecs))
01127       _x = self.action_goal.goal.target.region.cam_info.header.frame_id
01128       length = len(_x)
01129       if python3 or type(_x) == unicode:
01130         _x = _x.encode('utf-8')
01131         length = len(_x)
01132       buff.write(struct.pack('<I%ss'%length, length, _x))
01133       _x = self
01134       buff.write(_struct_2I.pack(_x.action_goal.goal.target.region.cam_info.height, _x.action_goal.goal.target.region.cam_info.width))
01135       _x = self.action_goal.goal.target.region.cam_info.distortion_model
01136       length = len(_x)
01137       if python3 or type(_x) == unicode:
01138         _x = _x.encode('utf-8')
01139         length = len(_x)
01140       buff.write(struct.pack('<I%ss'%length, length, _x))
01141       length = len(self.action_goal.goal.target.region.cam_info.D)
01142       buff.write(_struct_I.pack(length))
01143       pattern = '<%sd'%length
01144       buff.write(struct.pack(pattern, *self.action_goal.goal.target.region.cam_info.D))
01145       buff.write(_struct_9d.pack(*self.action_goal.goal.target.region.cam_info.K))
01146       buff.write(_struct_9d.pack(*self.action_goal.goal.target.region.cam_info.R))
01147       buff.write(_struct_12d.pack(*self.action_goal.goal.target.region.cam_info.P))
01148       _x = self
01149       buff.write(_struct_6IB3I.pack(_x.action_goal.goal.target.region.cam_info.binning_x, _x.action_goal.goal.target.region.cam_info.binning_y, _x.action_goal.goal.target.region.cam_info.roi.x_offset, _x.action_goal.goal.target.region.cam_info.roi.y_offset, _x.action_goal.goal.target.region.cam_info.roi.height, _x.action_goal.goal.target.region.cam_info.roi.width, _x.action_goal.goal.target.region.cam_info.roi.do_rectify, _x.action_goal.goal.target.region.roi_box_pose.header.seq, _x.action_goal.goal.target.region.roi_box_pose.header.stamp.secs, _x.action_goal.goal.target.region.roi_box_pose.header.stamp.nsecs))
01150       _x = self.action_goal.goal.target.region.roi_box_pose.header.frame_id
01151       length = len(_x)
01152       if python3 or type(_x) == unicode:
01153         _x = _x.encode('utf-8')
01154         length = len(_x)
01155       buff.write(struct.pack('<I%ss'%length, length, _x))
01156       _x = self
01157       buff.write(_struct_10d.pack(_x.action_goal.goal.target.region.roi_box_pose.pose.position.x, _x.action_goal.goal.target.region.roi_box_pose.pose.position.y, _x.action_goal.goal.target.region.roi_box_pose.pose.position.z, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.x, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.y, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.z, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.w, _x.action_goal.goal.target.region.roi_box_dims.x, _x.action_goal.goal.target.region.roi_box_dims.y, _x.action_goal.goal.target.region.roi_box_dims.z))
01158       _x = self.action_goal.goal.target.collision_name
01159       length = len(_x)
01160       if python3 or type(_x) == unicode:
01161         _x = _x.encode('utf-8')
01162         length = len(_x)
01163       buff.write(struct.pack('<I%ss'%length, length, _x))
01164       length = len(self.action_goal.goal.desired_grasps)
01165       buff.write(_struct_I.pack(length))
01166       for val1 in self.action_goal.goal.desired_grasps:
01167         _v7 = val1.pre_grasp_posture
01168         _v8 = _v7.header
01169         buff.write(_struct_I.pack(_v8.seq))
01170         _v9 = _v8.stamp
01171         _x = _v9
01172         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01173         _x = _v8.frame_id
01174         length = len(_x)
01175         if python3 or type(_x) == unicode:
01176           _x = _x.encode('utf-8')
01177           length = len(_x)
01178         buff.write(struct.pack('<I%ss'%length, length, _x))
01179         length = len(_v7.name)
01180         buff.write(_struct_I.pack(length))
01181         for val3 in _v7.name:
01182           length = len(val3)
01183           if python3 or type(val3) == unicode:
01184             val3 = val3.encode('utf-8')
01185             length = len(val3)
01186           buff.write(struct.pack('<I%ss'%length, length, val3))
01187         length = len(_v7.position)
01188         buff.write(_struct_I.pack(length))
01189         pattern = '<%sd'%length
01190         buff.write(struct.pack(pattern, *_v7.position))
01191         length = len(_v7.velocity)
01192         buff.write(_struct_I.pack(length))
01193         pattern = '<%sd'%length
01194         buff.write(struct.pack(pattern, *_v7.velocity))
01195         length = len(_v7.effort)
01196         buff.write(_struct_I.pack(length))
01197         pattern = '<%sd'%length
01198         buff.write(struct.pack(pattern, *_v7.effort))
01199         _v10 = val1.grasp_posture
01200         _v11 = _v10.header
01201         buff.write(_struct_I.pack(_v11.seq))
01202         _v12 = _v11.stamp
01203         _x = _v12
01204         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01205         _x = _v11.frame_id
01206         length = len(_x)
01207         if python3 or type(_x) == unicode:
01208           _x = _x.encode('utf-8')
01209           length = len(_x)
01210         buff.write(struct.pack('<I%ss'%length, length, _x))
01211         length = len(_v10.name)
01212         buff.write(_struct_I.pack(length))
01213         for val3 in _v10.name:
01214           length = len(val3)
01215           if python3 or type(val3) == unicode:
01216             val3 = val3.encode('utf-8')
01217             length = len(val3)
01218           buff.write(struct.pack('<I%ss'%length, length, val3))
01219         length = len(_v10.position)
01220         buff.write(_struct_I.pack(length))
01221         pattern = '<%sd'%length
01222         buff.write(struct.pack(pattern, *_v10.position))
01223         length = len(_v10.velocity)
01224         buff.write(_struct_I.pack(length))
01225         pattern = '<%sd'%length
01226         buff.write(struct.pack(pattern, *_v10.velocity))
01227         length = len(_v10.effort)
01228         buff.write(_struct_I.pack(length))
01229         pattern = '<%sd'%length
01230         buff.write(struct.pack(pattern, *_v10.effort))
01231         _v13 = val1.grasp_pose
01232         _v14 = _v13.position
01233         _x = _v14
01234         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01235         _v15 = _v13.orientation
01236         _x = _v15
01237         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01238         _x = val1
01239         buff.write(_struct_dB2f.pack(_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance))
01240         length = len(val1.moved_obstacles)
01241         buff.write(_struct_I.pack(length))
01242         for val2 in val1.moved_obstacles:
01243           _x = val2.reference_frame_id
01244           length = len(_x)
01245           if python3 or type(_x) == unicode:
01246             _x = _x.encode('utf-8')
01247             length = len(_x)
01248           buff.write(struct.pack('<I%ss'%length, length, _x))
01249           length = len(val2.potential_models)
01250           buff.write(_struct_I.pack(length))
01251           for val3 in val2.potential_models:
01252             buff.write(_struct_i.pack(val3.model_id))
01253             _v16 = val3.pose
01254             _v17 = _v16.header
01255             buff.write(_struct_I.pack(_v17.seq))
01256             _v18 = _v17.stamp
01257             _x = _v18
01258             buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01259             _x = _v17.frame_id
01260             length = len(_x)
01261             if python3 or type(_x) == unicode:
01262               _x = _x.encode('utf-8')
01263               length = len(_x)
01264             buff.write(struct.pack('<I%ss'%length, length, _x))
01265             _v19 = _v16.pose
01266             _v20 = _v19.position
01267             _x = _v20
01268             buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01269             _v21 = _v19.orientation
01270             _x = _v21
01271             buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01272             buff.write(_struct_f.pack(val3.confidence))
01273             _x = val3.detector_name
01274             length = len(_x)
01275             if python3 or type(_x) == unicode:
01276               _x = _x.encode('utf-8')
01277               length = len(_x)
01278             buff.write(struct.pack('<I%ss'%length, length, _x))
01279           _v22 = val2.cluster
01280           _v23 = _v22.header
01281           buff.write(_struct_I.pack(_v23.seq))
01282           _v24 = _v23.stamp
01283           _x = _v24
01284           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01285           _x = _v23.frame_id
01286           length = len(_x)
01287           if python3 or type(_x) == unicode:
01288             _x = _x.encode('utf-8')
01289             length = len(_x)
01290           buff.write(struct.pack('<I%ss'%length, length, _x))
01291           length = len(_v22.points)
01292           buff.write(_struct_I.pack(length))
01293           for val4 in _v22.points:
01294             _x = val4
01295             buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
01296           length = len(_v22.channels)
01297           buff.write(_struct_I.pack(length))
01298           for val4 in _v22.channels:
01299             _x = val4.name
01300             length = len(_x)
01301             if python3 or type(_x) == unicode:
01302               _x = _x.encode('utf-8')
01303               length = len(_x)
01304             buff.write(struct.pack('<I%ss'%length, length, _x))
01305             length = len(val4.values)
01306             buff.write(_struct_I.pack(length))
01307             pattern = '<%sf'%length
01308             buff.write(struct.pack(pattern, *val4.values))
01309           _v25 = val2.region
01310           _v26 = _v25.cloud
01311           _v27 = _v26.header
01312           buff.write(_struct_I.pack(_v27.seq))
01313           _v28 = _v27.stamp
01314           _x = _v28
01315           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01316           _x = _v27.frame_id
01317           length = len(_x)
01318           if python3 or type(_x) == unicode:
01319             _x = _x.encode('utf-8')
01320             length = len(_x)
01321           buff.write(struct.pack('<I%ss'%length, length, _x))
01322           _x = _v26
01323           buff.write(_struct_2I.pack(_x.height, _x.width))
01324           length = len(_v26.fields)
01325           buff.write(_struct_I.pack(length))
01326           for val5 in _v26.fields:
01327             _x = val5.name
01328             length = len(_x)
01329             if python3 or type(_x) == unicode:
01330               _x = _x.encode('utf-8')
01331               length = len(_x)
01332             buff.write(struct.pack('<I%ss'%length, length, _x))
01333             _x = val5
01334             buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
01335           _x = _v26
01336           buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
01337           _x = _v26.data
01338           length = len(_x)
01339           # - if encoded as a list instead, serialize as bytes instead of string
01340           if type(_x) in [list, tuple]:
01341             buff.write(struct.pack('<I%sB'%length, length, *_x))
01342           else:
01343             buff.write(struct.pack('<I%ss'%length, length, _x))
01344           buff.write(_struct_B.pack(_v26.is_dense))
01345           length = len(_v25.mask)
01346           buff.write(_struct_I.pack(length))
01347           pattern = '<%si'%length
01348           buff.write(struct.pack(pattern, *_v25.mask))
01349           _v29 = _v25.image
01350           _v30 = _v29.header
01351           buff.write(_struct_I.pack(_v30.seq))
01352           _v31 = _v30.stamp
01353           _x = _v31
01354           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01355           _x = _v30.frame_id
01356           length = len(_x)
01357           if python3 or type(_x) == unicode:
01358             _x = _x.encode('utf-8')
01359             length = len(_x)
01360           buff.write(struct.pack('<I%ss'%length, length, _x))
01361           _x = _v29
01362           buff.write(_struct_2I.pack(_x.height, _x.width))
01363           _x = _v29.encoding
01364           length = len(_x)
01365           if python3 or type(_x) == unicode:
01366             _x = _x.encode('utf-8')
01367             length = len(_x)
01368           buff.write(struct.pack('<I%ss'%length, length, _x))
01369           _x = _v29
01370           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
01371           _x = _v29.data
01372           length = len(_x)
01373           # - if encoded as a list instead, serialize as bytes instead of string
01374           if type(_x) in [list, tuple]:
01375             buff.write(struct.pack('<I%sB'%length, length, *_x))
01376           else:
01377             buff.write(struct.pack('<I%ss'%length, length, _x))
01378           _v32 = _v25.disparity_image
01379           _v33 = _v32.header
01380           buff.write(_struct_I.pack(_v33.seq))
01381           _v34 = _v33.stamp
01382           _x = _v34
01383           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01384           _x = _v33.frame_id
01385           length = len(_x)
01386           if python3 or type(_x) == unicode:
01387             _x = _x.encode('utf-8')
01388             length = len(_x)
01389           buff.write(struct.pack('<I%ss'%length, length, _x))
01390           _x = _v32
01391           buff.write(_struct_2I.pack(_x.height, _x.width))
01392           _x = _v32.encoding
01393           length = len(_x)
01394           if python3 or type(_x) == unicode:
01395             _x = _x.encode('utf-8')
01396             length = len(_x)
01397           buff.write(struct.pack('<I%ss'%length, length, _x))
01398           _x = _v32
01399           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
01400           _x = _v32.data
01401           length = len(_x)
01402           # - if encoded as a list instead, serialize as bytes instead of string
01403           if type(_x) in [list, tuple]:
01404             buff.write(struct.pack('<I%sB'%length, length, *_x))
01405           else:
01406             buff.write(struct.pack('<I%ss'%length, length, _x))
01407           _v35 = _v25.cam_info
01408           _v36 = _v35.header
01409           buff.write(_struct_I.pack(_v36.seq))
01410           _v37 = _v36.stamp
01411           _x = _v37
01412           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01413           _x = _v36.frame_id
01414           length = len(_x)
01415           if python3 or type(_x) == unicode:
01416             _x = _x.encode('utf-8')
01417             length = len(_x)
01418           buff.write(struct.pack('<I%ss'%length, length, _x))
01419           _x = _v35
01420           buff.write(_struct_2I.pack(_x.height, _x.width))
01421           _x = _v35.distortion_model
01422           length = len(_x)
01423           if python3 or type(_x) == unicode:
01424             _x = _x.encode('utf-8')
01425             length = len(_x)
01426           buff.write(struct.pack('<I%ss'%length, length, _x))
01427           length = len(_v35.D)
01428           buff.write(_struct_I.pack(length))
01429           pattern = '<%sd'%length
01430           buff.write(struct.pack(pattern, *_v35.D))
01431           buff.write(_struct_9d.pack(*_v35.K))
01432           buff.write(_struct_9d.pack(*_v35.R))
01433           buff.write(_struct_12d.pack(*_v35.P))
01434           _x = _v35
01435           buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
01436           _v38 = _v35.roi
01437           _x = _v38
01438           buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
01439           _v39 = _v25.roi_box_pose
01440           _v40 = _v39.header
01441           buff.write(_struct_I.pack(_v40.seq))
01442           _v41 = _v40.stamp
01443           _x = _v41
01444           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01445           _x = _v40.frame_id
01446           length = len(_x)
01447           if python3 or type(_x) == unicode:
01448             _x = _x.encode('utf-8')
01449             length = len(_x)
01450           buff.write(struct.pack('<I%ss'%length, length, _x))
01451           _v42 = _v39.pose
01452           _v43 = _v42.position
01453           _x = _v43
01454           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01455           _v44 = _v42.orientation
01456           _x = _v44
01457           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01458           _v45 = _v25.roi_box_dims
01459           _x = _v45
01460           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01461           _x = val2.collision_name
01462           length = len(_x)
01463           if python3 or type(_x) == unicode:
01464             _x = _x.encode('utf-8')
01465             length = len(_x)
01466           buff.write(struct.pack('<I%ss'%length, length, _x))
01467       _x = self
01468       buff.write(_struct_3I.pack(_x.action_goal.goal.lift.direction.header.seq, _x.action_goal.goal.lift.direction.header.stamp.secs, _x.action_goal.goal.lift.direction.header.stamp.nsecs))
01469       _x = self.action_goal.goal.lift.direction.header.frame_id
01470       length = len(_x)
01471       if python3 or type(_x) == unicode:
01472         _x = _x.encode('utf-8')
01473         length = len(_x)
01474       buff.write(struct.pack('<I%ss'%length, length, _x))
01475       _x = self
01476       buff.write(_struct_3d2f.pack(_x.action_goal.goal.lift.direction.vector.x, _x.action_goal.goal.lift.direction.vector.y, _x.action_goal.goal.lift.direction.vector.z, _x.action_goal.goal.lift.desired_distance, _x.action_goal.goal.lift.min_distance))
01477       _x = self.action_goal.goal.collision_object_name
01478       length = len(_x)
01479       if python3 or type(_x) == unicode:
01480         _x = _x.encode('utf-8')
01481         length = len(_x)
01482       buff.write(struct.pack('<I%ss'%length, length, _x))
01483       _x = self.action_goal.goal.collision_support_surface_name
01484       length = len(_x)
01485       if python3 or type(_x) == unicode:
01486         _x = _x.encode('utf-8')
01487         length = len(_x)
01488       buff.write(struct.pack('<I%ss'%length, length, _x))
01489       _x = self
01490       buff.write(_struct_5B.pack(_x.action_goal.goal.allow_gripper_support_collision, _x.action_goal.goal.use_reactive_execution, _x.action_goal.goal.use_reactive_lift, _x.action_goal.goal.only_perform_feasibility_test, _x.action_goal.goal.ignore_collisions))
01491       length = len(self.action_goal.goal.path_constraints.joint_constraints)
01492       buff.write(_struct_I.pack(length))
01493       for val1 in self.action_goal.goal.path_constraints.joint_constraints:
01494         _x = val1.joint_name
01495         length = len(_x)
01496         if python3 or type(_x) == unicode:
01497           _x = _x.encode('utf-8')
01498           length = len(_x)
01499         buff.write(struct.pack('<I%ss'%length, length, _x))
01500         _x = val1
01501         buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
01502       length = len(self.action_goal.goal.path_constraints.position_constraints)
01503       buff.write(_struct_I.pack(length))
01504       for val1 in self.action_goal.goal.path_constraints.position_constraints:
01505         _v46 = val1.header
01506         buff.write(_struct_I.pack(_v46.seq))
01507         _v47 = _v46.stamp
01508         _x = _v47
01509         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01510         _x = _v46.frame_id
01511         length = len(_x)
01512         if python3 or type(_x) == unicode:
01513           _x = _x.encode('utf-8')
01514           length = len(_x)
01515         buff.write(struct.pack('<I%ss'%length, length, _x))
01516         _x = val1.link_name
01517         length = len(_x)
01518         if python3 or type(_x) == unicode:
01519           _x = _x.encode('utf-8')
01520           length = len(_x)
01521         buff.write(struct.pack('<I%ss'%length, length, _x))
01522         _v48 = val1.target_point_offset
01523         _x = _v48
01524         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01525         _v49 = val1.position
01526         _x = _v49
01527         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01528         _v50 = val1.constraint_region_shape
01529         buff.write(_struct_b.pack(_v50.type))
01530         length = len(_v50.dimensions)
01531         buff.write(_struct_I.pack(length))
01532         pattern = '<%sd'%length
01533         buff.write(struct.pack(pattern, *_v50.dimensions))
01534         length = len(_v50.triangles)
01535         buff.write(_struct_I.pack(length))
01536         pattern = '<%si'%length
01537         buff.write(struct.pack(pattern, *_v50.triangles))
01538         length = len(_v50.vertices)
01539         buff.write(_struct_I.pack(length))
01540         for val3 in _v50.vertices:
01541           _x = val3
01542           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01543         _v51 = val1.constraint_region_orientation
01544         _x = _v51
01545         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01546         buff.write(_struct_d.pack(val1.weight))
01547       length = len(self.action_goal.goal.path_constraints.orientation_constraints)
01548       buff.write(_struct_I.pack(length))
01549       for val1 in self.action_goal.goal.path_constraints.orientation_constraints:
01550         _v52 = val1.header
01551         buff.write(_struct_I.pack(_v52.seq))
01552         _v53 = _v52.stamp
01553         _x = _v53
01554         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01555         _x = _v52.frame_id
01556         length = len(_x)
01557         if python3 or type(_x) == unicode:
01558           _x = _x.encode('utf-8')
01559           length = len(_x)
01560         buff.write(struct.pack('<I%ss'%length, length, _x))
01561         _x = val1.link_name
01562         length = len(_x)
01563         if python3 or type(_x) == unicode:
01564           _x = _x.encode('utf-8')
01565           length = len(_x)
01566         buff.write(struct.pack('<I%ss'%length, length, _x))
01567         buff.write(_struct_i.pack(val1.type))
01568         _v54 = val1.orientation
01569         _x = _v54
01570         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01571         _x = val1
01572         buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
01573       length = len(self.action_goal.goal.path_constraints.visibility_constraints)
01574       buff.write(_struct_I.pack(length))
01575       for val1 in self.action_goal.goal.path_constraints.visibility_constraints:
01576         _v55 = val1.header
01577         buff.write(_struct_I.pack(_v55.seq))
01578         _v56 = _v55.stamp
01579         _x = _v56
01580         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01581         _x = _v55.frame_id
01582         length = len(_x)
01583         if python3 or type(_x) == unicode:
01584           _x = _x.encode('utf-8')
01585           length = len(_x)
01586         buff.write(struct.pack('<I%ss'%length, length, _x))
01587         _v57 = val1.target
01588         _v58 = _v57.header
01589         buff.write(_struct_I.pack(_v58.seq))
01590         _v59 = _v58.stamp
01591         _x = _v59
01592         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01593         _x = _v58.frame_id
01594         length = len(_x)
01595         if python3 or type(_x) == unicode:
01596           _x = _x.encode('utf-8')
01597           length = len(_x)
01598         buff.write(struct.pack('<I%ss'%length, length, _x))
01599         _v60 = _v57.point
01600         _x = _v60
01601         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01602         _v61 = val1.sensor_pose
01603         _v62 = _v61.header
01604         buff.write(_struct_I.pack(_v62.seq))
01605         _v63 = _v62.stamp
01606         _x = _v63
01607         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01608         _x = _v62.frame_id
01609         length = len(_x)
01610         if python3 or type(_x) == unicode:
01611           _x = _x.encode('utf-8')
01612           length = len(_x)
01613         buff.write(struct.pack('<I%ss'%length, length, _x))
01614         _v64 = _v61.pose
01615         _v65 = _v64.position
01616         _x = _v65
01617         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01618         _v66 = _v64.orientation
01619         _x = _v66
01620         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01621         buff.write(_struct_d.pack(val1.absolute_tolerance))
01622       length = len(self.action_goal.goal.additional_collision_operations.collision_operations)
01623       buff.write(_struct_I.pack(length))
01624       for val1 in self.action_goal.goal.additional_collision_operations.collision_operations:
01625         _x = val1.object1
01626         length = len(_x)
01627         if python3 or type(_x) == unicode:
01628           _x = _x.encode('utf-8')
01629           length = len(_x)
01630         buff.write(struct.pack('<I%ss'%length, length, _x))
01631         _x = val1.object2
01632         length = len(_x)
01633         if python3 or type(_x) == unicode:
01634           _x = _x.encode('utf-8')
01635           length = len(_x)
01636         buff.write(struct.pack('<I%ss'%length, length, _x))
01637         _x = val1
01638         buff.write(_struct_di.pack(_x.penetration_distance, _x.operation))
01639       length = len(self.action_goal.goal.additional_link_padding)
01640       buff.write(_struct_I.pack(length))
01641       for val1 in self.action_goal.goal.additional_link_padding:
01642         _x = val1.link_name
01643         length = len(_x)
01644         if python3 or type(_x) == unicode:
01645           _x = _x.encode('utf-8')
01646           length = len(_x)
01647         buff.write(struct.pack('<I%ss'%length, length, _x))
01648         buff.write(_struct_d.pack(val1.padding))
01649       length = len(self.action_goal.goal.movable_obstacles)
01650       buff.write(_struct_I.pack(length))
01651       for val1 in self.action_goal.goal.movable_obstacles:
01652         _x = val1.reference_frame_id
01653         length = len(_x)
01654         if python3 or type(_x) == unicode:
01655           _x = _x.encode('utf-8')
01656           length = len(_x)
01657         buff.write(struct.pack('<I%ss'%length, length, _x))
01658         length = len(val1.potential_models)
01659         buff.write(_struct_I.pack(length))
01660         for val2 in val1.potential_models:
01661           buff.write(_struct_i.pack(val2.model_id))
01662           _v67 = val2.pose
01663           _v68 = _v67.header
01664           buff.write(_struct_I.pack(_v68.seq))
01665           _v69 = _v68.stamp
01666           _x = _v69
01667           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01668           _x = _v68.frame_id
01669           length = len(_x)
01670           if python3 or type(_x) == unicode:
01671             _x = _x.encode('utf-8')
01672             length = len(_x)
01673           buff.write(struct.pack('<I%ss'%length, length, _x))
01674           _v70 = _v67.pose
01675           _v71 = _v70.position
01676           _x = _v71
01677           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01678           _v72 = _v70.orientation
01679           _x = _v72
01680           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01681           buff.write(_struct_f.pack(val2.confidence))
01682           _x = val2.detector_name
01683           length = len(_x)
01684           if python3 or type(_x) == unicode:
01685             _x = _x.encode('utf-8')
01686             length = len(_x)
01687           buff.write(struct.pack('<I%ss'%length, length, _x))
01688         _v73 = val1.cluster
01689         _v74 = _v73.header
01690         buff.write(_struct_I.pack(_v74.seq))
01691         _v75 = _v74.stamp
01692         _x = _v75
01693         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01694         _x = _v74.frame_id
01695         length = len(_x)
01696         if python3 or type(_x) == unicode:
01697           _x = _x.encode('utf-8')
01698           length = len(_x)
01699         buff.write(struct.pack('<I%ss'%length, length, _x))
01700         length = len(_v73.points)
01701         buff.write(_struct_I.pack(length))
01702         for val3 in _v73.points:
01703           _x = val3
01704           buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
01705         length = len(_v73.channels)
01706         buff.write(_struct_I.pack(length))
01707         for val3 in _v73.channels:
01708           _x = val3.name
01709           length = len(_x)
01710           if python3 or type(_x) == unicode:
01711             _x = _x.encode('utf-8')
01712             length = len(_x)
01713           buff.write(struct.pack('<I%ss'%length, length, _x))
01714           length = len(val3.values)
01715           buff.write(_struct_I.pack(length))
01716           pattern = '<%sf'%length
01717           buff.write(struct.pack(pattern, *val3.values))
01718         _v76 = val1.region
01719         _v77 = _v76.cloud
01720         _v78 = _v77.header
01721         buff.write(_struct_I.pack(_v78.seq))
01722         _v79 = _v78.stamp
01723         _x = _v79
01724         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01725         _x = _v78.frame_id
01726         length = len(_x)
01727         if python3 or type(_x) == unicode:
01728           _x = _x.encode('utf-8')
01729           length = len(_x)
01730         buff.write(struct.pack('<I%ss'%length, length, _x))
01731         _x = _v77
01732         buff.write(_struct_2I.pack(_x.height, _x.width))
01733         length = len(_v77.fields)
01734         buff.write(_struct_I.pack(length))
01735         for val4 in _v77.fields:
01736           _x = val4.name
01737           length = len(_x)
01738           if python3 or type(_x) == unicode:
01739             _x = _x.encode('utf-8')
01740             length = len(_x)
01741           buff.write(struct.pack('<I%ss'%length, length, _x))
01742           _x = val4
01743           buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
01744         _x = _v77
01745         buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
01746         _x = _v77.data
01747         length = len(_x)
01748         # - if encoded as a list instead, serialize as bytes instead of string
01749         if type(_x) in [list, tuple]:
01750           buff.write(struct.pack('<I%sB'%length, length, *_x))
01751         else:
01752           buff.write(struct.pack('<I%ss'%length, length, _x))
01753         buff.write(_struct_B.pack(_v77.is_dense))
01754         length = len(_v76.mask)
01755         buff.write(_struct_I.pack(length))
01756         pattern = '<%si'%length
01757         buff.write(struct.pack(pattern, *_v76.mask))
01758         _v80 = _v76.image
01759         _v81 = _v80.header
01760         buff.write(_struct_I.pack(_v81.seq))
01761         _v82 = _v81.stamp
01762         _x = _v82
01763         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01764         _x = _v81.frame_id
01765         length = len(_x)
01766         if python3 or type(_x) == unicode:
01767           _x = _x.encode('utf-8')
01768           length = len(_x)
01769         buff.write(struct.pack('<I%ss'%length, length, _x))
01770         _x = _v80
01771         buff.write(_struct_2I.pack(_x.height, _x.width))
01772         _x = _v80.encoding
01773         length = len(_x)
01774         if python3 or type(_x) == unicode:
01775           _x = _x.encode('utf-8')
01776           length = len(_x)
01777         buff.write(struct.pack('<I%ss'%length, length, _x))
01778         _x = _v80
01779         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
01780         _x = _v80.data
01781         length = len(_x)
01782         # - if encoded as a list instead, serialize as bytes instead of string
01783         if type(_x) in [list, tuple]:
01784           buff.write(struct.pack('<I%sB'%length, length, *_x))
01785         else:
01786           buff.write(struct.pack('<I%ss'%length, length, _x))
01787         _v83 = _v76.disparity_image
01788         _v84 = _v83.header
01789         buff.write(_struct_I.pack(_v84.seq))
01790         _v85 = _v84.stamp
01791         _x = _v85
01792         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01793         _x = _v84.frame_id
01794         length = len(_x)
01795         if python3 or type(_x) == unicode:
01796           _x = _x.encode('utf-8')
01797           length = len(_x)
01798         buff.write(struct.pack('<I%ss'%length, length, _x))
01799         _x = _v83
01800         buff.write(_struct_2I.pack(_x.height, _x.width))
01801         _x = _v83.encoding
01802         length = len(_x)
01803         if python3 or type(_x) == unicode:
01804           _x = _x.encode('utf-8')
01805           length = len(_x)
01806         buff.write(struct.pack('<I%ss'%length, length, _x))
01807         _x = _v83
01808         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
01809         _x = _v83.data
01810         length = len(_x)
01811         # - if encoded as a list instead, serialize as bytes instead of string
01812         if type(_x) in [list, tuple]:
01813           buff.write(struct.pack('<I%sB'%length, length, *_x))
01814         else:
01815           buff.write(struct.pack('<I%ss'%length, length, _x))
01816         _v86 = _v76.cam_info
01817         _v87 = _v86.header
01818         buff.write(_struct_I.pack(_v87.seq))
01819         _v88 = _v87.stamp
01820         _x = _v88
01821         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01822         _x = _v87.frame_id
01823         length = len(_x)
01824         if python3 or type(_x) == unicode:
01825           _x = _x.encode('utf-8')
01826           length = len(_x)
01827         buff.write(struct.pack('<I%ss'%length, length, _x))
01828         _x = _v86
01829         buff.write(_struct_2I.pack(_x.height, _x.width))
01830         _x = _v86.distortion_model
01831         length = len(_x)
01832         if python3 or type(_x) == unicode:
01833           _x = _x.encode('utf-8')
01834           length = len(_x)
01835         buff.write(struct.pack('<I%ss'%length, length, _x))
01836         length = len(_v86.D)
01837         buff.write(_struct_I.pack(length))
01838         pattern = '<%sd'%length
01839         buff.write(struct.pack(pattern, *_v86.D))
01840         buff.write(_struct_9d.pack(*_v86.K))
01841         buff.write(_struct_9d.pack(*_v86.R))
01842         buff.write(_struct_12d.pack(*_v86.P))
01843         _x = _v86
01844         buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
01845         _v89 = _v86.roi
01846         _x = _v89
01847         buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
01848         _v90 = _v76.roi_box_pose
01849         _v91 = _v90.header
01850         buff.write(_struct_I.pack(_v91.seq))
01851         _v92 = _v91.stamp
01852         _x = _v92
01853         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01854         _x = _v91.frame_id
01855         length = len(_x)
01856         if python3 or type(_x) == unicode:
01857           _x = _x.encode('utf-8')
01858           length = len(_x)
01859         buff.write(struct.pack('<I%ss'%length, length, _x))
01860         _v93 = _v90.pose
01861         _v94 = _v93.position
01862         _x = _v94
01863         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01864         _v95 = _v93.orientation
01865         _x = _v95
01866         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01867         _v96 = _v76.roi_box_dims
01868         _x = _v96
01869         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01870         _x = val1.collision_name
01871         length = len(_x)
01872         if python3 or type(_x) == unicode:
01873           _x = _x.encode('utf-8')
01874           length = len(_x)
01875         buff.write(struct.pack('<I%ss'%length, length, _x))
01876       _x = self
01877       buff.write(_struct_f3I.pack(_x.action_goal.goal.max_contact_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
01878       _x = self.action_result.header.frame_id
01879       length = len(_x)
01880       if python3 or type(_x) == unicode:
01881         _x = _x.encode('utf-8')
01882         length = len(_x)
01883       buff.write(struct.pack('<I%ss'%length, length, _x))
01884       _x = self
01885       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
01886       _x = self.action_result.status.goal_id.id
01887       length = len(_x)
01888       if python3 or type(_x) == unicode:
01889         _x = _x.encode('utf-8')
01890         length = len(_x)
01891       buff.write(struct.pack('<I%ss'%length, length, _x))
01892       buff.write(_struct_B.pack(self.action_result.status.status))
01893       _x = self.action_result.status.text
01894       length = len(_x)
01895       if python3 or type(_x) == unicode:
01896         _x = _x.encode('utf-8')
01897         length = len(_x)
01898       buff.write(struct.pack('<I%ss'%length, length, _x))
01899       _x = self
01900       buff.write(_struct_i3I.pack(_x.action_result.result.manipulation_result.value, _x.action_result.result.grasp.pre_grasp_posture.header.seq, _x.action_result.result.grasp.pre_grasp_posture.header.stamp.secs, _x.action_result.result.grasp.pre_grasp_posture.header.stamp.nsecs))
01901       _x = self.action_result.result.grasp.pre_grasp_posture.header.frame_id
01902       length = len(_x)
01903       if python3 or type(_x) == unicode:
01904         _x = _x.encode('utf-8')
01905         length = len(_x)
01906       buff.write(struct.pack('<I%ss'%length, length, _x))
01907       length = len(self.action_result.result.grasp.pre_grasp_posture.name)
01908       buff.write(_struct_I.pack(length))
01909       for val1 in self.action_result.result.grasp.pre_grasp_posture.name:
01910         length = len(val1)
01911         if python3 or type(val1) == unicode:
01912           val1 = val1.encode('utf-8')
01913           length = len(val1)
01914         buff.write(struct.pack('<I%ss'%length, length, val1))
01915       length = len(self.action_result.result.grasp.pre_grasp_posture.position)
01916       buff.write(_struct_I.pack(length))
01917       pattern = '<%sd'%length
01918       buff.write(struct.pack(pattern, *self.action_result.result.grasp.pre_grasp_posture.position))
01919       length = len(self.action_result.result.grasp.pre_grasp_posture.velocity)
01920       buff.write(_struct_I.pack(length))
01921       pattern = '<%sd'%length
01922       buff.write(struct.pack(pattern, *self.action_result.result.grasp.pre_grasp_posture.velocity))
01923       length = len(self.action_result.result.grasp.pre_grasp_posture.effort)
01924       buff.write(_struct_I.pack(length))
01925       pattern = '<%sd'%length
01926       buff.write(struct.pack(pattern, *self.action_result.result.grasp.pre_grasp_posture.effort))
01927       _x = self
01928       buff.write(_struct_3I.pack(_x.action_result.result.grasp.grasp_posture.header.seq, _x.action_result.result.grasp.grasp_posture.header.stamp.secs, _x.action_result.result.grasp.grasp_posture.header.stamp.nsecs))
01929       _x = self.action_result.result.grasp.grasp_posture.header.frame_id
01930       length = len(_x)
01931       if python3 or type(_x) == unicode:
01932         _x = _x.encode('utf-8')
01933         length = len(_x)
01934       buff.write(struct.pack('<I%ss'%length, length, _x))
01935       length = len(self.action_result.result.grasp.grasp_posture.name)
01936       buff.write(_struct_I.pack(length))
01937       for val1 in self.action_result.result.grasp.grasp_posture.name:
01938         length = len(val1)
01939         if python3 or type(val1) == unicode:
01940           val1 = val1.encode('utf-8')
01941           length = len(val1)
01942         buff.write(struct.pack('<I%ss'%length, length, val1))
01943       length = len(self.action_result.result.grasp.grasp_posture.position)
01944       buff.write(_struct_I.pack(length))
01945       pattern = '<%sd'%length
01946       buff.write(struct.pack(pattern, *self.action_result.result.grasp.grasp_posture.position))
01947       length = len(self.action_result.result.grasp.grasp_posture.velocity)
01948       buff.write(_struct_I.pack(length))
01949       pattern = '<%sd'%length
01950       buff.write(struct.pack(pattern, *self.action_result.result.grasp.grasp_posture.velocity))
01951       length = len(self.action_result.result.grasp.grasp_posture.effort)
01952       buff.write(_struct_I.pack(length))
01953       pattern = '<%sd'%length
01954       buff.write(struct.pack(pattern, *self.action_result.result.grasp.grasp_posture.effort))
01955       _x = self
01956       buff.write(_struct_8dB2f.pack(_x.action_result.result.grasp.grasp_pose.position.x, _x.action_result.result.grasp.grasp_pose.position.y, _x.action_result.result.grasp.grasp_pose.position.z, _x.action_result.result.grasp.grasp_pose.orientation.x, _x.action_result.result.grasp.grasp_pose.orientation.y, _x.action_result.result.grasp.grasp_pose.orientation.z, _x.action_result.result.grasp.grasp_pose.orientation.w, _x.action_result.result.grasp.success_probability, _x.action_result.result.grasp.cluster_rep, _x.action_result.result.grasp.desired_approach_distance, _x.action_result.result.grasp.min_approach_distance))
01957       length = len(self.action_result.result.grasp.moved_obstacles)
01958       buff.write(_struct_I.pack(length))
01959       for val1 in self.action_result.result.grasp.moved_obstacles:
01960         _x = val1.reference_frame_id
01961         length = len(_x)
01962         if python3 or type(_x) == unicode:
01963           _x = _x.encode('utf-8')
01964           length = len(_x)
01965         buff.write(struct.pack('<I%ss'%length, length, _x))
01966         length = len(val1.potential_models)
01967         buff.write(_struct_I.pack(length))
01968         for val2 in val1.potential_models:
01969           buff.write(_struct_i.pack(val2.model_id))
01970           _v97 = val2.pose
01971           _v98 = _v97.header
01972           buff.write(_struct_I.pack(_v98.seq))
01973           _v99 = _v98.stamp
01974           _x = _v99
01975           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01976           _x = _v98.frame_id
01977           length = len(_x)
01978           if python3 or type(_x) == unicode:
01979             _x = _x.encode('utf-8')
01980             length = len(_x)
01981           buff.write(struct.pack('<I%ss'%length, length, _x))
01982           _v100 = _v97.pose
01983           _v101 = _v100.position
01984           _x = _v101
01985           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01986           _v102 = _v100.orientation
01987           _x = _v102
01988           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01989           buff.write(_struct_f.pack(val2.confidence))
01990           _x = val2.detector_name
01991           length = len(_x)
01992           if python3 or type(_x) == unicode:
01993             _x = _x.encode('utf-8')
01994             length = len(_x)
01995           buff.write(struct.pack('<I%ss'%length, length, _x))
01996         _v103 = val1.cluster
01997         _v104 = _v103.header
01998         buff.write(_struct_I.pack(_v104.seq))
01999         _v105 = _v104.stamp
02000         _x = _v105
02001         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02002         _x = _v104.frame_id
02003         length = len(_x)
02004         if python3 or type(_x) == unicode:
02005           _x = _x.encode('utf-8')
02006           length = len(_x)
02007         buff.write(struct.pack('<I%ss'%length, length, _x))
02008         length = len(_v103.points)
02009         buff.write(_struct_I.pack(length))
02010         for val3 in _v103.points:
02011           _x = val3
02012           buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
02013         length = len(_v103.channels)
02014         buff.write(_struct_I.pack(length))
02015         for val3 in _v103.channels:
02016           _x = val3.name
02017           length = len(_x)
02018           if python3 or type(_x) == unicode:
02019             _x = _x.encode('utf-8')
02020             length = len(_x)
02021           buff.write(struct.pack('<I%ss'%length, length, _x))
02022           length = len(val3.values)
02023           buff.write(_struct_I.pack(length))
02024           pattern = '<%sf'%length
02025           buff.write(struct.pack(pattern, *val3.values))
02026         _v106 = val1.region
02027         _v107 = _v106.cloud
02028         _v108 = _v107.header
02029         buff.write(_struct_I.pack(_v108.seq))
02030         _v109 = _v108.stamp
02031         _x = _v109
02032         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02033         _x = _v108.frame_id
02034         length = len(_x)
02035         if python3 or type(_x) == unicode:
02036           _x = _x.encode('utf-8')
02037           length = len(_x)
02038         buff.write(struct.pack('<I%ss'%length, length, _x))
02039         _x = _v107
02040         buff.write(_struct_2I.pack(_x.height, _x.width))
02041         length = len(_v107.fields)
02042         buff.write(_struct_I.pack(length))
02043         for val4 in _v107.fields:
02044           _x = val4.name
02045           length = len(_x)
02046           if python3 or type(_x) == unicode:
02047             _x = _x.encode('utf-8')
02048             length = len(_x)
02049           buff.write(struct.pack('<I%ss'%length, length, _x))
02050           _x = val4
02051           buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
02052         _x = _v107
02053         buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
02054         _x = _v107.data
02055         length = len(_x)
02056         # - if encoded as a list instead, serialize as bytes instead of string
02057         if type(_x) in [list, tuple]:
02058           buff.write(struct.pack('<I%sB'%length, length, *_x))
02059         else:
02060           buff.write(struct.pack('<I%ss'%length, length, _x))
02061         buff.write(_struct_B.pack(_v107.is_dense))
02062         length = len(_v106.mask)
02063         buff.write(_struct_I.pack(length))
02064         pattern = '<%si'%length
02065         buff.write(struct.pack(pattern, *_v106.mask))
02066         _v110 = _v106.image
02067         _v111 = _v110.header
02068         buff.write(_struct_I.pack(_v111.seq))
02069         _v112 = _v111.stamp
02070         _x = _v112
02071         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02072         _x = _v111.frame_id
02073         length = len(_x)
02074         if python3 or type(_x) == unicode:
02075           _x = _x.encode('utf-8')
02076           length = len(_x)
02077         buff.write(struct.pack('<I%ss'%length, length, _x))
02078         _x = _v110
02079         buff.write(_struct_2I.pack(_x.height, _x.width))
02080         _x = _v110.encoding
02081         length = len(_x)
02082         if python3 or type(_x) == unicode:
02083           _x = _x.encode('utf-8')
02084           length = len(_x)
02085         buff.write(struct.pack('<I%ss'%length, length, _x))
02086         _x = _v110
02087         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
02088         _x = _v110.data
02089         length = len(_x)
02090         # - if encoded as a list instead, serialize as bytes instead of string
02091         if type(_x) in [list, tuple]:
02092           buff.write(struct.pack('<I%sB'%length, length, *_x))
02093         else:
02094           buff.write(struct.pack('<I%ss'%length, length, _x))
02095         _v113 = _v106.disparity_image
02096         _v114 = _v113.header
02097         buff.write(_struct_I.pack(_v114.seq))
02098         _v115 = _v114.stamp
02099         _x = _v115
02100         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02101         _x = _v114.frame_id
02102         length = len(_x)
02103         if python3 or type(_x) == unicode:
02104           _x = _x.encode('utf-8')
02105           length = len(_x)
02106         buff.write(struct.pack('<I%ss'%length, length, _x))
02107         _x = _v113
02108         buff.write(_struct_2I.pack(_x.height, _x.width))
02109         _x = _v113.encoding
02110         length = len(_x)
02111         if python3 or type(_x) == unicode:
02112           _x = _x.encode('utf-8')
02113           length = len(_x)
02114         buff.write(struct.pack('<I%ss'%length, length, _x))
02115         _x = _v113
02116         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
02117         _x = _v113.data
02118         length = len(_x)
02119         # - if encoded as a list instead, serialize as bytes instead of string
02120         if type(_x) in [list, tuple]:
02121           buff.write(struct.pack('<I%sB'%length, length, *_x))
02122         else:
02123           buff.write(struct.pack('<I%ss'%length, length, _x))
02124         _v116 = _v106.cam_info
02125         _v117 = _v116.header
02126         buff.write(_struct_I.pack(_v117.seq))
02127         _v118 = _v117.stamp
02128         _x = _v118
02129         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02130         _x = _v117.frame_id
02131         length = len(_x)
02132         if python3 or type(_x) == unicode:
02133           _x = _x.encode('utf-8')
02134           length = len(_x)
02135         buff.write(struct.pack('<I%ss'%length, length, _x))
02136         _x = _v116
02137         buff.write(_struct_2I.pack(_x.height, _x.width))
02138         _x = _v116.distortion_model
02139         length = len(_x)
02140         if python3 or type(_x) == unicode:
02141           _x = _x.encode('utf-8')
02142           length = len(_x)
02143         buff.write(struct.pack('<I%ss'%length, length, _x))
02144         length = len(_v116.D)
02145         buff.write(_struct_I.pack(length))
02146         pattern = '<%sd'%length
02147         buff.write(struct.pack(pattern, *_v116.D))
02148         buff.write(_struct_9d.pack(*_v116.K))
02149         buff.write(_struct_9d.pack(*_v116.R))
02150         buff.write(_struct_12d.pack(*_v116.P))
02151         _x = _v116
02152         buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
02153         _v119 = _v116.roi
02154         _x = _v119
02155         buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
02156         _v120 = _v106.roi_box_pose
02157         _v121 = _v120.header
02158         buff.write(_struct_I.pack(_v121.seq))
02159         _v122 = _v121.stamp
02160         _x = _v122
02161         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02162         _x = _v121.frame_id
02163         length = len(_x)
02164         if python3 or type(_x) == unicode:
02165           _x = _x.encode('utf-8')
02166           length = len(_x)
02167         buff.write(struct.pack('<I%ss'%length, length, _x))
02168         _v123 = _v120.pose
02169         _v124 = _v123.position
02170         _x = _v124
02171         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02172         _v125 = _v123.orientation
02173         _x = _v125
02174         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02175         _v126 = _v106.roi_box_dims
02176         _x = _v126
02177         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02178         _x = val1.collision_name
02179         length = len(_x)
02180         if python3 or type(_x) == unicode:
02181           _x = _x.encode('utf-8')
02182           length = len(_x)
02183         buff.write(struct.pack('<I%ss'%length, length, _x))
02184       length = len(self.action_result.result.attempted_grasps)
02185       buff.write(_struct_I.pack(length))
02186       for val1 in self.action_result.result.attempted_grasps:
02187         _v127 = val1.pre_grasp_posture
02188         _v128 = _v127.header
02189         buff.write(_struct_I.pack(_v128.seq))
02190         _v129 = _v128.stamp
02191         _x = _v129
02192         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02193         _x = _v128.frame_id
02194         length = len(_x)
02195         if python3 or type(_x) == unicode:
02196           _x = _x.encode('utf-8')
02197           length = len(_x)
02198         buff.write(struct.pack('<I%ss'%length, length, _x))
02199         length = len(_v127.name)
02200         buff.write(_struct_I.pack(length))
02201         for val3 in _v127.name:
02202           length = len(val3)
02203           if python3 or type(val3) == unicode:
02204             val3 = val3.encode('utf-8')
02205             length = len(val3)
02206           buff.write(struct.pack('<I%ss'%length, length, val3))
02207         length = len(_v127.position)
02208         buff.write(_struct_I.pack(length))
02209         pattern = '<%sd'%length
02210         buff.write(struct.pack(pattern, *_v127.position))
02211         length = len(_v127.velocity)
02212         buff.write(_struct_I.pack(length))
02213         pattern = '<%sd'%length
02214         buff.write(struct.pack(pattern, *_v127.velocity))
02215         length = len(_v127.effort)
02216         buff.write(_struct_I.pack(length))
02217         pattern = '<%sd'%length
02218         buff.write(struct.pack(pattern, *_v127.effort))
02219         _v130 = val1.grasp_posture
02220         _v131 = _v130.header
02221         buff.write(_struct_I.pack(_v131.seq))
02222         _v132 = _v131.stamp
02223         _x = _v132
02224         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02225         _x = _v131.frame_id
02226         length = len(_x)
02227         if python3 or type(_x) == unicode:
02228           _x = _x.encode('utf-8')
02229           length = len(_x)
02230         buff.write(struct.pack('<I%ss'%length, length, _x))
02231         length = len(_v130.name)
02232         buff.write(_struct_I.pack(length))
02233         for val3 in _v130.name:
02234           length = len(val3)
02235           if python3 or type(val3) == unicode:
02236             val3 = val3.encode('utf-8')
02237             length = len(val3)
02238           buff.write(struct.pack('<I%ss'%length, length, val3))
02239         length = len(_v130.position)
02240         buff.write(_struct_I.pack(length))
02241         pattern = '<%sd'%length
02242         buff.write(struct.pack(pattern, *_v130.position))
02243         length = len(_v130.velocity)
02244         buff.write(_struct_I.pack(length))
02245         pattern = '<%sd'%length
02246         buff.write(struct.pack(pattern, *_v130.velocity))
02247         length = len(_v130.effort)
02248         buff.write(_struct_I.pack(length))
02249         pattern = '<%sd'%length
02250         buff.write(struct.pack(pattern, *_v130.effort))
02251         _v133 = val1.grasp_pose
02252         _v134 = _v133.position
02253         _x = _v134
02254         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02255         _v135 = _v133.orientation
02256         _x = _v135
02257         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02258         _x = val1
02259         buff.write(_struct_dB2f.pack(_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance))
02260         length = len(val1.moved_obstacles)
02261         buff.write(_struct_I.pack(length))
02262         for val2 in val1.moved_obstacles:
02263           _x = val2.reference_frame_id
02264           length = len(_x)
02265           if python3 or type(_x) == unicode:
02266             _x = _x.encode('utf-8')
02267             length = len(_x)
02268           buff.write(struct.pack('<I%ss'%length, length, _x))
02269           length = len(val2.potential_models)
02270           buff.write(_struct_I.pack(length))
02271           for val3 in val2.potential_models:
02272             buff.write(_struct_i.pack(val3.model_id))
02273             _v136 = val3.pose
02274             _v137 = _v136.header
02275             buff.write(_struct_I.pack(_v137.seq))
02276             _v138 = _v137.stamp
02277             _x = _v138
02278             buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02279             _x = _v137.frame_id
02280             length = len(_x)
02281             if python3 or type(_x) == unicode:
02282               _x = _x.encode('utf-8')
02283               length = len(_x)
02284             buff.write(struct.pack('<I%ss'%length, length, _x))
02285             _v139 = _v136.pose
02286             _v140 = _v139.position
02287             _x = _v140
02288             buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02289             _v141 = _v139.orientation
02290             _x = _v141
02291             buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02292             buff.write(_struct_f.pack(val3.confidence))
02293             _x = val3.detector_name
02294             length = len(_x)
02295             if python3 or type(_x) == unicode:
02296               _x = _x.encode('utf-8')
02297               length = len(_x)
02298             buff.write(struct.pack('<I%ss'%length, length, _x))
02299           _v142 = val2.cluster
02300           _v143 = _v142.header
02301           buff.write(_struct_I.pack(_v143.seq))
02302           _v144 = _v143.stamp
02303           _x = _v144
02304           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02305           _x = _v143.frame_id
02306           length = len(_x)
02307           if python3 or type(_x) == unicode:
02308             _x = _x.encode('utf-8')
02309             length = len(_x)
02310           buff.write(struct.pack('<I%ss'%length, length, _x))
02311           length = len(_v142.points)
02312           buff.write(_struct_I.pack(length))
02313           for val4 in _v142.points:
02314             _x = val4
02315             buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
02316           length = len(_v142.channels)
02317           buff.write(_struct_I.pack(length))
02318           for val4 in _v142.channels:
02319             _x = val4.name
02320             length = len(_x)
02321             if python3 or type(_x) == unicode:
02322               _x = _x.encode('utf-8')
02323               length = len(_x)
02324             buff.write(struct.pack('<I%ss'%length, length, _x))
02325             length = len(val4.values)
02326             buff.write(_struct_I.pack(length))
02327             pattern = '<%sf'%length
02328             buff.write(struct.pack(pattern, *val4.values))
02329           _v145 = val2.region
02330           _v146 = _v145.cloud
02331           _v147 = _v146.header
02332           buff.write(_struct_I.pack(_v147.seq))
02333           _v148 = _v147.stamp
02334           _x = _v148
02335           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02336           _x = _v147.frame_id
02337           length = len(_x)
02338           if python3 or type(_x) == unicode:
02339             _x = _x.encode('utf-8')
02340             length = len(_x)
02341           buff.write(struct.pack('<I%ss'%length, length, _x))
02342           _x = _v146
02343           buff.write(_struct_2I.pack(_x.height, _x.width))
02344           length = len(_v146.fields)
02345           buff.write(_struct_I.pack(length))
02346           for val5 in _v146.fields:
02347             _x = val5.name
02348             length = len(_x)
02349             if python3 or type(_x) == unicode:
02350               _x = _x.encode('utf-8')
02351               length = len(_x)
02352             buff.write(struct.pack('<I%ss'%length, length, _x))
02353             _x = val5
02354             buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
02355           _x = _v146
02356           buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
02357           _x = _v146.data
02358           length = len(_x)
02359           # - if encoded as a list instead, serialize as bytes instead of string
02360           if type(_x) in [list, tuple]:
02361             buff.write(struct.pack('<I%sB'%length, length, *_x))
02362           else:
02363             buff.write(struct.pack('<I%ss'%length, length, _x))
02364           buff.write(_struct_B.pack(_v146.is_dense))
02365           length = len(_v145.mask)
02366           buff.write(_struct_I.pack(length))
02367           pattern = '<%si'%length
02368           buff.write(struct.pack(pattern, *_v145.mask))
02369           _v149 = _v145.image
02370           _v150 = _v149.header
02371           buff.write(_struct_I.pack(_v150.seq))
02372           _v151 = _v150.stamp
02373           _x = _v151
02374           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02375           _x = _v150.frame_id
02376           length = len(_x)
02377           if python3 or type(_x) == unicode:
02378             _x = _x.encode('utf-8')
02379             length = len(_x)
02380           buff.write(struct.pack('<I%ss'%length, length, _x))
02381           _x = _v149
02382           buff.write(_struct_2I.pack(_x.height, _x.width))
02383           _x = _v149.encoding
02384           length = len(_x)
02385           if python3 or type(_x) == unicode:
02386             _x = _x.encode('utf-8')
02387             length = len(_x)
02388           buff.write(struct.pack('<I%ss'%length, length, _x))
02389           _x = _v149
02390           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
02391           _x = _v149.data
02392           length = len(_x)
02393           # - if encoded as a list instead, serialize as bytes instead of string
02394           if type(_x) in [list, tuple]:
02395             buff.write(struct.pack('<I%sB'%length, length, *_x))
02396           else:
02397             buff.write(struct.pack('<I%ss'%length, length, _x))
02398           _v152 = _v145.disparity_image
02399           _v153 = _v152.header
02400           buff.write(_struct_I.pack(_v153.seq))
02401           _v154 = _v153.stamp
02402           _x = _v154
02403           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02404           _x = _v153.frame_id
02405           length = len(_x)
02406           if python3 or type(_x) == unicode:
02407             _x = _x.encode('utf-8')
02408             length = len(_x)
02409           buff.write(struct.pack('<I%ss'%length, length, _x))
02410           _x = _v152
02411           buff.write(_struct_2I.pack(_x.height, _x.width))
02412           _x = _v152.encoding
02413           length = len(_x)
02414           if python3 or type(_x) == unicode:
02415             _x = _x.encode('utf-8')
02416             length = len(_x)
02417           buff.write(struct.pack('<I%ss'%length, length, _x))
02418           _x = _v152
02419           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
02420           _x = _v152.data
02421           length = len(_x)
02422           # - if encoded as a list instead, serialize as bytes instead of string
02423           if type(_x) in [list, tuple]:
02424             buff.write(struct.pack('<I%sB'%length, length, *_x))
02425           else:
02426             buff.write(struct.pack('<I%ss'%length, length, _x))
02427           _v155 = _v145.cam_info
02428           _v156 = _v155.header
02429           buff.write(_struct_I.pack(_v156.seq))
02430           _v157 = _v156.stamp
02431           _x = _v157
02432           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02433           _x = _v156.frame_id
02434           length = len(_x)
02435           if python3 or type(_x) == unicode:
02436             _x = _x.encode('utf-8')
02437             length = len(_x)
02438           buff.write(struct.pack('<I%ss'%length, length, _x))
02439           _x = _v155
02440           buff.write(_struct_2I.pack(_x.height, _x.width))
02441           _x = _v155.distortion_model
02442           length = len(_x)
02443           if python3 or type(_x) == unicode:
02444             _x = _x.encode('utf-8')
02445             length = len(_x)
02446           buff.write(struct.pack('<I%ss'%length, length, _x))
02447           length = len(_v155.D)
02448           buff.write(_struct_I.pack(length))
02449           pattern = '<%sd'%length
02450           buff.write(struct.pack(pattern, *_v155.D))
02451           buff.write(_struct_9d.pack(*_v155.K))
02452           buff.write(_struct_9d.pack(*_v155.R))
02453           buff.write(_struct_12d.pack(*_v155.P))
02454           _x = _v155
02455           buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
02456           _v158 = _v155.roi
02457           _x = _v158
02458           buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
02459           _v159 = _v145.roi_box_pose
02460           _v160 = _v159.header
02461           buff.write(_struct_I.pack(_v160.seq))
02462           _v161 = _v160.stamp
02463           _x = _v161
02464           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02465           _x = _v160.frame_id
02466           length = len(_x)
02467           if python3 or type(_x) == unicode:
02468             _x = _x.encode('utf-8')
02469             length = len(_x)
02470           buff.write(struct.pack('<I%ss'%length, length, _x))
02471           _v162 = _v159.pose
02472           _v163 = _v162.position
02473           _x = _v163
02474           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02475           _v164 = _v162.orientation
02476           _x = _v164
02477           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02478           _v165 = _v145.roi_box_dims
02479           _x = _v165
02480           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02481           _x = val2.collision_name
02482           length = len(_x)
02483           if python3 or type(_x) == unicode:
02484             _x = _x.encode('utf-8')
02485             length = len(_x)
02486           buff.write(struct.pack('<I%ss'%length, length, _x))
02487       length = len(self.action_result.result.attempted_grasp_results)
02488       buff.write(_struct_I.pack(length))
02489       for val1 in self.action_result.result.attempted_grasp_results:
02490         _x = val1
02491         buff.write(_struct_iB.pack(_x.result_code, _x.continuation_possible))
02492       _x = self
02493       buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
02494       _x = self.action_feedback.header.frame_id
02495       length = len(_x)
02496       if python3 or type(_x) == unicode:
02497         _x = _x.encode('utf-8')
02498         length = len(_x)
02499       buff.write(struct.pack('<I%ss'%length, length, _x))
02500       _x = self
02501       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
02502       _x = self.action_feedback.status.goal_id.id
02503       length = len(_x)
02504       if python3 or type(_x) == unicode:
02505         _x = _x.encode('utf-8')
02506         length = len(_x)
02507       buff.write(struct.pack('<I%ss'%length, length, _x))
02508       buff.write(_struct_B.pack(self.action_feedback.status.status))
02509       _x = self.action_feedback.status.text
02510       length = len(_x)
02511       if python3 or type(_x) == unicode:
02512         _x = _x.encode('utf-8')
02513         length = len(_x)
02514       buff.write(struct.pack('<I%ss'%length, length, _x))
02515       _x = self
02516       buff.write(_struct_2i.pack(_x.action_feedback.feedback.current_grasp, _x.action_feedback.feedback.total_grasps))
02517     except struct.error as se: self._check_types(se)
02518     except TypeError as te: self._check_types(te)
02519 
02520   def deserialize(self, str):
02521     """
02522     unpack serialized message in str into this message instance
02523     :param str: byte array of serialized message, ``str``
02524     """
02525     try:
02526       if self.action_goal is None:
02527         self.action_goal = object_manipulation_msgs.msg.PickupActionGoal()
02528       if self.action_result is None:
02529         self.action_result = object_manipulation_msgs.msg.PickupActionResult()
02530       if self.action_feedback is None:
02531         self.action_feedback = object_manipulation_msgs.msg.PickupActionFeedback()
02532       end = 0
02533       _x = self
02534       start = end
02535       end += 12
02536       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02537       start = end
02538       end += 4
02539       (length,) = _struct_I.unpack(str[start:end])
02540       start = end
02541       end += length
02542       if python3:
02543         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
02544       else:
02545         self.action_goal.header.frame_id = str[start:end]
02546       _x = self
02547       start = end
02548       end += 8
02549       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
02550       start = end
02551       end += 4
02552       (length,) = _struct_I.unpack(str[start:end])
02553       start = end
02554       end += length
02555       if python3:
02556         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
02557       else:
02558         self.action_goal.goal_id.id = str[start:end]
02559       start = end
02560       end += 4
02561       (length,) = _struct_I.unpack(str[start:end])
02562       start = end
02563       end += length
02564       if python3:
02565         self.action_goal.goal.arm_name = str[start:end].decode('utf-8')
02566       else:
02567         self.action_goal.goal.arm_name = str[start:end]
02568       start = end
02569       end += 4
02570       (length,) = _struct_I.unpack(str[start:end])
02571       start = end
02572       end += length
02573       if python3:
02574         self.action_goal.goal.target.reference_frame_id = str[start:end].decode('utf-8')
02575       else:
02576         self.action_goal.goal.target.reference_frame_id = str[start:end]
02577       start = end
02578       end += 4
02579       (length,) = _struct_I.unpack(str[start:end])
02580       self.action_goal.goal.target.potential_models = []
02581       for i in range(0, length):
02582         val1 = household_objects_database_msgs.msg.DatabaseModelPose()
02583         start = end
02584         end += 4
02585         (val1.model_id,) = _struct_i.unpack(str[start:end])
02586         _v166 = val1.pose
02587         _v167 = _v166.header
02588         start = end
02589         end += 4
02590         (_v167.seq,) = _struct_I.unpack(str[start:end])
02591         _v168 = _v167.stamp
02592         _x = _v168
02593         start = end
02594         end += 8
02595         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02596         start = end
02597         end += 4
02598         (length,) = _struct_I.unpack(str[start:end])
02599         start = end
02600         end += length
02601         if python3:
02602           _v167.frame_id = str[start:end].decode('utf-8')
02603         else:
02604           _v167.frame_id = str[start:end]
02605         _v169 = _v166.pose
02606         _v170 = _v169.position
02607         _x = _v170
02608         start = end
02609         end += 24
02610         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02611         _v171 = _v169.orientation
02612         _x = _v171
02613         start = end
02614         end += 32
02615         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02616         start = end
02617         end += 4
02618         (val1.confidence,) = _struct_f.unpack(str[start:end])
02619         start = end
02620         end += 4
02621         (length,) = _struct_I.unpack(str[start:end])
02622         start = end
02623         end += length
02624         if python3:
02625           val1.detector_name = str[start:end].decode('utf-8')
02626         else:
02627           val1.detector_name = str[start:end]
02628         self.action_goal.goal.target.potential_models.append(val1)
02629       _x = self
02630       start = end
02631       end += 12
02632       (_x.action_goal.goal.target.cluster.header.seq, _x.action_goal.goal.target.cluster.header.stamp.secs, _x.action_goal.goal.target.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02633       start = end
02634       end += 4
02635       (length,) = _struct_I.unpack(str[start:end])
02636       start = end
02637       end += length
02638       if python3:
02639         self.action_goal.goal.target.cluster.header.frame_id = str[start:end].decode('utf-8')
02640       else:
02641         self.action_goal.goal.target.cluster.header.frame_id = str[start:end]
02642       start = end
02643       end += 4
02644       (length,) = _struct_I.unpack(str[start:end])
02645       self.action_goal.goal.target.cluster.points = []
02646       for i in range(0, length):
02647         val1 = geometry_msgs.msg.Point32()
02648         _x = val1
02649         start = end
02650         end += 12
02651         (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
02652         self.action_goal.goal.target.cluster.points.append(val1)
02653       start = end
02654       end += 4
02655       (length,) = _struct_I.unpack(str[start:end])
02656       self.action_goal.goal.target.cluster.channels = []
02657       for i in range(0, length):
02658         val1 = sensor_msgs.msg.ChannelFloat32()
02659         start = end
02660         end += 4
02661         (length,) = _struct_I.unpack(str[start:end])
02662         start = end
02663         end += length
02664         if python3:
02665           val1.name = str[start:end].decode('utf-8')
02666         else:
02667           val1.name = str[start:end]
02668         start = end
02669         end += 4
02670         (length,) = _struct_I.unpack(str[start:end])
02671         pattern = '<%sf'%length
02672         start = end
02673         end += struct.calcsize(pattern)
02674         val1.values = struct.unpack(pattern, str[start:end])
02675         self.action_goal.goal.target.cluster.channels.append(val1)
02676       _x = self
02677       start = end
02678       end += 12
02679       (_x.action_goal.goal.target.region.cloud.header.seq, _x.action_goal.goal.target.region.cloud.header.stamp.secs, _x.action_goal.goal.target.region.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02680       start = end
02681       end += 4
02682       (length,) = _struct_I.unpack(str[start:end])
02683       start = end
02684       end += length
02685       if python3:
02686         self.action_goal.goal.target.region.cloud.header.frame_id = str[start:end].decode('utf-8')
02687       else:
02688         self.action_goal.goal.target.region.cloud.header.frame_id = str[start:end]
02689       _x = self
02690       start = end
02691       end += 8
02692       (_x.action_goal.goal.target.region.cloud.height, _x.action_goal.goal.target.region.cloud.width,) = _struct_2I.unpack(str[start:end])
02693       start = end
02694       end += 4
02695       (length,) = _struct_I.unpack(str[start:end])
02696       self.action_goal.goal.target.region.cloud.fields = []
02697       for i in range(0, length):
02698         val1 = sensor_msgs.msg.PointField()
02699         start = end
02700         end += 4
02701         (length,) = _struct_I.unpack(str[start:end])
02702         start = end
02703         end += length
02704         if python3:
02705           val1.name = str[start:end].decode('utf-8')
02706         else:
02707           val1.name = str[start:end]
02708         _x = val1
02709         start = end
02710         end += 9
02711         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
02712         self.action_goal.goal.target.region.cloud.fields.append(val1)
02713       _x = self
02714       start = end
02715       end += 9
02716       (_x.action_goal.goal.target.region.cloud.is_bigendian, _x.action_goal.goal.target.region.cloud.point_step, _x.action_goal.goal.target.region.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
02717       self.action_goal.goal.target.region.cloud.is_bigendian = bool(self.action_goal.goal.target.region.cloud.is_bigendian)
02718       start = end
02719       end += 4
02720       (length,) = _struct_I.unpack(str[start:end])
02721       start = end
02722       end += length
02723       if python3:
02724         self.action_goal.goal.target.region.cloud.data = str[start:end].decode('utf-8')
02725       else:
02726         self.action_goal.goal.target.region.cloud.data = str[start:end]
02727       start = end
02728       end += 1
02729       (self.action_goal.goal.target.region.cloud.is_dense,) = _struct_B.unpack(str[start:end])
02730       self.action_goal.goal.target.region.cloud.is_dense = bool(self.action_goal.goal.target.region.cloud.is_dense)
02731       start = end
02732       end += 4
02733       (length,) = _struct_I.unpack(str[start:end])
02734       pattern = '<%si'%length
02735       start = end
02736       end += struct.calcsize(pattern)
02737       self.action_goal.goal.target.region.mask = struct.unpack(pattern, str[start:end])
02738       _x = self
02739       start = end
02740       end += 12
02741       (_x.action_goal.goal.target.region.image.header.seq, _x.action_goal.goal.target.region.image.header.stamp.secs, _x.action_goal.goal.target.region.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02742       start = end
02743       end += 4
02744       (length,) = _struct_I.unpack(str[start:end])
02745       start = end
02746       end += length
02747       if python3:
02748         self.action_goal.goal.target.region.image.header.frame_id = str[start:end].decode('utf-8')
02749       else:
02750         self.action_goal.goal.target.region.image.header.frame_id = str[start:end]
02751       _x = self
02752       start = end
02753       end += 8
02754       (_x.action_goal.goal.target.region.image.height, _x.action_goal.goal.target.region.image.width,) = _struct_2I.unpack(str[start:end])
02755       start = end
02756       end += 4
02757       (length,) = _struct_I.unpack(str[start:end])
02758       start = end
02759       end += length
02760       if python3:
02761         self.action_goal.goal.target.region.image.encoding = str[start:end].decode('utf-8')
02762       else:
02763         self.action_goal.goal.target.region.image.encoding = str[start:end]
02764       _x = self
02765       start = end
02766       end += 5
02767       (_x.action_goal.goal.target.region.image.is_bigendian, _x.action_goal.goal.target.region.image.step,) = _struct_BI.unpack(str[start:end])
02768       start = end
02769       end += 4
02770       (length,) = _struct_I.unpack(str[start:end])
02771       start = end
02772       end += length
02773       if python3:
02774         self.action_goal.goal.target.region.image.data = str[start:end].decode('utf-8')
02775       else:
02776         self.action_goal.goal.target.region.image.data = str[start:end]
02777       _x = self
02778       start = end
02779       end += 12
02780       (_x.action_goal.goal.target.region.disparity_image.header.seq, _x.action_goal.goal.target.region.disparity_image.header.stamp.secs, _x.action_goal.goal.target.region.disparity_image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02781       start = end
02782       end += 4
02783       (length,) = _struct_I.unpack(str[start:end])
02784       start = end
02785       end += length
02786       if python3:
02787         self.action_goal.goal.target.region.disparity_image.header.frame_id = str[start:end].decode('utf-8')
02788       else:
02789         self.action_goal.goal.target.region.disparity_image.header.frame_id = str[start:end]
02790       _x = self
02791       start = end
02792       end += 8
02793       (_x.action_goal.goal.target.region.disparity_image.height, _x.action_goal.goal.target.region.disparity_image.width,) = _struct_2I.unpack(str[start:end])
02794       start = end
02795       end += 4
02796       (length,) = _struct_I.unpack(str[start:end])
02797       start = end
02798       end += length
02799       if python3:
02800         self.action_goal.goal.target.region.disparity_image.encoding = str[start:end].decode('utf-8')
02801       else:
02802         self.action_goal.goal.target.region.disparity_image.encoding = str[start:end]
02803       _x = self
02804       start = end
02805       end += 5
02806       (_x.action_goal.goal.target.region.disparity_image.is_bigendian, _x.action_goal.goal.target.region.disparity_image.step,) = _struct_BI.unpack(str[start:end])
02807       start = end
02808       end += 4
02809       (length,) = _struct_I.unpack(str[start:end])
02810       start = end
02811       end += length
02812       if python3:
02813         self.action_goal.goal.target.region.disparity_image.data = str[start:end].decode('utf-8')
02814       else:
02815         self.action_goal.goal.target.region.disparity_image.data = str[start:end]
02816       _x = self
02817       start = end
02818       end += 12
02819       (_x.action_goal.goal.target.region.cam_info.header.seq, _x.action_goal.goal.target.region.cam_info.header.stamp.secs, _x.action_goal.goal.target.region.cam_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02820       start = end
02821       end += 4
02822       (length,) = _struct_I.unpack(str[start:end])
02823       start = end
02824       end += length
02825       if python3:
02826         self.action_goal.goal.target.region.cam_info.header.frame_id = str[start:end].decode('utf-8')
02827       else:
02828         self.action_goal.goal.target.region.cam_info.header.frame_id = str[start:end]
02829       _x = self
02830       start = end
02831       end += 8
02832       (_x.action_goal.goal.target.region.cam_info.height, _x.action_goal.goal.target.region.cam_info.width,) = _struct_2I.unpack(str[start:end])
02833       start = end
02834       end += 4
02835       (length,) = _struct_I.unpack(str[start:end])
02836       start = end
02837       end += length
02838       if python3:
02839         self.action_goal.goal.target.region.cam_info.distortion_model = str[start:end].decode('utf-8')
02840       else:
02841         self.action_goal.goal.target.region.cam_info.distortion_model = str[start:end]
02842       start = end
02843       end += 4
02844       (length,) = _struct_I.unpack(str[start:end])
02845       pattern = '<%sd'%length
02846       start = end
02847       end += struct.calcsize(pattern)
02848       self.action_goal.goal.target.region.cam_info.D = struct.unpack(pattern, str[start:end])
02849       start = end
02850       end += 72
02851       self.action_goal.goal.target.region.cam_info.K = _struct_9d.unpack(str[start:end])
02852       start = end
02853       end += 72
02854       self.action_goal.goal.target.region.cam_info.R = _struct_9d.unpack(str[start:end])
02855       start = end
02856       end += 96
02857       self.action_goal.goal.target.region.cam_info.P = _struct_12d.unpack(str[start:end])
02858       _x = self
02859       start = end
02860       end += 37
02861       (_x.action_goal.goal.target.region.cam_info.binning_x, _x.action_goal.goal.target.region.cam_info.binning_y, _x.action_goal.goal.target.region.cam_info.roi.x_offset, _x.action_goal.goal.target.region.cam_info.roi.y_offset, _x.action_goal.goal.target.region.cam_info.roi.height, _x.action_goal.goal.target.region.cam_info.roi.width, _x.action_goal.goal.target.region.cam_info.roi.do_rectify, _x.action_goal.goal.target.region.roi_box_pose.header.seq, _x.action_goal.goal.target.region.roi_box_pose.header.stamp.secs, _x.action_goal.goal.target.region.roi_box_pose.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
02862       self.action_goal.goal.target.region.cam_info.roi.do_rectify = bool(self.action_goal.goal.target.region.cam_info.roi.do_rectify)
02863       start = end
02864       end += 4
02865       (length,) = _struct_I.unpack(str[start:end])
02866       start = end
02867       end += length
02868       if python3:
02869         self.action_goal.goal.target.region.roi_box_pose.header.frame_id = str[start:end].decode('utf-8')
02870       else:
02871         self.action_goal.goal.target.region.roi_box_pose.header.frame_id = str[start:end]
02872       _x = self
02873       start = end
02874       end += 80
02875       (_x.action_goal.goal.target.region.roi_box_pose.pose.position.x, _x.action_goal.goal.target.region.roi_box_pose.pose.position.y, _x.action_goal.goal.target.region.roi_box_pose.pose.position.z, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.x, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.y, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.z, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.w, _x.action_goal.goal.target.region.roi_box_dims.x, _x.action_goal.goal.target.region.roi_box_dims.y, _x.action_goal.goal.target.region.roi_box_dims.z,) = _struct_10d.unpack(str[start:end])
02876       start = end
02877       end += 4
02878       (length,) = _struct_I.unpack(str[start:end])
02879       start = end
02880       end += length
02881       if python3:
02882         self.action_goal.goal.target.collision_name = str[start:end].decode('utf-8')
02883       else:
02884         self.action_goal.goal.target.collision_name = str[start:end]
02885       start = end
02886       end += 4
02887       (length,) = _struct_I.unpack(str[start:end])
02888       self.action_goal.goal.desired_grasps = []
02889       for i in range(0, length):
02890         val1 = object_manipulation_msgs.msg.Grasp()
02891         _v172 = val1.pre_grasp_posture
02892         _v173 = _v172.header
02893         start = end
02894         end += 4
02895         (_v173.seq,) = _struct_I.unpack(str[start:end])
02896         _v174 = _v173.stamp
02897         _x = _v174
02898         start = end
02899         end += 8
02900         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02901         start = end
02902         end += 4
02903         (length,) = _struct_I.unpack(str[start:end])
02904         start = end
02905         end += length
02906         if python3:
02907           _v173.frame_id = str[start:end].decode('utf-8')
02908         else:
02909           _v173.frame_id = str[start:end]
02910         start = end
02911         end += 4
02912         (length,) = _struct_I.unpack(str[start:end])
02913         _v172.name = []
02914         for i in range(0, length):
02915           start = end
02916           end += 4
02917           (length,) = _struct_I.unpack(str[start:end])
02918           start = end
02919           end += length
02920           if python3:
02921             val3 = str[start:end].decode('utf-8')
02922           else:
02923             val3 = str[start:end]
02924           _v172.name.append(val3)
02925         start = end
02926         end += 4
02927         (length,) = _struct_I.unpack(str[start:end])
02928         pattern = '<%sd'%length
02929         start = end
02930         end += struct.calcsize(pattern)
02931         _v172.position = struct.unpack(pattern, str[start:end])
02932         start = end
02933         end += 4
02934         (length,) = _struct_I.unpack(str[start:end])
02935         pattern = '<%sd'%length
02936         start = end
02937         end += struct.calcsize(pattern)
02938         _v172.velocity = struct.unpack(pattern, str[start:end])
02939         start = end
02940         end += 4
02941         (length,) = _struct_I.unpack(str[start:end])
02942         pattern = '<%sd'%length
02943         start = end
02944         end += struct.calcsize(pattern)
02945         _v172.effort = struct.unpack(pattern, str[start:end])
02946         _v175 = val1.grasp_posture
02947         _v176 = _v175.header
02948         start = end
02949         end += 4
02950         (_v176.seq,) = _struct_I.unpack(str[start:end])
02951         _v177 = _v176.stamp
02952         _x = _v177
02953         start = end
02954         end += 8
02955         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02956         start = end
02957         end += 4
02958         (length,) = _struct_I.unpack(str[start:end])
02959         start = end
02960         end += length
02961         if python3:
02962           _v176.frame_id = str[start:end].decode('utf-8')
02963         else:
02964           _v176.frame_id = str[start:end]
02965         start = end
02966         end += 4
02967         (length,) = _struct_I.unpack(str[start:end])
02968         _v175.name = []
02969         for i in range(0, length):
02970           start = end
02971           end += 4
02972           (length,) = _struct_I.unpack(str[start:end])
02973           start = end
02974           end += length
02975           if python3:
02976             val3 = str[start:end].decode('utf-8')
02977           else:
02978             val3 = str[start:end]
02979           _v175.name.append(val3)
02980         start = end
02981         end += 4
02982         (length,) = _struct_I.unpack(str[start:end])
02983         pattern = '<%sd'%length
02984         start = end
02985         end += struct.calcsize(pattern)
02986         _v175.position = struct.unpack(pattern, str[start:end])
02987         start = end
02988         end += 4
02989         (length,) = _struct_I.unpack(str[start:end])
02990         pattern = '<%sd'%length
02991         start = end
02992         end += struct.calcsize(pattern)
02993         _v175.velocity = struct.unpack(pattern, str[start:end])
02994         start = end
02995         end += 4
02996         (length,) = _struct_I.unpack(str[start:end])
02997         pattern = '<%sd'%length
02998         start = end
02999         end += struct.calcsize(pattern)
03000         _v175.effort = struct.unpack(pattern, str[start:end])
03001         _v178 = val1.grasp_pose
03002         _v179 = _v178.position
03003         _x = _v179
03004         start = end
03005         end += 24
03006         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03007         _v180 = _v178.orientation
03008         _x = _v180
03009         start = end
03010         end += 32
03011         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03012         _x = val1
03013         start = end
03014         end += 17
03015         (_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance,) = _struct_dB2f.unpack(str[start:end])
03016         val1.cluster_rep = bool(val1.cluster_rep)
03017         start = end
03018         end += 4
03019         (length,) = _struct_I.unpack(str[start:end])
03020         val1.moved_obstacles = []
03021         for i in range(0, length):
03022           val2 = object_manipulation_msgs.msg.GraspableObject()
03023           start = end
03024           end += 4
03025           (length,) = _struct_I.unpack(str[start:end])
03026           start = end
03027           end += length
03028           if python3:
03029             val2.reference_frame_id = str[start:end].decode('utf-8')
03030           else:
03031             val2.reference_frame_id = str[start:end]
03032           start = end
03033           end += 4
03034           (length,) = _struct_I.unpack(str[start:end])
03035           val2.potential_models = []
03036           for i in range(0, length):
03037             val3 = household_objects_database_msgs.msg.DatabaseModelPose()
03038             start = end
03039             end += 4
03040             (val3.model_id,) = _struct_i.unpack(str[start:end])
03041             _v181 = val3.pose
03042             _v182 = _v181.header
03043             start = end
03044             end += 4
03045             (_v182.seq,) = _struct_I.unpack(str[start:end])
03046             _v183 = _v182.stamp
03047             _x = _v183
03048             start = end
03049             end += 8
03050             (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03051             start = end
03052             end += 4
03053             (length,) = _struct_I.unpack(str[start:end])
03054             start = end
03055             end += length
03056             if python3:
03057               _v182.frame_id = str[start:end].decode('utf-8')
03058             else:
03059               _v182.frame_id = str[start:end]
03060             _v184 = _v181.pose
03061             _v185 = _v184.position
03062             _x = _v185
03063             start = end
03064             end += 24
03065             (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03066             _v186 = _v184.orientation
03067             _x = _v186
03068             start = end
03069             end += 32
03070             (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03071             start = end
03072             end += 4
03073             (val3.confidence,) = _struct_f.unpack(str[start:end])
03074             start = end
03075             end += 4
03076             (length,) = _struct_I.unpack(str[start:end])
03077             start = end
03078             end += length
03079             if python3:
03080               val3.detector_name = str[start:end].decode('utf-8')
03081             else:
03082               val3.detector_name = str[start:end]
03083             val2.potential_models.append(val3)
03084           _v187 = val2.cluster
03085           _v188 = _v187.header
03086           start = end
03087           end += 4
03088           (_v188.seq,) = _struct_I.unpack(str[start:end])
03089           _v189 = _v188.stamp
03090           _x = _v189
03091           start = end
03092           end += 8
03093           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03094           start = end
03095           end += 4
03096           (length,) = _struct_I.unpack(str[start:end])
03097           start = end
03098           end += length
03099           if python3:
03100             _v188.frame_id = str[start:end].decode('utf-8')
03101           else:
03102             _v188.frame_id = str[start:end]
03103           start = end
03104           end += 4
03105           (length,) = _struct_I.unpack(str[start:end])
03106           _v187.points = []
03107           for i in range(0, length):
03108             val4 = geometry_msgs.msg.Point32()
03109             _x = val4
03110             start = end
03111             end += 12
03112             (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
03113             _v187.points.append(val4)
03114           start = end
03115           end += 4
03116           (length,) = _struct_I.unpack(str[start:end])
03117           _v187.channels = []
03118           for i in range(0, length):
03119             val4 = sensor_msgs.msg.ChannelFloat32()
03120             start = end
03121             end += 4
03122             (length,) = _struct_I.unpack(str[start:end])
03123             start = end
03124             end += length
03125             if python3:
03126               val4.name = str[start:end].decode('utf-8')
03127             else:
03128               val4.name = str[start:end]
03129             start = end
03130             end += 4
03131             (length,) = _struct_I.unpack(str[start:end])
03132             pattern = '<%sf'%length
03133             start = end
03134             end += struct.calcsize(pattern)
03135             val4.values = struct.unpack(pattern, str[start:end])
03136             _v187.channels.append(val4)
03137           _v190 = val2.region
03138           _v191 = _v190.cloud
03139           _v192 = _v191.header
03140           start = end
03141           end += 4
03142           (_v192.seq,) = _struct_I.unpack(str[start:end])
03143           _v193 = _v192.stamp
03144           _x = _v193
03145           start = end
03146           end += 8
03147           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03148           start = end
03149           end += 4
03150           (length,) = _struct_I.unpack(str[start:end])
03151           start = end
03152           end += length
03153           if python3:
03154             _v192.frame_id = str[start:end].decode('utf-8')
03155           else:
03156             _v192.frame_id = str[start:end]
03157           _x = _v191
03158           start = end
03159           end += 8
03160           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
03161           start = end
03162           end += 4
03163           (length,) = _struct_I.unpack(str[start:end])
03164           _v191.fields = []
03165           for i in range(0, length):
03166             val5 = sensor_msgs.msg.PointField()
03167             start = end
03168             end += 4
03169             (length,) = _struct_I.unpack(str[start:end])
03170             start = end
03171             end += length
03172             if python3:
03173               val5.name = str[start:end].decode('utf-8')
03174             else:
03175               val5.name = str[start:end]
03176             _x = val5
03177             start = end
03178             end += 9
03179             (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
03180             _v191.fields.append(val5)
03181           _x = _v191
03182           start = end
03183           end += 9
03184           (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
03185           _v191.is_bigendian = bool(_v191.is_bigendian)
03186           start = end
03187           end += 4
03188           (length,) = _struct_I.unpack(str[start:end])
03189           start = end
03190           end += length
03191           if python3:
03192             _v191.data = str[start:end].decode('utf-8')
03193           else:
03194             _v191.data = str[start:end]
03195           start = end
03196           end += 1
03197           (_v191.is_dense,) = _struct_B.unpack(str[start:end])
03198           _v191.is_dense = bool(_v191.is_dense)
03199           start = end
03200           end += 4
03201           (length,) = _struct_I.unpack(str[start:end])
03202           pattern = '<%si'%length
03203           start = end
03204           end += struct.calcsize(pattern)
03205           _v190.mask = struct.unpack(pattern, str[start:end])
03206           _v194 = _v190.image
03207           _v195 = _v194.header
03208           start = end
03209           end += 4
03210           (_v195.seq,) = _struct_I.unpack(str[start:end])
03211           _v196 = _v195.stamp
03212           _x = _v196
03213           start = end
03214           end += 8
03215           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03216           start = end
03217           end += 4
03218           (length,) = _struct_I.unpack(str[start:end])
03219           start = end
03220           end += length
03221           if python3:
03222             _v195.frame_id = str[start:end].decode('utf-8')
03223           else:
03224             _v195.frame_id = str[start:end]
03225           _x = _v194
03226           start = end
03227           end += 8
03228           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
03229           start = end
03230           end += 4
03231           (length,) = _struct_I.unpack(str[start:end])
03232           start = end
03233           end += length
03234           if python3:
03235             _v194.encoding = str[start:end].decode('utf-8')
03236           else:
03237             _v194.encoding = str[start:end]
03238           _x = _v194
03239           start = end
03240           end += 5
03241           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
03242           start = end
03243           end += 4
03244           (length,) = _struct_I.unpack(str[start:end])
03245           start = end
03246           end += length
03247           if python3:
03248             _v194.data = str[start:end].decode('utf-8')
03249           else:
03250             _v194.data = str[start:end]
03251           _v197 = _v190.disparity_image
03252           _v198 = _v197.header
03253           start = end
03254           end += 4
03255           (_v198.seq,) = _struct_I.unpack(str[start:end])
03256           _v199 = _v198.stamp
03257           _x = _v199
03258           start = end
03259           end += 8
03260           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03261           start = end
03262           end += 4
03263           (length,) = _struct_I.unpack(str[start:end])
03264           start = end
03265           end += length
03266           if python3:
03267             _v198.frame_id = str[start:end].decode('utf-8')
03268           else:
03269             _v198.frame_id = str[start:end]
03270           _x = _v197
03271           start = end
03272           end += 8
03273           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
03274           start = end
03275           end += 4
03276           (length,) = _struct_I.unpack(str[start:end])
03277           start = end
03278           end += length
03279           if python3:
03280             _v197.encoding = str[start:end].decode('utf-8')
03281           else:
03282             _v197.encoding = str[start:end]
03283           _x = _v197
03284           start = end
03285           end += 5
03286           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
03287           start = end
03288           end += 4
03289           (length,) = _struct_I.unpack(str[start:end])
03290           start = end
03291           end += length
03292           if python3:
03293             _v197.data = str[start:end].decode('utf-8')
03294           else:
03295             _v197.data = str[start:end]
03296           _v200 = _v190.cam_info
03297           _v201 = _v200.header
03298           start = end
03299           end += 4
03300           (_v201.seq,) = _struct_I.unpack(str[start:end])
03301           _v202 = _v201.stamp
03302           _x = _v202
03303           start = end
03304           end += 8
03305           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03306           start = end
03307           end += 4
03308           (length,) = _struct_I.unpack(str[start:end])
03309           start = end
03310           end += length
03311           if python3:
03312             _v201.frame_id = str[start:end].decode('utf-8')
03313           else:
03314             _v201.frame_id = str[start:end]
03315           _x = _v200
03316           start = end
03317           end += 8
03318           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
03319           start = end
03320           end += 4
03321           (length,) = _struct_I.unpack(str[start:end])
03322           start = end
03323           end += length
03324           if python3:
03325             _v200.distortion_model = str[start:end].decode('utf-8')
03326           else:
03327             _v200.distortion_model = str[start:end]
03328           start = end
03329           end += 4
03330           (length,) = _struct_I.unpack(str[start:end])
03331           pattern = '<%sd'%length
03332           start = end
03333           end += struct.calcsize(pattern)
03334           _v200.D = struct.unpack(pattern, str[start:end])
03335           start = end
03336           end += 72
03337           _v200.K = _struct_9d.unpack(str[start:end])
03338           start = end
03339           end += 72
03340           _v200.R = _struct_9d.unpack(str[start:end])
03341           start = end
03342           end += 96
03343           _v200.P = _struct_12d.unpack(str[start:end])
03344           _x = _v200
03345           start = end
03346           end += 8
03347           (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
03348           _v203 = _v200.roi
03349           _x = _v203
03350           start = end
03351           end += 17
03352           (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
03353           _v203.do_rectify = bool(_v203.do_rectify)
03354           _v204 = _v190.roi_box_pose
03355           _v205 = _v204.header
03356           start = end
03357           end += 4
03358           (_v205.seq,) = _struct_I.unpack(str[start:end])
03359           _v206 = _v205.stamp
03360           _x = _v206
03361           start = end
03362           end += 8
03363           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03364           start = end
03365           end += 4
03366           (length,) = _struct_I.unpack(str[start:end])
03367           start = end
03368           end += length
03369           if python3:
03370             _v205.frame_id = str[start:end].decode('utf-8')
03371           else:
03372             _v205.frame_id = str[start:end]
03373           _v207 = _v204.pose
03374           _v208 = _v207.position
03375           _x = _v208
03376           start = end
03377           end += 24
03378           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03379           _v209 = _v207.orientation
03380           _x = _v209
03381           start = end
03382           end += 32
03383           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03384           _v210 = _v190.roi_box_dims
03385           _x = _v210
03386           start = end
03387           end += 24
03388           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03389           start = end
03390           end += 4
03391           (length,) = _struct_I.unpack(str[start:end])
03392           start = end
03393           end += length
03394           if python3:
03395             val2.collision_name = str[start:end].decode('utf-8')
03396           else:
03397             val2.collision_name = str[start:end]
03398           val1.moved_obstacles.append(val2)
03399         self.action_goal.goal.desired_grasps.append(val1)
03400       _x = self
03401       start = end
03402       end += 12
03403       (_x.action_goal.goal.lift.direction.header.seq, _x.action_goal.goal.lift.direction.header.stamp.secs, _x.action_goal.goal.lift.direction.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03404       start = end
03405       end += 4
03406       (length,) = _struct_I.unpack(str[start:end])
03407       start = end
03408       end += length
03409       if python3:
03410         self.action_goal.goal.lift.direction.header.frame_id = str[start:end].decode('utf-8')
03411       else:
03412         self.action_goal.goal.lift.direction.header.frame_id = str[start:end]
03413       _x = self
03414       start = end
03415       end += 32
03416       (_x.action_goal.goal.lift.direction.vector.x, _x.action_goal.goal.lift.direction.vector.y, _x.action_goal.goal.lift.direction.vector.z, _x.action_goal.goal.lift.desired_distance, _x.action_goal.goal.lift.min_distance,) = _struct_3d2f.unpack(str[start:end])
03417       start = end
03418       end += 4
03419       (length,) = _struct_I.unpack(str[start:end])
03420       start = end
03421       end += length
03422       if python3:
03423         self.action_goal.goal.collision_object_name = str[start:end].decode('utf-8')
03424       else:
03425         self.action_goal.goal.collision_object_name = str[start:end]
03426       start = end
03427       end += 4
03428       (length,) = _struct_I.unpack(str[start:end])
03429       start = end
03430       end += length
03431       if python3:
03432         self.action_goal.goal.collision_support_surface_name = str[start:end].decode('utf-8')
03433       else:
03434         self.action_goal.goal.collision_support_surface_name = str[start:end]
03435       _x = self
03436       start = end
03437       end += 5
03438       (_x.action_goal.goal.allow_gripper_support_collision, _x.action_goal.goal.use_reactive_execution, _x.action_goal.goal.use_reactive_lift, _x.action_goal.goal.only_perform_feasibility_test, _x.action_goal.goal.ignore_collisions,) = _struct_5B.unpack(str[start:end])
03439       self.action_goal.goal.allow_gripper_support_collision = bool(self.action_goal.goal.allow_gripper_support_collision)
03440       self.action_goal.goal.use_reactive_execution = bool(self.action_goal.goal.use_reactive_execution)
03441       self.action_goal.goal.use_reactive_lift = bool(self.action_goal.goal.use_reactive_lift)
03442       self.action_goal.goal.only_perform_feasibility_test = bool(self.action_goal.goal.only_perform_feasibility_test)
03443       self.action_goal.goal.ignore_collisions = bool(self.action_goal.goal.ignore_collisions)
03444       start = end
03445       end += 4
03446       (length,) = _struct_I.unpack(str[start:end])
03447       self.action_goal.goal.path_constraints.joint_constraints = []
03448       for i in range(0, length):
03449         val1 = arm_navigation_msgs.msg.JointConstraint()
03450         start = end
03451         end += 4
03452         (length,) = _struct_I.unpack(str[start:end])
03453         start = end
03454         end += length
03455         if python3:
03456           val1.joint_name = str[start:end].decode('utf-8')
03457         else:
03458           val1.joint_name = str[start:end]
03459         _x = val1
03460         start = end
03461         end += 32
03462         (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
03463         self.action_goal.goal.path_constraints.joint_constraints.append(val1)
03464       start = end
03465       end += 4
03466       (length,) = _struct_I.unpack(str[start:end])
03467       self.action_goal.goal.path_constraints.position_constraints = []
03468       for i in range(0, length):
03469         val1 = arm_navigation_msgs.msg.PositionConstraint()
03470         _v211 = val1.header
03471         start = end
03472         end += 4
03473         (_v211.seq,) = _struct_I.unpack(str[start:end])
03474         _v212 = _v211.stamp
03475         _x = _v212
03476         start = end
03477         end += 8
03478         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03479         start = end
03480         end += 4
03481         (length,) = _struct_I.unpack(str[start:end])
03482         start = end
03483         end += length
03484         if python3:
03485           _v211.frame_id = str[start:end].decode('utf-8')
03486         else:
03487           _v211.frame_id = str[start:end]
03488         start = end
03489         end += 4
03490         (length,) = _struct_I.unpack(str[start:end])
03491         start = end
03492         end += length
03493         if python3:
03494           val1.link_name = str[start:end].decode('utf-8')
03495         else:
03496           val1.link_name = str[start:end]
03497         _v213 = val1.target_point_offset
03498         _x = _v213
03499         start = end
03500         end += 24
03501         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03502         _v214 = val1.position
03503         _x = _v214
03504         start = end
03505         end += 24
03506         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03507         _v215 = val1.constraint_region_shape
03508         start = end
03509         end += 1
03510         (_v215.type,) = _struct_b.unpack(str[start:end])
03511         start = end
03512         end += 4
03513         (length,) = _struct_I.unpack(str[start:end])
03514         pattern = '<%sd'%length
03515         start = end
03516         end += struct.calcsize(pattern)
03517         _v215.dimensions = struct.unpack(pattern, str[start:end])
03518         start = end
03519         end += 4
03520         (length,) = _struct_I.unpack(str[start:end])
03521         pattern = '<%si'%length
03522         start = end
03523         end += struct.calcsize(pattern)
03524         _v215.triangles = struct.unpack(pattern, str[start:end])
03525         start = end
03526         end += 4
03527         (length,) = _struct_I.unpack(str[start:end])
03528         _v215.vertices = []
03529         for i in range(0, length):
03530           val3 = geometry_msgs.msg.Point()
03531           _x = val3
03532           start = end
03533           end += 24
03534           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03535           _v215.vertices.append(val3)
03536         _v216 = val1.constraint_region_orientation
03537         _x = _v216
03538         start = end
03539         end += 32
03540         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03541         start = end
03542         end += 8
03543         (val1.weight,) = _struct_d.unpack(str[start:end])
03544         self.action_goal.goal.path_constraints.position_constraints.append(val1)
03545       start = end
03546       end += 4
03547       (length,) = _struct_I.unpack(str[start:end])
03548       self.action_goal.goal.path_constraints.orientation_constraints = []
03549       for i in range(0, length):
03550         val1 = arm_navigation_msgs.msg.OrientationConstraint()
03551         _v217 = val1.header
03552         start = end
03553         end += 4
03554         (_v217.seq,) = _struct_I.unpack(str[start:end])
03555         _v218 = _v217.stamp
03556         _x = _v218
03557         start = end
03558         end += 8
03559         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03560         start = end
03561         end += 4
03562         (length,) = _struct_I.unpack(str[start:end])
03563         start = end
03564         end += length
03565         if python3:
03566           _v217.frame_id = str[start:end].decode('utf-8')
03567         else:
03568           _v217.frame_id = str[start:end]
03569         start = end
03570         end += 4
03571         (length,) = _struct_I.unpack(str[start:end])
03572         start = end
03573         end += length
03574         if python3:
03575           val1.link_name = str[start:end].decode('utf-8')
03576         else:
03577           val1.link_name = str[start:end]
03578         start = end
03579         end += 4
03580         (val1.type,) = _struct_i.unpack(str[start:end])
03581         _v219 = val1.orientation
03582         _x = _v219
03583         start = end
03584         end += 32
03585         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03586         _x = val1
03587         start = end
03588         end += 32
03589         (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
03590         self.action_goal.goal.path_constraints.orientation_constraints.append(val1)
03591       start = end
03592       end += 4
03593       (length,) = _struct_I.unpack(str[start:end])
03594       self.action_goal.goal.path_constraints.visibility_constraints = []
03595       for i in range(0, length):
03596         val1 = arm_navigation_msgs.msg.VisibilityConstraint()
03597         _v220 = val1.header
03598         start = end
03599         end += 4
03600         (_v220.seq,) = _struct_I.unpack(str[start:end])
03601         _v221 = _v220.stamp
03602         _x = _v221
03603         start = end
03604         end += 8
03605         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03606         start = end
03607         end += 4
03608         (length,) = _struct_I.unpack(str[start:end])
03609         start = end
03610         end += length
03611         if python3:
03612           _v220.frame_id = str[start:end].decode('utf-8')
03613         else:
03614           _v220.frame_id = str[start:end]
03615         _v222 = val1.target
03616         _v223 = _v222.header
03617         start = end
03618         end += 4
03619         (_v223.seq,) = _struct_I.unpack(str[start:end])
03620         _v224 = _v223.stamp
03621         _x = _v224
03622         start = end
03623         end += 8
03624         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03625         start = end
03626         end += 4
03627         (length,) = _struct_I.unpack(str[start:end])
03628         start = end
03629         end += length
03630         if python3:
03631           _v223.frame_id = str[start:end].decode('utf-8')
03632         else:
03633           _v223.frame_id = str[start:end]
03634         _v225 = _v222.point
03635         _x = _v225
03636         start = end
03637         end += 24
03638         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03639         _v226 = val1.sensor_pose
03640         _v227 = _v226.header
03641         start = end
03642         end += 4
03643         (_v227.seq,) = _struct_I.unpack(str[start:end])
03644         _v228 = _v227.stamp
03645         _x = _v228
03646         start = end
03647         end += 8
03648         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03649         start = end
03650         end += 4
03651         (length,) = _struct_I.unpack(str[start:end])
03652         start = end
03653         end += length
03654         if python3:
03655           _v227.frame_id = str[start:end].decode('utf-8')
03656         else:
03657           _v227.frame_id = str[start:end]
03658         _v229 = _v226.pose
03659         _v230 = _v229.position
03660         _x = _v230
03661         start = end
03662         end += 24
03663         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03664         _v231 = _v229.orientation
03665         _x = _v231
03666         start = end
03667         end += 32
03668         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03669         start = end
03670         end += 8
03671         (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
03672         self.action_goal.goal.path_constraints.visibility_constraints.append(val1)
03673       start = end
03674       end += 4
03675       (length,) = _struct_I.unpack(str[start:end])
03676       self.action_goal.goal.additional_collision_operations.collision_operations = []
03677       for i in range(0, length):
03678         val1 = arm_navigation_msgs.msg.CollisionOperation()
03679         start = end
03680         end += 4
03681         (length,) = _struct_I.unpack(str[start:end])
03682         start = end
03683         end += length
03684         if python3:
03685           val1.object1 = str[start:end].decode('utf-8')
03686         else:
03687           val1.object1 = str[start:end]
03688         start = end
03689         end += 4
03690         (length,) = _struct_I.unpack(str[start:end])
03691         start = end
03692         end += length
03693         if python3:
03694           val1.object2 = str[start:end].decode('utf-8')
03695         else:
03696           val1.object2 = str[start:end]
03697         _x = val1
03698         start = end
03699         end += 12
03700         (_x.penetration_distance, _x.operation,) = _struct_di.unpack(str[start:end])
03701         self.action_goal.goal.additional_collision_operations.collision_operations.append(val1)
03702       start = end
03703       end += 4
03704       (length,) = _struct_I.unpack(str[start:end])
03705       self.action_goal.goal.additional_link_padding = []
03706       for i in range(0, length):
03707         val1 = arm_navigation_msgs.msg.LinkPadding()
03708         start = end
03709         end += 4
03710         (length,) = _struct_I.unpack(str[start:end])
03711         start = end
03712         end += length
03713         if python3:
03714           val1.link_name = str[start:end].decode('utf-8')
03715         else:
03716           val1.link_name = str[start:end]
03717         start = end
03718         end += 8
03719         (val1.padding,) = _struct_d.unpack(str[start:end])
03720         self.action_goal.goal.additional_link_padding.append(val1)
03721       start = end
03722       end += 4
03723       (length,) = _struct_I.unpack(str[start:end])
03724       self.action_goal.goal.movable_obstacles = []
03725       for i in range(0, length):
03726         val1 = object_manipulation_msgs.msg.GraspableObject()
03727         start = end
03728         end += 4
03729         (length,) = _struct_I.unpack(str[start:end])
03730         start = end
03731         end += length
03732         if python3:
03733           val1.reference_frame_id = str[start:end].decode('utf-8')
03734         else:
03735           val1.reference_frame_id = str[start:end]
03736         start = end
03737         end += 4
03738         (length,) = _struct_I.unpack(str[start:end])
03739         val1.potential_models = []
03740         for i in range(0, length):
03741           val2 = household_objects_database_msgs.msg.DatabaseModelPose()
03742           start = end
03743           end += 4
03744           (val2.model_id,) = _struct_i.unpack(str[start:end])
03745           _v232 = val2.pose
03746           _v233 = _v232.header
03747           start = end
03748           end += 4
03749           (_v233.seq,) = _struct_I.unpack(str[start:end])
03750           _v234 = _v233.stamp
03751           _x = _v234
03752           start = end
03753           end += 8
03754           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03755           start = end
03756           end += 4
03757           (length,) = _struct_I.unpack(str[start:end])
03758           start = end
03759           end += length
03760           if python3:
03761             _v233.frame_id = str[start:end].decode('utf-8')
03762           else:
03763             _v233.frame_id = str[start:end]
03764           _v235 = _v232.pose
03765           _v236 = _v235.position
03766           _x = _v236
03767           start = end
03768           end += 24
03769           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03770           _v237 = _v235.orientation
03771           _x = _v237
03772           start = end
03773           end += 32
03774           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03775           start = end
03776           end += 4
03777           (val2.confidence,) = _struct_f.unpack(str[start:end])
03778           start = end
03779           end += 4
03780           (length,) = _struct_I.unpack(str[start:end])
03781           start = end
03782           end += length
03783           if python3:
03784             val2.detector_name = str[start:end].decode('utf-8')
03785           else:
03786             val2.detector_name = str[start:end]
03787           val1.potential_models.append(val2)
03788         _v238 = val1.cluster
03789         _v239 = _v238.header
03790         start = end
03791         end += 4
03792         (_v239.seq,) = _struct_I.unpack(str[start:end])
03793         _v240 = _v239.stamp
03794         _x = _v240
03795         start = end
03796         end += 8
03797         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03798         start = end
03799         end += 4
03800         (length,) = _struct_I.unpack(str[start:end])
03801         start = end
03802         end += length
03803         if python3:
03804           _v239.frame_id = str[start:end].decode('utf-8')
03805         else:
03806           _v239.frame_id = str[start:end]
03807         start = end
03808         end += 4
03809         (length,) = _struct_I.unpack(str[start:end])
03810         _v238.points = []
03811         for i in range(0, length):
03812           val3 = geometry_msgs.msg.Point32()
03813           _x = val3
03814           start = end
03815           end += 12
03816           (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
03817           _v238.points.append(val3)
03818         start = end
03819         end += 4
03820         (length,) = _struct_I.unpack(str[start:end])
03821         _v238.channels = []
03822         for i in range(0, length):
03823           val3 = sensor_msgs.msg.ChannelFloat32()
03824           start = end
03825           end += 4
03826           (length,) = _struct_I.unpack(str[start:end])
03827           start = end
03828           end += length
03829           if python3:
03830             val3.name = str[start:end].decode('utf-8')
03831           else:
03832             val3.name = str[start:end]
03833           start = end
03834           end += 4
03835           (length,) = _struct_I.unpack(str[start:end])
03836           pattern = '<%sf'%length
03837           start = end
03838           end += struct.calcsize(pattern)
03839           val3.values = struct.unpack(pattern, str[start:end])
03840           _v238.channels.append(val3)
03841         _v241 = val1.region
03842         _v242 = _v241.cloud
03843         _v243 = _v242.header
03844         start = end
03845         end += 4
03846         (_v243.seq,) = _struct_I.unpack(str[start:end])
03847         _v244 = _v243.stamp
03848         _x = _v244
03849         start = end
03850         end += 8
03851         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03852         start = end
03853         end += 4
03854         (length,) = _struct_I.unpack(str[start:end])
03855         start = end
03856         end += length
03857         if python3:
03858           _v243.frame_id = str[start:end].decode('utf-8')
03859         else:
03860           _v243.frame_id = str[start:end]
03861         _x = _v242
03862         start = end
03863         end += 8
03864         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
03865         start = end
03866         end += 4
03867         (length,) = _struct_I.unpack(str[start:end])
03868         _v242.fields = []
03869         for i in range(0, length):
03870           val4 = sensor_msgs.msg.PointField()
03871           start = end
03872           end += 4
03873           (length,) = _struct_I.unpack(str[start:end])
03874           start = end
03875           end += length
03876           if python3:
03877             val4.name = str[start:end].decode('utf-8')
03878           else:
03879             val4.name = str[start:end]
03880           _x = val4
03881           start = end
03882           end += 9
03883           (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
03884           _v242.fields.append(val4)
03885         _x = _v242
03886         start = end
03887         end += 9
03888         (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
03889         _v242.is_bigendian = bool(_v242.is_bigendian)
03890         start = end
03891         end += 4
03892         (length,) = _struct_I.unpack(str[start:end])
03893         start = end
03894         end += length
03895         if python3:
03896           _v242.data = str[start:end].decode('utf-8')
03897         else:
03898           _v242.data = str[start:end]
03899         start = end
03900         end += 1
03901         (_v242.is_dense,) = _struct_B.unpack(str[start:end])
03902         _v242.is_dense = bool(_v242.is_dense)
03903         start = end
03904         end += 4
03905         (length,) = _struct_I.unpack(str[start:end])
03906         pattern = '<%si'%length
03907         start = end
03908         end += struct.calcsize(pattern)
03909         _v241.mask = struct.unpack(pattern, str[start:end])
03910         _v245 = _v241.image
03911         _v246 = _v245.header
03912         start = end
03913         end += 4
03914         (_v246.seq,) = _struct_I.unpack(str[start:end])
03915         _v247 = _v246.stamp
03916         _x = _v247
03917         start = end
03918         end += 8
03919         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03920         start = end
03921         end += 4
03922         (length,) = _struct_I.unpack(str[start:end])
03923         start = end
03924         end += length
03925         if python3:
03926           _v246.frame_id = str[start:end].decode('utf-8')
03927         else:
03928           _v246.frame_id = str[start:end]
03929         _x = _v245
03930         start = end
03931         end += 8
03932         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
03933         start = end
03934         end += 4
03935         (length,) = _struct_I.unpack(str[start:end])
03936         start = end
03937         end += length
03938         if python3:
03939           _v245.encoding = str[start:end].decode('utf-8')
03940         else:
03941           _v245.encoding = str[start:end]
03942         _x = _v245
03943         start = end
03944         end += 5
03945         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
03946         start = end
03947         end += 4
03948         (length,) = _struct_I.unpack(str[start:end])
03949         start = end
03950         end += length
03951         if python3:
03952           _v245.data = str[start:end].decode('utf-8')
03953         else:
03954           _v245.data = str[start:end]
03955         _v248 = _v241.disparity_image
03956         _v249 = _v248.header
03957         start = end
03958         end += 4
03959         (_v249.seq,) = _struct_I.unpack(str[start:end])
03960         _v250 = _v249.stamp
03961         _x = _v250
03962         start = end
03963         end += 8
03964         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03965         start = end
03966         end += 4
03967         (length,) = _struct_I.unpack(str[start:end])
03968         start = end
03969         end += length
03970         if python3:
03971           _v249.frame_id = str[start:end].decode('utf-8')
03972         else:
03973           _v249.frame_id = str[start:end]
03974         _x = _v248
03975         start = end
03976         end += 8
03977         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
03978         start = end
03979         end += 4
03980         (length,) = _struct_I.unpack(str[start:end])
03981         start = end
03982         end += length
03983         if python3:
03984           _v248.encoding = str[start:end].decode('utf-8')
03985         else:
03986           _v248.encoding = str[start:end]
03987         _x = _v248
03988         start = end
03989         end += 5
03990         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
03991         start = end
03992         end += 4
03993         (length,) = _struct_I.unpack(str[start:end])
03994         start = end
03995         end += length
03996         if python3:
03997           _v248.data = str[start:end].decode('utf-8')
03998         else:
03999           _v248.data = str[start:end]
04000         _v251 = _v241.cam_info
04001         _v252 = _v251.header
04002         start = end
04003         end += 4
04004         (_v252.seq,) = _struct_I.unpack(str[start:end])
04005         _v253 = _v252.stamp
04006         _x = _v253
04007         start = end
04008         end += 8
04009         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04010         start = end
04011         end += 4
04012         (length,) = _struct_I.unpack(str[start:end])
04013         start = end
04014         end += length
04015         if python3:
04016           _v252.frame_id = str[start:end].decode('utf-8')
04017         else:
04018           _v252.frame_id = str[start:end]
04019         _x = _v251
04020         start = end
04021         end += 8
04022         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04023         start = end
04024         end += 4
04025         (length,) = _struct_I.unpack(str[start:end])
04026         start = end
04027         end += length
04028         if python3:
04029           _v251.distortion_model = str[start:end].decode('utf-8')
04030         else:
04031           _v251.distortion_model = str[start:end]
04032         start = end
04033         end += 4
04034         (length,) = _struct_I.unpack(str[start:end])
04035         pattern = '<%sd'%length
04036         start = end
04037         end += struct.calcsize(pattern)
04038         _v251.D = struct.unpack(pattern, str[start:end])
04039         start = end
04040         end += 72
04041         _v251.K = _struct_9d.unpack(str[start:end])
04042         start = end
04043         end += 72
04044         _v251.R = _struct_9d.unpack(str[start:end])
04045         start = end
04046         end += 96
04047         _v251.P = _struct_12d.unpack(str[start:end])
04048         _x = _v251
04049         start = end
04050         end += 8
04051         (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
04052         _v254 = _v251.roi
04053         _x = _v254
04054         start = end
04055         end += 17
04056         (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
04057         _v254.do_rectify = bool(_v254.do_rectify)
04058         _v255 = _v241.roi_box_pose
04059         _v256 = _v255.header
04060         start = end
04061         end += 4
04062         (_v256.seq,) = _struct_I.unpack(str[start:end])
04063         _v257 = _v256.stamp
04064         _x = _v257
04065         start = end
04066         end += 8
04067         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04068         start = end
04069         end += 4
04070         (length,) = _struct_I.unpack(str[start:end])
04071         start = end
04072         end += length
04073         if python3:
04074           _v256.frame_id = str[start:end].decode('utf-8')
04075         else:
04076           _v256.frame_id = str[start:end]
04077         _v258 = _v255.pose
04078         _v259 = _v258.position
04079         _x = _v259
04080         start = end
04081         end += 24
04082         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04083         _v260 = _v258.orientation
04084         _x = _v260
04085         start = end
04086         end += 32
04087         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04088         _v261 = _v241.roi_box_dims
04089         _x = _v261
04090         start = end
04091         end += 24
04092         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04093         start = end
04094         end += 4
04095         (length,) = _struct_I.unpack(str[start:end])
04096         start = end
04097         end += length
04098         if python3:
04099           val1.collision_name = str[start:end].decode('utf-8')
04100         else:
04101           val1.collision_name = str[start:end]
04102         self.action_goal.goal.movable_obstacles.append(val1)
04103       _x = self
04104       start = end
04105       end += 16
04106       (_x.action_goal.goal.max_contact_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_f3I.unpack(str[start:end])
04107       start = end
04108       end += 4
04109       (length,) = _struct_I.unpack(str[start:end])
04110       start = end
04111       end += length
04112       if python3:
04113         self.action_result.header.frame_id = str[start:end].decode('utf-8')
04114       else:
04115         self.action_result.header.frame_id = str[start:end]
04116       _x = self
04117       start = end
04118       end += 8
04119       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
04120       start = end
04121       end += 4
04122       (length,) = _struct_I.unpack(str[start:end])
04123       start = end
04124       end += length
04125       if python3:
04126         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
04127       else:
04128         self.action_result.status.goal_id.id = str[start:end]
04129       start = end
04130       end += 1
04131       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
04132       start = end
04133       end += 4
04134       (length,) = _struct_I.unpack(str[start:end])
04135       start = end
04136       end += length
04137       if python3:
04138         self.action_result.status.text = str[start:end].decode('utf-8')
04139       else:
04140         self.action_result.status.text = str[start:end]
04141       _x = self
04142       start = end
04143       end += 16
04144       (_x.action_result.result.manipulation_result.value, _x.action_result.result.grasp.pre_grasp_posture.header.seq, _x.action_result.result.grasp.pre_grasp_posture.header.stamp.secs, _x.action_result.result.grasp.pre_grasp_posture.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
04145       start = end
04146       end += 4
04147       (length,) = _struct_I.unpack(str[start:end])
04148       start = end
04149       end += length
04150       if python3:
04151         self.action_result.result.grasp.pre_grasp_posture.header.frame_id = str[start:end].decode('utf-8')
04152       else:
04153         self.action_result.result.grasp.pre_grasp_posture.header.frame_id = str[start:end]
04154       start = end
04155       end += 4
04156       (length,) = _struct_I.unpack(str[start:end])
04157       self.action_result.result.grasp.pre_grasp_posture.name = []
04158       for i in range(0, length):
04159         start = end
04160         end += 4
04161         (length,) = _struct_I.unpack(str[start:end])
04162         start = end
04163         end += length
04164         if python3:
04165           val1 = str[start:end].decode('utf-8')
04166         else:
04167           val1 = str[start:end]
04168         self.action_result.result.grasp.pre_grasp_posture.name.append(val1)
04169       start = end
04170       end += 4
04171       (length,) = _struct_I.unpack(str[start:end])
04172       pattern = '<%sd'%length
04173       start = end
04174       end += struct.calcsize(pattern)
04175       self.action_result.result.grasp.pre_grasp_posture.position = struct.unpack(pattern, str[start:end])
04176       start = end
04177       end += 4
04178       (length,) = _struct_I.unpack(str[start:end])
04179       pattern = '<%sd'%length
04180       start = end
04181       end += struct.calcsize(pattern)
04182       self.action_result.result.grasp.pre_grasp_posture.velocity = struct.unpack(pattern, str[start:end])
04183       start = end
04184       end += 4
04185       (length,) = _struct_I.unpack(str[start:end])
04186       pattern = '<%sd'%length
04187       start = end
04188       end += struct.calcsize(pattern)
04189       self.action_result.result.grasp.pre_grasp_posture.effort = struct.unpack(pattern, str[start:end])
04190       _x = self
04191       start = end
04192       end += 12
04193       (_x.action_result.result.grasp.grasp_posture.header.seq, _x.action_result.result.grasp.grasp_posture.header.stamp.secs, _x.action_result.result.grasp.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
04194       start = end
04195       end += 4
04196       (length,) = _struct_I.unpack(str[start:end])
04197       start = end
04198       end += length
04199       if python3:
04200         self.action_result.result.grasp.grasp_posture.header.frame_id = str[start:end].decode('utf-8')
04201       else:
04202         self.action_result.result.grasp.grasp_posture.header.frame_id = str[start:end]
04203       start = end
04204       end += 4
04205       (length,) = _struct_I.unpack(str[start:end])
04206       self.action_result.result.grasp.grasp_posture.name = []
04207       for i in range(0, length):
04208         start = end
04209         end += 4
04210         (length,) = _struct_I.unpack(str[start:end])
04211         start = end
04212         end += length
04213         if python3:
04214           val1 = str[start:end].decode('utf-8')
04215         else:
04216           val1 = str[start:end]
04217         self.action_result.result.grasp.grasp_posture.name.append(val1)
04218       start = end
04219       end += 4
04220       (length,) = _struct_I.unpack(str[start:end])
04221       pattern = '<%sd'%length
04222       start = end
04223       end += struct.calcsize(pattern)
04224       self.action_result.result.grasp.grasp_posture.position = struct.unpack(pattern, str[start:end])
04225       start = end
04226       end += 4
04227       (length,) = _struct_I.unpack(str[start:end])
04228       pattern = '<%sd'%length
04229       start = end
04230       end += struct.calcsize(pattern)
04231       self.action_result.result.grasp.grasp_posture.velocity = struct.unpack(pattern, str[start:end])
04232       start = end
04233       end += 4
04234       (length,) = _struct_I.unpack(str[start:end])
04235       pattern = '<%sd'%length
04236       start = end
04237       end += struct.calcsize(pattern)
04238       self.action_result.result.grasp.grasp_posture.effort = struct.unpack(pattern, str[start:end])
04239       _x = self
04240       start = end
04241       end += 73
04242       (_x.action_result.result.grasp.grasp_pose.position.x, _x.action_result.result.grasp.grasp_pose.position.y, _x.action_result.result.grasp.grasp_pose.position.z, _x.action_result.result.grasp.grasp_pose.orientation.x, _x.action_result.result.grasp.grasp_pose.orientation.y, _x.action_result.result.grasp.grasp_pose.orientation.z, _x.action_result.result.grasp.grasp_pose.orientation.w, _x.action_result.result.grasp.success_probability, _x.action_result.result.grasp.cluster_rep, _x.action_result.result.grasp.desired_approach_distance, _x.action_result.result.grasp.min_approach_distance,) = _struct_8dB2f.unpack(str[start:end])
04243       self.action_result.result.grasp.cluster_rep = bool(self.action_result.result.grasp.cluster_rep)
04244       start = end
04245       end += 4
04246       (length,) = _struct_I.unpack(str[start:end])
04247       self.action_result.result.grasp.moved_obstacles = []
04248       for i in range(0, length):
04249         val1 = object_manipulation_msgs.msg.GraspableObject()
04250         start = end
04251         end += 4
04252         (length,) = _struct_I.unpack(str[start:end])
04253         start = end
04254         end += length
04255         if python3:
04256           val1.reference_frame_id = str[start:end].decode('utf-8')
04257         else:
04258           val1.reference_frame_id = str[start:end]
04259         start = end
04260         end += 4
04261         (length,) = _struct_I.unpack(str[start:end])
04262         val1.potential_models = []
04263         for i in range(0, length):
04264           val2 = household_objects_database_msgs.msg.DatabaseModelPose()
04265           start = end
04266           end += 4
04267           (val2.model_id,) = _struct_i.unpack(str[start:end])
04268           _v262 = val2.pose
04269           _v263 = _v262.header
04270           start = end
04271           end += 4
04272           (_v263.seq,) = _struct_I.unpack(str[start:end])
04273           _v264 = _v263.stamp
04274           _x = _v264
04275           start = end
04276           end += 8
04277           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04278           start = end
04279           end += 4
04280           (length,) = _struct_I.unpack(str[start:end])
04281           start = end
04282           end += length
04283           if python3:
04284             _v263.frame_id = str[start:end].decode('utf-8')
04285           else:
04286             _v263.frame_id = str[start:end]
04287           _v265 = _v262.pose
04288           _v266 = _v265.position
04289           _x = _v266
04290           start = end
04291           end += 24
04292           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04293           _v267 = _v265.orientation
04294           _x = _v267
04295           start = end
04296           end += 32
04297           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04298           start = end
04299           end += 4
04300           (val2.confidence,) = _struct_f.unpack(str[start:end])
04301           start = end
04302           end += 4
04303           (length,) = _struct_I.unpack(str[start:end])
04304           start = end
04305           end += length
04306           if python3:
04307             val2.detector_name = str[start:end].decode('utf-8')
04308           else:
04309             val2.detector_name = str[start:end]
04310           val1.potential_models.append(val2)
04311         _v268 = val1.cluster
04312         _v269 = _v268.header
04313         start = end
04314         end += 4
04315         (_v269.seq,) = _struct_I.unpack(str[start:end])
04316         _v270 = _v269.stamp
04317         _x = _v270
04318         start = end
04319         end += 8
04320         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04321         start = end
04322         end += 4
04323         (length,) = _struct_I.unpack(str[start:end])
04324         start = end
04325         end += length
04326         if python3:
04327           _v269.frame_id = str[start:end].decode('utf-8')
04328         else:
04329           _v269.frame_id = str[start:end]
04330         start = end
04331         end += 4
04332         (length,) = _struct_I.unpack(str[start:end])
04333         _v268.points = []
04334         for i in range(0, length):
04335           val3 = geometry_msgs.msg.Point32()
04336           _x = val3
04337           start = end
04338           end += 12
04339           (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
04340           _v268.points.append(val3)
04341         start = end
04342         end += 4
04343         (length,) = _struct_I.unpack(str[start:end])
04344         _v268.channels = []
04345         for i in range(0, length):
04346           val3 = sensor_msgs.msg.ChannelFloat32()
04347           start = end
04348           end += 4
04349           (length,) = _struct_I.unpack(str[start:end])
04350           start = end
04351           end += length
04352           if python3:
04353             val3.name = str[start:end].decode('utf-8')
04354           else:
04355             val3.name = str[start:end]
04356           start = end
04357           end += 4
04358           (length,) = _struct_I.unpack(str[start:end])
04359           pattern = '<%sf'%length
04360           start = end
04361           end += struct.calcsize(pattern)
04362           val3.values = struct.unpack(pattern, str[start:end])
04363           _v268.channels.append(val3)
04364         _v271 = val1.region
04365         _v272 = _v271.cloud
04366         _v273 = _v272.header
04367         start = end
04368         end += 4
04369         (_v273.seq,) = _struct_I.unpack(str[start:end])
04370         _v274 = _v273.stamp
04371         _x = _v274
04372         start = end
04373         end += 8
04374         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04375         start = end
04376         end += 4
04377         (length,) = _struct_I.unpack(str[start:end])
04378         start = end
04379         end += length
04380         if python3:
04381           _v273.frame_id = str[start:end].decode('utf-8')
04382         else:
04383           _v273.frame_id = str[start:end]
04384         _x = _v272
04385         start = end
04386         end += 8
04387         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04388         start = end
04389         end += 4
04390         (length,) = _struct_I.unpack(str[start:end])
04391         _v272.fields = []
04392         for i in range(0, length):
04393           val4 = sensor_msgs.msg.PointField()
04394           start = end
04395           end += 4
04396           (length,) = _struct_I.unpack(str[start:end])
04397           start = end
04398           end += length
04399           if python3:
04400             val4.name = str[start:end].decode('utf-8')
04401           else:
04402             val4.name = str[start:end]
04403           _x = val4
04404           start = end
04405           end += 9
04406           (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
04407           _v272.fields.append(val4)
04408         _x = _v272
04409         start = end
04410         end += 9
04411         (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
04412         _v272.is_bigendian = bool(_v272.is_bigendian)
04413         start = end
04414         end += 4
04415         (length,) = _struct_I.unpack(str[start:end])
04416         start = end
04417         end += length
04418         if python3:
04419           _v272.data = str[start:end].decode('utf-8')
04420         else:
04421           _v272.data = str[start:end]
04422         start = end
04423         end += 1
04424         (_v272.is_dense,) = _struct_B.unpack(str[start:end])
04425         _v272.is_dense = bool(_v272.is_dense)
04426         start = end
04427         end += 4
04428         (length,) = _struct_I.unpack(str[start:end])
04429         pattern = '<%si'%length
04430         start = end
04431         end += struct.calcsize(pattern)
04432         _v271.mask = struct.unpack(pattern, str[start:end])
04433         _v275 = _v271.image
04434         _v276 = _v275.header
04435         start = end
04436         end += 4
04437         (_v276.seq,) = _struct_I.unpack(str[start:end])
04438         _v277 = _v276.stamp
04439         _x = _v277
04440         start = end
04441         end += 8
04442         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04443         start = end
04444         end += 4
04445         (length,) = _struct_I.unpack(str[start:end])
04446         start = end
04447         end += length
04448         if python3:
04449           _v276.frame_id = str[start:end].decode('utf-8')
04450         else:
04451           _v276.frame_id = str[start:end]
04452         _x = _v275
04453         start = end
04454         end += 8
04455         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04456         start = end
04457         end += 4
04458         (length,) = _struct_I.unpack(str[start:end])
04459         start = end
04460         end += length
04461         if python3:
04462           _v275.encoding = str[start:end].decode('utf-8')
04463         else:
04464           _v275.encoding = str[start:end]
04465         _x = _v275
04466         start = end
04467         end += 5
04468         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
04469         start = end
04470         end += 4
04471         (length,) = _struct_I.unpack(str[start:end])
04472         start = end
04473         end += length
04474         if python3:
04475           _v275.data = str[start:end].decode('utf-8')
04476         else:
04477           _v275.data = str[start:end]
04478         _v278 = _v271.disparity_image
04479         _v279 = _v278.header
04480         start = end
04481         end += 4
04482         (_v279.seq,) = _struct_I.unpack(str[start:end])
04483         _v280 = _v279.stamp
04484         _x = _v280
04485         start = end
04486         end += 8
04487         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04488         start = end
04489         end += 4
04490         (length,) = _struct_I.unpack(str[start:end])
04491         start = end
04492         end += length
04493         if python3:
04494           _v279.frame_id = str[start:end].decode('utf-8')
04495         else:
04496           _v279.frame_id = str[start:end]
04497         _x = _v278
04498         start = end
04499         end += 8
04500         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04501         start = end
04502         end += 4
04503         (length,) = _struct_I.unpack(str[start:end])
04504         start = end
04505         end += length
04506         if python3:
04507           _v278.encoding = str[start:end].decode('utf-8')
04508         else:
04509           _v278.encoding = str[start:end]
04510         _x = _v278
04511         start = end
04512         end += 5
04513         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
04514         start = end
04515         end += 4
04516         (length,) = _struct_I.unpack(str[start:end])
04517         start = end
04518         end += length
04519         if python3:
04520           _v278.data = str[start:end].decode('utf-8')
04521         else:
04522           _v278.data = str[start:end]
04523         _v281 = _v271.cam_info
04524         _v282 = _v281.header
04525         start = end
04526         end += 4
04527         (_v282.seq,) = _struct_I.unpack(str[start:end])
04528         _v283 = _v282.stamp
04529         _x = _v283
04530         start = end
04531         end += 8
04532         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04533         start = end
04534         end += 4
04535         (length,) = _struct_I.unpack(str[start:end])
04536         start = end
04537         end += length
04538         if python3:
04539           _v282.frame_id = str[start:end].decode('utf-8')
04540         else:
04541           _v282.frame_id = str[start:end]
04542         _x = _v281
04543         start = end
04544         end += 8
04545         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04546         start = end
04547         end += 4
04548         (length,) = _struct_I.unpack(str[start:end])
04549         start = end
04550         end += length
04551         if python3:
04552           _v281.distortion_model = str[start:end].decode('utf-8')
04553         else:
04554           _v281.distortion_model = str[start:end]
04555         start = end
04556         end += 4
04557         (length,) = _struct_I.unpack(str[start:end])
04558         pattern = '<%sd'%length
04559         start = end
04560         end += struct.calcsize(pattern)
04561         _v281.D = struct.unpack(pattern, str[start:end])
04562         start = end
04563         end += 72
04564         _v281.K = _struct_9d.unpack(str[start:end])
04565         start = end
04566         end += 72
04567         _v281.R = _struct_9d.unpack(str[start:end])
04568         start = end
04569         end += 96
04570         _v281.P = _struct_12d.unpack(str[start:end])
04571         _x = _v281
04572         start = end
04573         end += 8
04574         (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
04575         _v284 = _v281.roi
04576         _x = _v284
04577         start = end
04578         end += 17
04579         (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
04580         _v284.do_rectify = bool(_v284.do_rectify)
04581         _v285 = _v271.roi_box_pose
04582         _v286 = _v285.header
04583         start = end
04584         end += 4
04585         (_v286.seq,) = _struct_I.unpack(str[start:end])
04586         _v287 = _v286.stamp
04587         _x = _v287
04588         start = end
04589         end += 8
04590         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04591         start = end
04592         end += 4
04593         (length,) = _struct_I.unpack(str[start:end])
04594         start = end
04595         end += length
04596         if python3:
04597           _v286.frame_id = str[start:end].decode('utf-8')
04598         else:
04599           _v286.frame_id = str[start:end]
04600         _v288 = _v285.pose
04601         _v289 = _v288.position
04602         _x = _v289
04603         start = end
04604         end += 24
04605         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04606         _v290 = _v288.orientation
04607         _x = _v290
04608         start = end
04609         end += 32
04610         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04611         _v291 = _v271.roi_box_dims
04612         _x = _v291
04613         start = end
04614         end += 24
04615         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04616         start = end
04617         end += 4
04618         (length,) = _struct_I.unpack(str[start:end])
04619         start = end
04620         end += length
04621         if python3:
04622           val1.collision_name = str[start:end].decode('utf-8')
04623         else:
04624           val1.collision_name = str[start:end]
04625         self.action_result.result.grasp.moved_obstacles.append(val1)
04626       start = end
04627       end += 4
04628       (length,) = _struct_I.unpack(str[start:end])
04629       self.action_result.result.attempted_grasps = []
04630       for i in range(0, length):
04631         val1 = object_manipulation_msgs.msg.Grasp()
04632         _v292 = val1.pre_grasp_posture
04633         _v293 = _v292.header
04634         start = end
04635         end += 4
04636         (_v293.seq,) = _struct_I.unpack(str[start:end])
04637         _v294 = _v293.stamp
04638         _x = _v294
04639         start = end
04640         end += 8
04641         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04642         start = end
04643         end += 4
04644         (length,) = _struct_I.unpack(str[start:end])
04645         start = end
04646         end += length
04647         if python3:
04648           _v293.frame_id = str[start:end].decode('utf-8')
04649         else:
04650           _v293.frame_id = str[start:end]
04651         start = end
04652         end += 4
04653         (length,) = _struct_I.unpack(str[start:end])
04654         _v292.name = []
04655         for i in range(0, length):
04656           start = end
04657           end += 4
04658           (length,) = _struct_I.unpack(str[start:end])
04659           start = end
04660           end += length
04661           if python3:
04662             val3 = str[start:end].decode('utf-8')
04663           else:
04664             val3 = str[start:end]
04665           _v292.name.append(val3)
04666         start = end
04667         end += 4
04668         (length,) = _struct_I.unpack(str[start:end])
04669         pattern = '<%sd'%length
04670         start = end
04671         end += struct.calcsize(pattern)
04672         _v292.position = struct.unpack(pattern, str[start:end])
04673         start = end
04674         end += 4
04675         (length,) = _struct_I.unpack(str[start:end])
04676         pattern = '<%sd'%length
04677         start = end
04678         end += struct.calcsize(pattern)
04679         _v292.velocity = struct.unpack(pattern, str[start:end])
04680         start = end
04681         end += 4
04682         (length,) = _struct_I.unpack(str[start:end])
04683         pattern = '<%sd'%length
04684         start = end
04685         end += struct.calcsize(pattern)
04686         _v292.effort = struct.unpack(pattern, str[start:end])
04687         _v295 = val1.grasp_posture
04688         _v296 = _v295.header
04689         start = end
04690         end += 4
04691         (_v296.seq,) = _struct_I.unpack(str[start:end])
04692         _v297 = _v296.stamp
04693         _x = _v297
04694         start = end
04695         end += 8
04696         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04697         start = end
04698         end += 4
04699         (length,) = _struct_I.unpack(str[start:end])
04700         start = end
04701         end += length
04702         if python3:
04703           _v296.frame_id = str[start:end].decode('utf-8')
04704         else:
04705           _v296.frame_id = str[start:end]
04706         start = end
04707         end += 4
04708         (length,) = _struct_I.unpack(str[start:end])
04709         _v295.name = []
04710         for i in range(0, length):
04711           start = end
04712           end += 4
04713           (length,) = _struct_I.unpack(str[start:end])
04714           start = end
04715           end += length
04716           if python3:
04717             val3 = str[start:end].decode('utf-8')
04718           else:
04719             val3 = str[start:end]
04720           _v295.name.append(val3)
04721         start = end
04722         end += 4
04723         (length,) = _struct_I.unpack(str[start:end])
04724         pattern = '<%sd'%length
04725         start = end
04726         end += struct.calcsize(pattern)
04727         _v295.position = struct.unpack(pattern, str[start:end])
04728         start = end
04729         end += 4
04730         (length,) = _struct_I.unpack(str[start:end])
04731         pattern = '<%sd'%length
04732         start = end
04733         end += struct.calcsize(pattern)
04734         _v295.velocity = struct.unpack(pattern, str[start:end])
04735         start = end
04736         end += 4
04737         (length,) = _struct_I.unpack(str[start:end])
04738         pattern = '<%sd'%length
04739         start = end
04740         end += struct.calcsize(pattern)
04741         _v295.effort = struct.unpack(pattern, str[start:end])
04742         _v298 = val1.grasp_pose
04743         _v299 = _v298.position
04744         _x = _v299
04745         start = end
04746         end += 24
04747         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04748         _v300 = _v298.orientation
04749         _x = _v300
04750         start = end
04751         end += 32
04752         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04753         _x = val1
04754         start = end
04755         end += 17
04756         (_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance,) = _struct_dB2f.unpack(str[start:end])
04757         val1.cluster_rep = bool(val1.cluster_rep)
04758         start = end
04759         end += 4
04760         (length,) = _struct_I.unpack(str[start:end])
04761         val1.moved_obstacles = []
04762         for i in range(0, length):
04763           val2 = object_manipulation_msgs.msg.GraspableObject()
04764           start = end
04765           end += 4
04766           (length,) = _struct_I.unpack(str[start:end])
04767           start = end
04768           end += length
04769           if python3:
04770             val2.reference_frame_id = str[start:end].decode('utf-8')
04771           else:
04772             val2.reference_frame_id = str[start:end]
04773           start = end
04774           end += 4
04775           (length,) = _struct_I.unpack(str[start:end])
04776           val2.potential_models = []
04777           for i in range(0, length):
04778             val3 = household_objects_database_msgs.msg.DatabaseModelPose()
04779             start = end
04780             end += 4
04781             (val3.model_id,) = _struct_i.unpack(str[start:end])
04782             _v301 = val3.pose
04783             _v302 = _v301.header
04784             start = end
04785             end += 4
04786             (_v302.seq,) = _struct_I.unpack(str[start:end])
04787             _v303 = _v302.stamp
04788             _x = _v303
04789             start = end
04790             end += 8
04791             (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04792             start = end
04793             end += 4
04794             (length,) = _struct_I.unpack(str[start:end])
04795             start = end
04796             end += length
04797             if python3:
04798               _v302.frame_id = str[start:end].decode('utf-8')
04799             else:
04800               _v302.frame_id = str[start:end]
04801             _v304 = _v301.pose
04802             _v305 = _v304.position
04803             _x = _v305
04804             start = end
04805             end += 24
04806             (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04807             _v306 = _v304.orientation
04808             _x = _v306
04809             start = end
04810             end += 32
04811             (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04812             start = end
04813             end += 4
04814             (val3.confidence,) = _struct_f.unpack(str[start:end])
04815             start = end
04816             end += 4
04817             (length,) = _struct_I.unpack(str[start:end])
04818             start = end
04819             end += length
04820             if python3:
04821               val3.detector_name = str[start:end].decode('utf-8')
04822             else:
04823               val3.detector_name = str[start:end]
04824             val2.potential_models.append(val3)
04825           _v307 = val2.cluster
04826           _v308 = _v307.header
04827           start = end
04828           end += 4
04829           (_v308.seq,) = _struct_I.unpack(str[start:end])
04830           _v309 = _v308.stamp
04831           _x = _v309
04832           start = end
04833           end += 8
04834           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04835           start = end
04836           end += 4
04837           (length,) = _struct_I.unpack(str[start:end])
04838           start = end
04839           end += length
04840           if python3:
04841             _v308.frame_id = str[start:end].decode('utf-8')
04842           else:
04843             _v308.frame_id = str[start:end]
04844           start = end
04845           end += 4
04846           (length,) = _struct_I.unpack(str[start:end])
04847           _v307.points = []
04848           for i in range(0, length):
04849             val4 = geometry_msgs.msg.Point32()
04850             _x = val4
04851             start = end
04852             end += 12
04853             (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
04854             _v307.points.append(val4)
04855           start = end
04856           end += 4
04857           (length,) = _struct_I.unpack(str[start:end])
04858           _v307.channels = []
04859           for i in range(0, length):
04860             val4 = sensor_msgs.msg.ChannelFloat32()
04861             start = end
04862             end += 4
04863             (length,) = _struct_I.unpack(str[start:end])
04864             start = end
04865             end += length
04866             if python3:
04867               val4.name = str[start:end].decode('utf-8')
04868             else:
04869               val4.name = str[start:end]
04870             start = end
04871             end += 4
04872             (length,) = _struct_I.unpack(str[start:end])
04873             pattern = '<%sf'%length
04874             start = end
04875             end += struct.calcsize(pattern)
04876             val4.values = struct.unpack(pattern, str[start:end])
04877             _v307.channels.append(val4)
04878           _v310 = val2.region
04879           _v311 = _v310.cloud
04880           _v312 = _v311.header
04881           start = end
04882           end += 4
04883           (_v312.seq,) = _struct_I.unpack(str[start:end])
04884           _v313 = _v312.stamp
04885           _x = _v313
04886           start = end
04887           end += 8
04888           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04889           start = end
04890           end += 4
04891           (length,) = _struct_I.unpack(str[start:end])
04892           start = end
04893           end += length
04894           if python3:
04895             _v312.frame_id = str[start:end].decode('utf-8')
04896           else:
04897             _v312.frame_id = str[start:end]
04898           _x = _v311
04899           start = end
04900           end += 8
04901           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04902           start = end
04903           end += 4
04904           (length,) = _struct_I.unpack(str[start:end])
04905           _v311.fields = []
04906           for i in range(0, length):
04907             val5 = sensor_msgs.msg.PointField()
04908             start = end
04909             end += 4
04910             (length,) = _struct_I.unpack(str[start:end])
04911             start = end
04912             end += length
04913             if python3:
04914               val5.name = str[start:end].decode('utf-8')
04915             else:
04916               val5.name = str[start:end]
04917             _x = val5
04918             start = end
04919             end += 9
04920             (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
04921             _v311.fields.append(val5)
04922           _x = _v311
04923           start = end
04924           end += 9
04925           (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
04926           _v311.is_bigendian = bool(_v311.is_bigendian)
04927           start = end
04928           end += 4
04929           (length,) = _struct_I.unpack(str[start:end])
04930           start = end
04931           end += length
04932           if python3:
04933             _v311.data = str[start:end].decode('utf-8')
04934           else:
04935             _v311.data = str[start:end]
04936           start = end
04937           end += 1
04938           (_v311.is_dense,) = _struct_B.unpack(str[start:end])
04939           _v311.is_dense = bool(_v311.is_dense)
04940           start = end
04941           end += 4
04942           (length,) = _struct_I.unpack(str[start:end])
04943           pattern = '<%si'%length
04944           start = end
04945           end += struct.calcsize(pattern)
04946           _v310.mask = struct.unpack(pattern, str[start:end])
04947           _v314 = _v310.image
04948           _v315 = _v314.header
04949           start = end
04950           end += 4
04951           (_v315.seq,) = _struct_I.unpack(str[start:end])
04952           _v316 = _v315.stamp
04953           _x = _v316
04954           start = end
04955           end += 8
04956           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04957           start = end
04958           end += 4
04959           (length,) = _struct_I.unpack(str[start:end])
04960           start = end
04961           end += length
04962           if python3:
04963             _v315.frame_id = str[start:end].decode('utf-8')
04964           else:
04965             _v315.frame_id = str[start:end]
04966           _x = _v314
04967           start = end
04968           end += 8
04969           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04970           start = end
04971           end += 4
04972           (length,) = _struct_I.unpack(str[start:end])
04973           start = end
04974           end += length
04975           if python3:
04976             _v314.encoding = str[start:end].decode('utf-8')
04977           else:
04978             _v314.encoding = str[start:end]
04979           _x = _v314
04980           start = end
04981           end += 5
04982           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
04983           start = end
04984           end += 4
04985           (length,) = _struct_I.unpack(str[start:end])
04986           start = end
04987           end += length
04988           if python3:
04989             _v314.data = str[start:end].decode('utf-8')
04990           else:
04991             _v314.data = str[start:end]
04992           _v317 = _v310.disparity_image
04993           _v318 = _v317.header
04994           start = end
04995           end += 4
04996           (_v318.seq,) = _struct_I.unpack(str[start:end])
04997           _v319 = _v318.stamp
04998           _x = _v319
04999           start = end
05000           end += 8
05001           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
05002           start = end
05003           end += 4
05004           (length,) = _struct_I.unpack(str[start:end])
05005           start = end
05006           end += length
05007           if python3:
05008             _v318.frame_id = str[start:end].decode('utf-8')
05009           else:
05010             _v318.frame_id = str[start:end]
05011           _x = _v317
05012           start = end
05013           end += 8
05014           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
05015           start = end
05016           end += 4
05017           (length,) = _struct_I.unpack(str[start:end])
05018           start = end
05019           end += length
05020           if python3:
05021             _v317.encoding = str[start:end].decode('utf-8')
05022           else:
05023             _v317.encoding = str[start:end]
05024           _x = _v317
05025           start = end
05026           end += 5
05027           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
05028           start = end
05029           end += 4
05030           (length,) = _struct_I.unpack(str[start:end])
05031           start = end
05032           end += length
05033           if python3:
05034             _v317.data = str[start:end].decode('utf-8')
05035           else:
05036             _v317.data = str[start:end]
05037           _v320 = _v310.cam_info
05038           _v321 = _v320.header
05039           start = end
05040           end += 4
05041           (_v321.seq,) = _struct_I.unpack(str[start:end])
05042           _v322 = _v321.stamp
05043           _x = _v322
05044           start = end
05045           end += 8
05046           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
05047           start = end
05048           end += 4
05049           (length,) = _struct_I.unpack(str[start:end])
05050           start = end
05051           end += length
05052           if python3:
05053             _v321.frame_id = str[start:end].decode('utf-8')
05054           else:
05055             _v321.frame_id = str[start:end]
05056           _x = _v320
05057           start = end
05058           end += 8
05059           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
05060           start = end
05061           end += 4
05062           (length,) = _struct_I.unpack(str[start:end])
05063           start = end
05064           end += length
05065           if python3:
05066             _v320.distortion_model = str[start:end].decode('utf-8')
05067           else:
05068             _v320.distortion_model = str[start:end]
05069           start = end
05070           end += 4
05071           (length,) = _struct_I.unpack(str[start:end])
05072           pattern = '<%sd'%length
05073           start = end
05074           end += struct.calcsize(pattern)
05075           _v320.D = struct.unpack(pattern, str[start:end])
05076           start = end
05077           end += 72
05078           _v320.K = _struct_9d.unpack(str[start:end])
05079           start = end
05080           end += 72
05081           _v320.R = _struct_9d.unpack(str[start:end])
05082           start = end
05083           end += 96
05084           _v320.P = _struct_12d.unpack(str[start:end])
05085           _x = _v320
05086           start = end
05087           end += 8
05088           (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
05089           _v323 = _v320.roi
05090           _x = _v323
05091           start = end
05092           end += 17
05093           (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
05094           _v323.do_rectify = bool(_v323.do_rectify)
05095           _v324 = _v310.roi_box_pose
05096           _v325 = _v324.header
05097           start = end
05098           end += 4
05099           (_v325.seq,) = _struct_I.unpack(str[start:end])
05100           _v326 = _v325.stamp
05101           _x = _v326
05102           start = end
05103           end += 8
05104           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
05105           start = end
05106           end += 4
05107           (length,) = _struct_I.unpack(str[start:end])
05108           start = end
05109           end += length
05110           if python3:
05111             _v325.frame_id = str[start:end].decode('utf-8')
05112           else:
05113             _v325.frame_id = str[start:end]
05114           _v327 = _v324.pose
05115           _v328 = _v327.position
05116           _x = _v328
05117           start = end
05118           end += 24
05119           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
05120           _v329 = _v327.orientation
05121           _x = _v329
05122           start = end
05123           end += 32
05124           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
05125           _v330 = _v310.roi_box_dims
05126           _x = _v330
05127           start = end
05128           end += 24
05129           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
05130           start = end
05131           end += 4
05132           (length,) = _struct_I.unpack(str[start:end])
05133           start = end
05134           end += length
05135           if python3:
05136             val2.collision_name = str[start:end].decode('utf-8')
05137           else:
05138             val2.collision_name = str[start:end]
05139           val1.moved_obstacles.append(val2)
05140         self.action_result.result.attempted_grasps.append(val1)
05141       start = end
05142       end += 4
05143       (length,) = _struct_I.unpack(str[start:end])
05144       self.action_result.result.attempted_grasp_results = []
05145       for i in range(0, length):
05146         val1 = object_manipulation_msgs.msg.GraspResult()
05147         _x = val1
05148         start = end
05149         end += 5
05150         (_x.result_code, _x.continuation_possible,) = _struct_iB.unpack(str[start:end])
05151         val1.continuation_possible = bool(val1.continuation_possible)
05152         self.action_result.result.attempted_grasp_results.append(val1)
05153       _x = self
05154       start = end
05155       end += 12
05156       (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
05157       start = end
05158       end += 4
05159       (length,) = _struct_I.unpack(str[start:end])
05160       start = end
05161       end += length
05162       if python3:
05163         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
05164       else:
05165         self.action_feedback.header.frame_id = str[start:end]
05166       _x = self
05167       start = end
05168       end += 8
05169       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
05170       start = end
05171       end += 4
05172       (length,) = _struct_I.unpack(str[start:end])
05173       start = end
05174       end += length
05175       if python3:
05176         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
05177       else:
05178         self.action_feedback.status.goal_id.id = str[start:end]
05179       start = end
05180       end += 1
05181       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
05182       start = end
05183       end += 4
05184       (length,) = _struct_I.unpack(str[start:end])
05185       start = end
05186       end += length
05187       if python3:
05188         self.action_feedback.status.text = str[start:end].decode('utf-8')
05189       else:
05190         self.action_feedback.status.text = str[start:end]
05191       _x = self
05192       start = end
05193       end += 8
05194       (_x.action_feedback.feedback.current_grasp, _x.action_feedback.feedback.total_grasps,) = _struct_2i.unpack(str[start:end])
05195       return self
05196     except struct.error as e:
05197       raise genpy.DeserializationError(e) #most likely buffer underfill
05198 
05199 
05200   def serialize_numpy(self, buff, numpy):
05201     """
05202     serialize message with numpy array types into buffer
05203     :param buff: buffer, ``StringIO``
05204     :param numpy: numpy python module
05205     """
05206     try:
05207       _x = self
05208       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
05209       _x = self.action_goal.header.frame_id
05210       length = len(_x)
05211       if python3 or type(_x) == unicode:
05212         _x = _x.encode('utf-8')
05213         length = len(_x)
05214       buff.write(struct.pack('<I%ss'%length, length, _x))
05215       _x = self
05216       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
05217       _x = self.action_goal.goal_id.id
05218       length = len(_x)
05219       if python3 or type(_x) == unicode:
05220         _x = _x.encode('utf-8')
05221         length = len(_x)
05222       buff.write(struct.pack('<I%ss'%length, length, _x))
05223       _x = self.action_goal.goal.arm_name
05224       length = len(_x)
05225       if python3 or type(_x) == unicode:
05226         _x = _x.encode('utf-8')
05227         length = len(_x)
05228       buff.write(struct.pack('<I%ss'%length, length, _x))
05229       _x = self.action_goal.goal.target.reference_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       length = len(self.action_goal.goal.target.potential_models)
05236       buff.write(_struct_I.pack(length))
05237       for val1 in self.action_goal.goal.target.potential_models:
05238         buff.write(_struct_i.pack(val1.model_id))
05239         _v331 = val1.pose
05240         _v332 = _v331.header
05241         buff.write(_struct_I.pack(_v332.seq))
05242         _v333 = _v332.stamp
05243         _x = _v333
05244         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05245         _x = _v332.frame_id
05246         length = len(_x)
05247         if python3 or type(_x) == unicode:
05248           _x = _x.encode('utf-8')
05249           length = len(_x)
05250         buff.write(struct.pack('<I%ss'%length, length, _x))
05251         _v334 = _v331.pose
05252         _v335 = _v334.position
05253         _x = _v335
05254         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
05255         _v336 = _v334.orientation
05256         _x = _v336
05257         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
05258         buff.write(_struct_f.pack(val1.confidence))
05259         _x = val1.detector_name
05260         length = len(_x)
05261         if python3 or type(_x) == unicode:
05262           _x = _x.encode('utf-8')
05263           length = len(_x)
05264         buff.write(struct.pack('<I%ss'%length, length, _x))
05265       _x = self
05266       buff.write(_struct_3I.pack(_x.action_goal.goal.target.cluster.header.seq, _x.action_goal.goal.target.cluster.header.stamp.secs, _x.action_goal.goal.target.cluster.header.stamp.nsecs))
05267       _x = self.action_goal.goal.target.cluster.header.frame_id
05268       length = len(_x)
05269       if python3 or type(_x) == unicode:
05270         _x = _x.encode('utf-8')
05271         length = len(_x)
05272       buff.write(struct.pack('<I%ss'%length, length, _x))
05273       length = len(self.action_goal.goal.target.cluster.points)
05274       buff.write(_struct_I.pack(length))
05275       for val1 in self.action_goal.goal.target.cluster.points:
05276         _x = val1
05277         buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
05278       length = len(self.action_goal.goal.target.cluster.channels)
05279       buff.write(_struct_I.pack(length))
05280       for val1 in self.action_goal.goal.target.cluster.channels:
05281         _x = val1.name
05282         length = len(_x)
05283         if python3 or type(_x) == unicode:
05284           _x = _x.encode('utf-8')
05285           length = len(_x)
05286         buff.write(struct.pack('<I%ss'%length, length, _x))
05287         length = len(val1.values)
05288         buff.write(_struct_I.pack(length))
05289         pattern = '<%sf'%length
05290         buff.write(val1.values.tostring())
05291       _x = self
05292       buff.write(_struct_3I.pack(_x.action_goal.goal.target.region.cloud.header.seq, _x.action_goal.goal.target.region.cloud.header.stamp.secs, _x.action_goal.goal.target.region.cloud.header.stamp.nsecs))
05293       _x = self.action_goal.goal.target.region.cloud.header.frame_id
05294       length = len(_x)
05295       if python3 or type(_x) == unicode:
05296         _x = _x.encode('utf-8')
05297         length = len(_x)
05298       buff.write(struct.pack('<I%ss'%length, length, _x))
05299       _x = self
05300       buff.write(_struct_2I.pack(_x.action_goal.goal.target.region.cloud.height, _x.action_goal.goal.target.region.cloud.width))
05301       length = len(self.action_goal.goal.target.region.cloud.fields)
05302       buff.write(_struct_I.pack(length))
05303       for val1 in self.action_goal.goal.target.region.cloud.fields:
05304         _x = val1.name
05305         length = len(_x)
05306         if python3 or type(_x) == unicode:
05307           _x = _x.encode('utf-8')
05308           length = len(_x)
05309         buff.write(struct.pack('<I%ss'%length, length, _x))
05310         _x = val1
05311         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
05312       _x = self
05313       buff.write(_struct_B2I.pack(_x.action_goal.goal.target.region.cloud.is_bigendian, _x.action_goal.goal.target.region.cloud.point_step, _x.action_goal.goal.target.region.cloud.row_step))
05314       _x = self.action_goal.goal.target.region.cloud.data
05315       length = len(_x)
05316       # - if encoded as a list instead, serialize as bytes instead of string
05317       if type(_x) in [list, tuple]:
05318         buff.write(struct.pack('<I%sB'%length, length, *_x))
05319       else:
05320         buff.write(struct.pack('<I%ss'%length, length, _x))
05321       buff.write(_struct_B.pack(self.action_goal.goal.target.region.cloud.is_dense))
05322       length = len(self.action_goal.goal.target.region.mask)
05323       buff.write(_struct_I.pack(length))
05324       pattern = '<%si'%length
05325       buff.write(self.action_goal.goal.target.region.mask.tostring())
05326       _x = self
05327       buff.write(_struct_3I.pack(_x.action_goal.goal.target.region.image.header.seq, _x.action_goal.goal.target.region.image.header.stamp.secs, _x.action_goal.goal.target.region.image.header.stamp.nsecs))
05328       _x = self.action_goal.goal.target.region.image.header.frame_id
05329       length = len(_x)
05330       if python3 or type(_x) == unicode:
05331         _x = _x.encode('utf-8')
05332         length = len(_x)
05333       buff.write(struct.pack('<I%ss'%length, length, _x))
05334       _x = self
05335       buff.write(_struct_2I.pack(_x.action_goal.goal.target.region.image.height, _x.action_goal.goal.target.region.image.width))
05336       _x = self.action_goal.goal.target.region.image.encoding
05337       length = len(_x)
05338       if python3 or type(_x) == unicode:
05339         _x = _x.encode('utf-8')
05340         length = len(_x)
05341       buff.write(struct.pack('<I%ss'%length, length, _x))
05342       _x = self
05343       buff.write(_struct_BI.pack(_x.action_goal.goal.target.region.image.is_bigendian, _x.action_goal.goal.target.region.image.step))
05344       _x = self.action_goal.goal.target.region.image.data
05345       length = len(_x)
05346       # - if encoded as a list instead, serialize as bytes instead of string
05347       if type(_x) in [list, tuple]:
05348         buff.write(struct.pack('<I%sB'%length, length, *_x))
05349       else:
05350         buff.write(struct.pack('<I%ss'%length, length, _x))
05351       _x = self
05352       buff.write(_struct_3I.pack(_x.action_goal.goal.target.region.disparity_image.header.seq, _x.action_goal.goal.target.region.disparity_image.header.stamp.secs, _x.action_goal.goal.target.region.disparity_image.header.stamp.nsecs))
05353       _x = self.action_goal.goal.target.region.disparity_image.header.frame_id
05354       length = len(_x)
05355       if python3 or type(_x) == unicode:
05356         _x = _x.encode('utf-8')
05357         length = len(_x)
05358       buff.write(struct.pack('<I%ss'%length, length, _x))
05359       _x = self
05360       buff.write(_struct_2I.pack(_x.action_goal.goal.target.region.disparity_image.height, _x.action_goal.goal.target.region.disparity_image.width))
05361       _x = self.action_goal.goal.target.region.disparity_image.encoding
05362       length = len(_x)
05363       if python3 or type(_x) == unicode:
05364         _x = _x.encode('utf-8')
05365         length = len(_x)
05366       buff.write(struct.pack('<I%ss'%length, length, _x))
05367       _x = self
05368       buff.write(_struct_BI.pack(_x.action_goal.goal.target.region.disparity_image.is_bigendian, _x.action_goal.goal.target.region.disparity_image.step))
05369       _x = self.action_goal.goal.target.region.disparity_image.data
05370       length = len(_x)
05371       # - if encoded as a list instead, serialize as bytes instead of string
05372       if type(_x) in [list, tuple]:
05373         buff.write(struct.pack('<I%sB'%length, length, *_x))
05374       else:
05375         buff.write(struct.pack('<I%ss'%length, length, _x))
05376       _x = self
05377       buff.write(_struct_3I.pack(_x.action_goal.goal.target.region.cam_info.header.seq, _x.action_goal.goal.target.region.cam_info.header.stamp.secs, _x.action_goal.goal.target.region.cam_info.header.stamp.nsecs))
05378       _x = self.action_goal.goal.target.region.cam_info.header.frame_id
05379       length = len(_x)
05380       if python3 or type(_x) == unicode:
05381         _x = _x.encode('utf-8')
05382         length = len(_x)
05383       buff.write(struct.pack('<I%ss'%length, length, _x))
05384       _x = self
05385       buff.write(_struct_2I.pack(_x.action_goal.goal.target.region.cam_info.height, _x.action_goal.goal.target.region.cam_info.width))
05386       _x = self.action_goal.goal.target.region.cam_info.distortion_model
05387       length = len(_x)
05388       if python3 or type(_x) == unicode:
05389         _x = _x.encode('utf-8')
05390         length = len(_x)
05391       buff.write(struct.pack('<I%ss'%length, length, _x))
05392       length = len(self.action_goal.goal.target.region.cam_info.D)
05393       buff.write(_struct_I.pack(length))
05394       pattern = '<%sd'%length
05395       buff.write(self.action_goal.goal.target.region.cam_info.D.tostring())
05396       buff.write(self.action_goal.goal.target.region.cam_info.K.tostring())
05397       buff.write(self.action_goal.goal.target.region.cam_info.R.tostring())
05398       buff.write(self.action_goal.goal.target.region.cam_info.P.tostring())
05399       _x = self
05400       buff.write(_struct_6IB3I.pack(_x.action_goal.goal.target.region.cam_info.binning_x, _x.action_goal.goal.target.region.cam_info.binning_y, _x.action_goal.goal.target.region.cam_info.roi.x_offset, _x.action_goal.goal.target.region.cam_info.roi.y_offset, _x.action_goal.goal.target.region.cam_info.roi.height, _x.action_goal.goal.target.region.cam_info.roi.width, _x.action_goal.goal.target.region.cam_info.roi.do_rectify, _x.action_goal.goal.target.region.roi_box_pose.header.seq, _x.action_goal.goal.target.region.roi_box_pose.header.stamp.secs, _x.action_goal.goal.target.region.roi_box_pose.header.stamp.nsecs))
05401       _x = self.action_goal.goal.target.region.roi_box_pose.header.frame_id
05402       length = len(_x)
05403       if python3 or type(_x) == unicode:
05404         _x = _x.encode('utf-8')
05405         length = len(_x)
05406       buff.write(struct.pack('<I%ss'%length, length, _x))
05407       _x = self
05408       buff.write(_struct_10d.pack(_x.action_goal.goal.target.region.roi_box_pose.pose.position.x, _x.action_goal.goal.target.region.roi_box_pose.pose.position.y, _x.action_goal.goal.target.region.roi_box_pose.pose.position.z, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.x, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.y, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.z, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.w, _x.action_goal.goal.target.region.roi_box_dims.x, _x.action_goal.goal.target.region.roi_box_dims.y, _x.action_goal.goal.target.region.roi_box_dims.z))
05409       _x = self.action_goal.goal.target.collision_name
05410       length = len(_x)
05411       if python3 or type(_x) == unicode:
05412         _x = _x.encode('utf-8')
05413         length = len(_x)
05414       buff.write(struct.pack('<I%ss'%length, length, _x))
05415       length = len(self.action_goal.goal.desired_grasps)
05416       buff.write(_struct_I.pack(length))
05417       for val1 in self.action_goal.goal.desired_grasps:
05418         _v337 = val1.pre_grasp_posture
05419         _v338 = _v337.header
05420         buff.write(_struct_I.pack(_v338.seq))
05421         _v339 = _v338.stamp
05422         _x = _v339
05423         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05424         _x = _v338.frame_id
05425         length = len(_x)
05426         if python3 or type(_x) == unicode:
05427           _x = _x.encode('utf-8')
05428           length = len(_x)
05429         buff.write(struct.pack('<I%ss'%length, length, _x))
05430         length = len(_v337.name)
05431         buff.write(_struct_I.pack(length))
05432         for val3 in _v337.name:
05433           length = len(val3)
05434           if python3 or type(val3) == unicode:
05435             val3 = val3.encode('utf-8')
05436             length = len(val3)
05437           buff.write(struct.pack('<I%ss'%length, length, val3))
05438         length = len(_v337.position)
05439         buff.write(_struct_I.pack(length))
05440         pattern = '<%sd'%length
05441         buff.write(_v337.position.tostring())
05442         length = len(_v337.velocity)
05443         buff.write(_struct_I.pack(length))
05444         pattern = '<%sd'%length
05445         buff.write(_v337.velocity.tostring())
05446         length = len(_v337.effort)
05447         buff.write(_struct_I.pack(length))
05448         pattern = '<%sd'%length
05449         buff.write(_v337.effort.tostring())
05450         _v340 = val1.grasp_posture
05451         _v341 = _v340.header
05452         buff.write(_struct_I.pack(_v341.seq))
05453         _v342 = _v341.stamp
05454         _x = _v342
05455         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05456         _x = _v341.frame_id
05457         length = len(_x)
05458         if python3 or type(_x) == unicode:
05459           _x = _x.encode('utf-8')
05460           length = len(_x)
05461         buff.write(struct.pack('<I%ss'%length, length, _x))
05462         length = len(_v340.name)
05463         buff.write(_struct_I.pack(length))
05464         for val3 in _v340.name:
05465           length = len(val3)
05466           if python3 or type(val3) == unicode:
05467             val3 = val3.encode('utf-8')
05468             length = len(val3)
05469           buff.write(struct.pack('<I%ss'%length, length, val3))
05470         length = len(_v340.position)
05471         buff.write(_struct_I.pack(length))
05472         pattern = '<%sd'%length
05473         buff.write(_v340.position.tostring())
05474         length = len(_v340.velocity)
05475         buff.write(_struct_I.pack(length))
05476         pattern = '<%sd'%length
05477         buff.write(_v340.velocity.tostring())
05478         length = len(_v340.effort)
05479         buff.write(_struct_I.pack(length))
05480         pattern = '<%sd'%length
05481         buff.write(_v340.effort.tostring())
05482         _v343 = val1.grasp_pose
05483         _v344 = _v343.position
05484         _x = _v344
05485         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
05486         _v345 = _v343.orientation
05487         _x = _v345
05488         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
05489         _x = val1
05490         buff.write(_struct_dB2f.pack(_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance))
05491         length = len(val1.moved_obstacles)
05492         buff.write(_struct_I.pack(length))
05493         for val2 in val1.moved_obstacles:
05494           _x = val2.reference_frame_id
05495           length = len(_x)
05496           if python3 or type(_x) == unicode:
05497             _x = _x.encode('utf-8')
05498             length = len(_x)
05499           buff.write(struct.pack('<I%ss'%length, length, _x))
05500           length = len(val2.potential_models)
05501           buff.write(_struct_I.pack(length))
05502           for val3 in val2.potential_models:
05503             buff.write(_struct_i.pack(val3.model_id))
05504             _v346 = val3.pose
05505             _v347 = _v346.header
05506             buff.write(_struct_I.pack(_v347.seq))
05507             _v348 = _v347.stamp
05508             _x = _v348
05509             buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05510             _x = _v347.frame_id
05511             length = len(_x)
05512             if python3 or type(_x) == unicode:
05513               _x = _x.encode('utf-8')
05514               length = len(_x)
05515             buff.write(struct.pack('<I%ss'%length, length, _x))
05516             _v349 = _v346.pose
05517             _v350 = _v349.position
05518             _x = _v350
05519             buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
05520             _v351 = _v349.orientation
05521             _x = _v351
05522             buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
05523             buff.write(_struct_f.pack(val3.confidence))
05524             _x = val3.detector_name
05525             length = len(_x)
05526             if python3 or type(_x) == unicode:
05527               _x = _x.encode('utf-8')
05528               length = len(_x)
05529             buff.write(struct.pack('<I%ss'%length, length, _x))
05530           _v352 = val2.cluster
05531           _v353 = _v352.header
05532           buff.write(_struct_I.pack(_v353.seq))
05533           _v354 = _v353.stamp
05534           _x = _v354
05535           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05536           _x = _v353.frame_id
05537           length = len(_x)
05538           if python3 or type(_x) == unicode:
05539             _x = _x.encode('utf-8')
05540             length = len(_x)
05541           buff.write(struct.pack('<I%ss'%length, length, _x))
05542           length = len(_v352.points)
05543           buff.write(_struct_I.pack(length))
05544           for val4 in _v352.points:
05545             _x = val4
05546             buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
05547           length = len(_v352.channels)
05548           buff.write(_struct_I.pack(length))
05549           for val4 in _v352.channels:
05550             _x = val4.name
05551             length = len(_x)
05552             if python3 or type(_x) == unicode:
05553               _x = _x.encode('utf-8')
05554               length = len(_x)
05555             buff.write(struct.pack('<I%ss'%length, length, _x))
05556             length = len(val4.values)
05557             buff.write(_struct_I.pack(length))
05558             pattern = '<%sf'%length
05559             buff.write(val4.values.tostring())
05560           _v355 = val2.region
05561           _v356 = _v355.cloud
05562           _v357 = _v356.header
05563           buff.write(_struct_I.pack(_v357.seq))
05564           _v358 = _v357.stamp
05565           _x = _v358
05566           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05567           _x = _v357.frame_id
05568           length = len(_x)
05569           if python3 or type(_x) == unicode:
05570             _x = _x.encode('utf-8')
05571             length = len(_x)
05572           buff.write(struct.pack('<I%ss'%length, length, _x))
05573           _x = _v356
05574           buff.write(_struct_2I.pack(_x.height, _x.width))
05575           length = len(_v356.fields)
05576           buff.write(_struct_I.pack(length))
05577           for val5 in _v356.fields:
05578             _x = val5.name
05579             length = len(_x)
05580             if python3 or type(_x) == unicode:
05581               _x = _x.encode('utf-8')
05582               length = len(_x)
05583             buff.write(struct.pack('<I%ss'%length, length, _x))
05584             _x = val5
05585             buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
05586           _x = _v356
05587           buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
05588           _x = _v356.data
05589           length = len(_x)
05590           # - if encoded as a list instead, serialize as bytes instead of string
05591           if type(_x) in [list, tuple]:
05592             buff.write(struct.pack('<I%sB'%length, length, *_x))
05593           else:
05594             buff.write(struct.pack('<I%ss'%length, length, _x))
05595           buff.write(_struct_B.pack(_v356.is_dense))
05596           length = len(_v355.mask)
05597           buff.write(_struct_I.pack(length))
05598           pattern = '<%si'%length
05599           buff.write(_v355.mask.tostring())
05600           _v359 = _v355.image
05601           _v360 = _v359.header
05602           buff.write(_struct_I.pack(_v360.seq))
05603           _v361 = _v360.stamp
05604           _x = _v361
05605           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05606           _x = _v360.frame_id
05607           length = len(_x)
05608           if python3 or type(_x) == unicode:
05609             _x = _x.encode('utf-8')
05610             length = len(_x)
05611           buff.write(struct.pack('<I%ss'%length, length, _x))
05612           _x = _v359
05613           buff.write(_struct_2I.pack(_x.height, _x.width))
05614           _x = _v359.encoding
05615           length = len(_x)
05616           if python3 or type(_x) == unicode:
05617             _x = _x.encode('utf-8')
05618             length = len(_x)
05619           buff.write(struct.pack('<I%ss'%length, length, _x))
05620           _x = _v359
05621           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
05622           _x = _v359.data
05623           length = len(_x)
05624           # - if encoded as a list instead, serialize as bytes instead of string
05625           if type(_x) in [list, tuple]:
05626             buff.write(struct.pack('<I%sB'%length, length, *_x))
05627           else:
05628             buff.write(struct.pack('<I%ss'%length, length, _x))
05629           _v362 = _v355.disparity_image
05630           _v363 = _v362.header
05631           buff.write(_struct_I.pack(_v363.seq))
05632           _v364 = _v363.stamp
05633           _x = _v364
05634           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05635           _x = _v363.frame_id
05636           length = len(_x)
05637           if python3 or type(_x) == unicode:
05638             _x = _x.encode('utf-8')
05639             length = len(_x)
05640           buff.write(struct.pack('<I%ss'%length, length, _x))
05641           _x = _v362
05642           buff.write(_struct_2I.pack(_x.height, _x.width))
05643           _x = _v362.encoding
05644           length = len(_x)
05645           if python3 or type(_x) == unicode:
05646             _x = _x.encode('utf-8')
05647             length = len(_x)
05648           buff.write(struct.pack('<I%ss'%length, length, _x))
05649           _x = _v362
05650           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
05651           _x = _v362.data
05652           length = len(_x)
05653           # - if encoded as a list instead, serialize as bytes instead of string
05654           if type(_x) in [list, tuple]:
05655             buff.write(struct.pack('<I%sB'%length, length, *_x))
05656           else:
05657             buff.write(struct.pack('<I%ss'%length, length, _x))
05658           _v365 = _v355.cam_info
05659           _v366 = _v365.header
05660           buff.write(_struct_I.pack(_v366.seq))
05661           _v367 = _v366.stamp
05662           _x = _v367
05663           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05664           _x = _v366.frame_id
05665           length = len(_x)
05666           if python3 or type(_x) == unicode:
05667             _x = _x.encode('utf-8')
05668             length = len(_x)
05669           buff.write(struct.pack('<I%ss'%length, length, _x))
05670           _x = _v365
05671           buff.write(_struct_2I.pack(_x.height, _x.width))
05672           _x = _v365.distortion_model
05673           length = len(_x)
05674           if python3 or type(_x) == unicode:
05675             _x = _x.encode('utf-8')
05676             length = len(_x)
05677           buff.write(struct.pack('<I%ss'%length, length, _x))
05678           length = len(_v365.D)
05679           buff.write(_struct_I.pack(length))
05680           pattern = '<%sd'%length
05681           buff.write(_v365.D.tostring())
05682           buff.write(_v365.K.tostring())
05683           buff.write(_v365.R.tostring())
05684           buff.write(_v365.P.tostring())
05685           _x = _v365
05686           buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
05687           _v368 = _v365.roi
05688           _x = _v368
05689           buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
05690           _v369 = _v355.roi_box_pose
05691           _v370 = _v369.header
05692           buff.write(_struct_I.pack(_v370.seq))
05693           _v371 = _v370.stamp
05694           _x = _v371
05695           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05696           _x = _v370.frame_id
05697           length = len(_x)
05698           if python3 or type(_x) == unicode:
05699             _x = _x.encode('utf-8')
05700             length = len(_x)
05701           buff.write(struct.pack('<I%ss'%length, length, _x))
05702           _v372 = _v369.pose
05703           _v373 = _v372.position
05704           _x = _v373
05705           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
05706           _v374 = _v372.orientation
05707           _x = _v374
05708           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
05709           _v375 = _v355.roi_box_dims
05710           _x = _v375
05711           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
05712           _x = val2.collision_name
05713           length = len(_x)
05714           if python3 or type(_x) == unicode:
05715             _x = _x.encode('utf-8')
05716             length = len(_x)
05717           buff.write(struct.pack('<I%ss'%length, length, _x))
05718       _x = self
05719       buff.write(_struct_3I.pack(_x.action_goal.goal.lift.direction.header.seq, _x.action_goal.goal.lift.direction.header.stamp.secs, _x.action_goal.goal.lift.direction.header.stamp.nsecs))
05720       _x = self.action_goal.goal.lift.direction.header.frame_id
05721       length = len(_x)
05722       if python3 or type(_x) == unicode:
05723         _x = _x.encode('utf-8')
05724         length = len(_x)
05725       buff.write(struct.pack('<I%ss'%length, length, _x))
05726       _x = self
05727       buff.write(_struct_3d2f.pack(_x.action_goal.goal.lift.direction.vector.x, _x.action_goal.goal.lift.direction.vector.y, _x.action_goal.goal.lift.direction.vector.z, _x.action_goal.goal.lift.desired_distance, _x.action_goal.goal.lift.min_distance))
05728       _x = self.action_goal.goal.collision_object_name
05729       length = len(_x)
05730       if python3 or type(_x) == unicode:
05731         _x = _x.encode('utf-8')
05732         length = len(_x)
05733       buff.write(struct.pack('<I%ss'%length, length, _x))
05734       _x = self.action_goal.goal.collision_support_surface_name
05735       length = len(_x)
05736       if python3 or type(_x) == unicode:
05737         _x = _x.encode('utf-8')
05738         length = len(_x)
05739       buff.write(struct.pack('<I%ss'%length, length, _x))
05740       _x = self
05741       buff.write(_struct_5B.pack(_x.action_goal.goal.allow_gripper_support_collision, _x.action_goal.goal.use_reactive_execution, _x.action_goal.goal.use_reactive_lift, _x.action_goal.goal.only_perform_feasibility_test, _x.action_goal.goal.ignore_collisions))
05742       length = len(self.action_goal.goal.path_constraints.joint_constraints)
05743       buff.write(_struct_I.pack(length))
05744       for val1 in self.action_goal.goal.path_constraints.joint_constraints:
05745         _x = val1.joint_name
05746         length = len(_x)
05747         if python3 or type(_x) == unicode:
05748           _x = _x.encode('utf-8')
05749           length = len(_x)
05750         buff.write(struct.pack('<I%ss'%length, length, _x))
05751         _x = val1
05752         buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
05753       length = len(self.action_goal.goal.path_constraints.position_constraints)
05754       buff.write(_struct_I.pack(length))
05755       for val1 in self.action_goal.goal.path_constraints.position_constraints:
05756         _v376 = val1.header
05757         buff.write(_struct_I.pack(_v376.seq))
05758         _v377 = _v376.stamp
05759         _x = _v377
05760         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05761         _x = _v376.frame_id
05762         length = len(_x)
05763         if python3 or type(_x) == unicode:
05764           _x = _x.encode('utf-8')
05765           length = len(_x)
05766         buff.write(struct.pack('<I%ss'%length, length, _x))
05767         _x = val1.link_name
05768         length = len(_x)
05769         if python3 or type(_x) == unicode:
05770           _x = _x.encode('utf-8')
05771           length = len(_x)
05772         buff.write(struct.pack('<I%ss'%length, length, _x))
05773         _v378 = val1.target_point_offset
05774         _x = _v378
05775         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
05776         _v379 = val1.position
05777         _x = _v379
05778         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
05779         _v380 = val1.constraint_region_shape
05780         buff.write(_struct_b.pack(_v380.type))
05781         length = len(_v380.dimensions)
05782         buff.write(_struct_I.pack(length))
05783         pattern = '<%sd'%length
05784         buff.write(_v380.dimensions.tostring())
05785         length = len(_v380.triangles)
05786         buff.write(_struct_I.pack(length))
05787         pattern = '<%si'%length
05788         buff.write(_v380.triangles.tostring())
05789         length = len(_v380.vertices)
05790         buff.write(_struct_I.pack(length))
05791         for val3 in _v380.vertices:
05792           _x = val3
05793           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
05794         _v381 = val1.constraint_region_orientation
05795         _x = _v381
05796         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
05797         buff.write(_struct_d.pack(val1.weight))
05798       length = len(self.action_goal.goal.path_constraints.orientation_constraints)
05799       buff.write(_struct_I.pack(length))
05800       for val1 in self.action_goal.goal.path_constraints.orientation_constraints:
05801         _v382 = val1.header
05802         buff.write(_struct_I.pack(_v382.seq))
05803         _v383 = _v382.stamp
05804         _x = _v383
05805         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05806         _x = _v382.frame_id
05807         length = len(_x)
05808         if python3 or type(_x) == unicode:
05809           _x = _x.encode('utf-8')
05810           length = len(_x)
05811         buff.write(struct.pack('<I%ss'%length, length, _x))
05812         _x = val1.link_name
05813         length = len(_x)
05814         if python3 or type(_x) == unicode:
05815           _x = _x.encode('utf-8')
05816           length = len(_x)
05817         buff.write(struct.pack('<I%ss'%length, length, _x))
05818         buff.write(_struct_i.pack(val1.type))
05819         _v384 = val1.orientation
05820         _x = _v384
05821         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
05822         _x = val1
05823         buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
05824       length = len(self.action_goal.goal.path_constraints.visibility_constraints)
05825       buff.write(_struct_I.pack(length))
05826       for val1 in self.action_goal.goal.path_constraints.visibility_constraints:
05827         _v385 = val1.header
05828         buff.write(_struct_I.pack(_v385.seq))
05829         _v386 = _v385.stamp
05830         _x = _v386
05831         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05832         _x = _v385.frame_id
05833         length = len(_x)
05834         if python3 or type(_x) == unicode:
05835           _x = _x.encode('utf-8')
05836           length = len(_x)
05837         buff.write(struct.pack('<I%ss'%length, length, _x))
05838         _v387 = val1.target
05839         _v388 = _v387.header
05840         buff.write(_struct_I.pack(_v388.seq))
05841         _v389 = _v388.stamp
05842         _x = _v389
05843         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05844         _x = _v388.frame_id
05845         length = len(_x)
05846         if python3 or type(_x) == unicode:
05847           _x = _x.encode('utf-8')
05848           length = len(_x)
05849         buff.write(struct.pack('<I%ss'%length, length, _x))
05850         _v390 = _v387.point
05851         _x = _v390
05852         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
05853         _v391 = val1.sensor_pose
05854         _v392 = _v391.header
05855         buff.write(_struct_I.pack(_v392.seq))
05856         _v393 = _v392.stamp
05857         _x = _v393
05858         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05859         _x = _v392.frame_id
05860         length = len(_x)
05861         if python3 or type(_x) == unicode:
05862           _x = _x.encode('utf-8')
05863           length = len(_x)
05864         buff.write(struct.pack('<I%ss'%length, length, _x))
05865         _v394 = _v391.pose
05866         _v395 = _v394.position
05867         _x = _v395
05868         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
05869         _v396 = _v394.orientation
05870         _x = _v396
05871         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
05872         buff.write(_struct_d.pack(val1.absolute_tolerance))
05873       length = len(self.action_goal.goal.additional_collision_operations.collision_operations)
05874       buff.write(_struct_I.pack(length))
05875       for val1 in self.action_goal.goal.additional_collision_operations.collision_operations:
05876         _x = val1.object1
05877         length = len(_x)
05878         if python3 or type(_x) == unicode:
05879           _x = _x.encode('utf-8')
05880           length = len(_x)
05881         buff.write(struct.pack('<I%ss'%length, length, _x))
05882         _x = val1.object2
05883         length = len(_x)
05884         if python3 or type(_x) == unicode:
05885           _x = _x.encode('utf-8')
05886           length = len(_x)
05887         buff.write(struct.pack('<I%ss'%length, length, _x))
05888         _x = val1
05889         buff.write(_struct_di.pack(_x.penetration_distance, _x.operation))
05890       length = len(self.action_goal.goal.additional_link_padding)
05891       buff.write(_struct_I.pack(length))
05892       for val1 in self.action_goal.goal.additional_link_padding:
05893         _x = val1.link_name
05894         length = len(_x)
05895         if python3 or type(_x) == unicode:
05896           _x = _x.encode('utf-8')
05897           length = len(_x)
05898         buff.write(struct.pack('<I%ss'%length, length, _x))
05899         buff.write(_struct_d.pack(val1.padding))
05900       length = len(self.action_goal.goal.movable_obstacles)
05901       buff.write(_struct_I.pack(length))
05902       for val1 in self.action_goal.goal.movable_obstacles:
05903         _x = val1.reference_frame_id
05904         length = len(_x)
05905         if python3 or type(_x) == unicode:
05906           _x = _x.encode('utf-8')
05907           length = len(_x)
05908         buff.write(struct.pack('<I%ss'%length, length, _x))
05909         length = len(val1.potential_models)
05910         buff.write(_struct_I.pack(length))
05911         for val2 in val1.potential_models:
05912           buff.write(_struct_i.pack(val2.model_id))
05913           _v397 = val2.pose
05914           _v398 = _v397.header
05915           buff.write(_struct_I.pack(_v398.seq))
05916           _v399 = _v398.stamp
05917           _x = _v399
05918           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05919           _x = _v398.frame_id
05920           length = len(_x)
05921           if python3 or type(_x) == unicode:
05922             _x = _x.encode('utf-8')
05923             length = len(_x)
05924           buff.write(struct.pack('<I%ss'%length, length, _x))
05925           _v400 = _v397.pose
05926           _v401 = _v400.position
05927           _x = _v401
05928           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
05929           _v402 = _v400.orientation
05930           _x = _v402
05931           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
05932           buff.write(_struct_f.pack(val2.confidence))
05933           _x = val2.detector_name
05934           length = len(_x)
05935           if python3 or type(_x) == unicode:
05936             _x = _x.encode('utf-8')
05937             length = len(_x)
05938           buff.write(struct.pack('<I%ss'%length, length, _x))
05939         _v403 = val1.cluster
05940         _v404 = _v403.header
05941         buff.write(_struct_I.pack(_v404.seq))
05942         _v405 = _v404.stamp
05943         _x = _v405
05944         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05945         _x = _v404.frame_id
05946         length = len(_x)
05947         if python3 or type(_x) == unicode:
05948           _x = _x.encode('utf-8')
05949           length = len(_x)
05950         buff.write(struct.pack('<I%ss'%length, length, _x))
05951         length = len(_v403.points)
05952         buff.write(_struct_I.pack(length))
05953         for val3 in _v403.points:
05954           _x = val3
05955           buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
05956         length = len(_v403.channels)
05957         buff.write(_struct_I.pack(length))
05958         for val3 in _v403.channels:
05959           _x = val3.name
05960           length = len(_x)
05961           if python3 or type(_x) == unicode:
05962             _x = _x.encode('utf-8')
05963             length = len(_x)
05964           buff.write(struct.pack('<I%ss'%length, length, _x))
05965           length = len(val3.values)
05966           buff.write(_struct_I.pack(length))
05967           pattern = '<%sf'%length
05968           buff.write(val3.values.tostring())
05969         _v406 = val1.region
05970         _v407 = _v406.cloud
05971         _v408 = _v407.header
05972         buff.write(_struct_I.pack(_v408.seq))
05973         _v409 = _v408.stamp
05974         _x = _v409
05975         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
05976         _x = _v408.frame_id
05977         length = len(_x)
05978         if python3 or type(_x) == unicode:
05979           _x = _x.encode('utf-8')
05980           length = len(_x)
05981         buff.write(struct.pack('<I%ss'%length, length, _x))
05982         _x = _v407
05983         buff.write(_struct_2I.pack(_x.height, _x.width))
05984         length = len(_v407.fields)
05985         buff.write(_struct_I.pack(length))
05986         for val4 in _v407.fields:
05987           _x = val4.name
05988           length = len(_x)
05989           if python3 or type(_x) == unicode:
05990             _x = _x.encode('utf-8')
05991             length = len(_x)
05992           buff.write(struct.pack('<I%ss'%length, length, _x))
05993           _x = val4
05994           buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
05995         _x = _v407
05996         buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
05997         _x = _v407.data
05998         length = len(_x)
05999         # - if encoded as a list instead, serialize as bytes instead of string
06000         if type(_x) in [list, tuple]:
06001           buff.write(struct.pack('<I%sB'%length, length, *_x))
06002         else:
06003           buff.write(struct.pack('<I%ss'%length, length, _x))
06004         buff.write(_struct_B.pack(_v407.is_dense))
06005         length = len(_v406.mask)
06006         buff.write(_struct_I.pack(length))
06007         pattern = '<%si'%length
06008         buff.write(_v406.mask.tostring())
06009         _v410 = _v406.image
06010         _v411 = _v410.header
06011         buff.write(_struct_I.pack(_v411.seq))
06012         _v412 = _v411.stamp
06013         _x = _v412
06014         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06015         _x = _v411.frame_id
06016         length = len(_x)
06017         if python3 or type(_x) == unicode:
06018           _x = _x.encode('utf-8')
06019           length = len(_x)
06020         buff.write(struct.pack('<I%ss'%length, length, _x))
06021         _x = _v410
06022         buff.write(_struct_2I.pack(_x.height, _x.width))
06023         _x = _v410.encoding
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         _x = _v410
06030         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
06031         _x = _v410.data
06032         length = len(_x)
06033         # - if encoded as a list instead, serialize as bytes instead of string
06034         if type(_x) in [list, tuple]:
06035           buff.write(struct.pack('<I%sB'%length, length, *_x))
06036         else:
06037           buff.write(struct.pack('<I%ss'%length, length, _x))
06038         _v413 = _v406.disparity_image
06039         _v414 = _v413.header
06040         buff.write(_struct_I.pack(_v414.seq))
06041         _v415 = _v414.stamp
06042         _x = _v415
06043         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06044         _x = _v414.frame_id
06045         length = len(_x)
06046         if python3 or type(_x) == unicode:
06047           _x = _x.encode('utf-8')
06048           length = len(_x)
06049         buff.write(struct.pack('<I%ss'%length, length, _x))
06050         _x = _v413
06051         buff.write(_struct_2I.pack(_x.height, _x.width))
06052         _x = _v413.encoding
06053         length = len(_x)
06054         if python3 or type(_x) == unicode:
06055           _x = _x.encode('utf-8')
06056           length = len(_x)
06057         buff.write(struct.pack('<I%ss'%length, length, _x))
06058         _x = _v413
06059         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
06060         _x = _v413.data
06061         length = len(_x)
06062         # - if encoded as a list instead, serialize as bytes instead of string
06063         if type(_x) in [list, tuple]:
06064           buff.write(struct.pack('<I%sB'%length, length, *_x))
06065         else:
06066           buff.write(struct.pack('<I%ss'%length, length, _x))
06067         _v416 = _v406.cam_info
06068         _v417 = _v416.header
06069         buff.write(_struct_I.pack(_v417.seq))
06070         _v418 = _v417.stamp
06071         _x = _v418
06072         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06073         _x = _v417.frame_id
06074         length = len(_x)
06075         if python3 or type(_x) == unicode:
06076           _x = _x.encode('utf-8')
06077           length = len(_x)
06078         buff.write(struct.pack('<I%ss'%length, length, _x))
06079         _x = _v416
06080         buff.write(_struct_2I.pack(_x.height, _x.width))
06081         _x = _v416.distortion_model
06082         length = len(_x)
06083         if python3 or type(_x) == unicode:
06084           _x = _x.encode('utf-8')
06085           length = len(_x)
06086         buff.write(struct.pack('<I%ss'%length, length, _x))
06087         length = len(_v416.D)
06088         buff.write(_struct_I.pack(length))
06089         pattern = '<%sd'%length
06090         buff.write(_v416.D.tostring())
06091         buff.write(_v416.K.tostring())
06092         buff.write(_v416.R.tostring())
06093         buff.write(_v416.P.tostring())
06094         _x = _v416
06095         buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
06096         _v419 = _v416.roi
06097         _x = _v419
06098         buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
06099         _v420 = _v406.roi_box_pose
06100         _v421 = _v420.header
06101         buff.write(_struct_I.pack(_v421.seq))
06102         _v422 = _v421.stamp
06103         _x = _v422
06104         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06105         _x = _v421.frame_id
06106         length = len(_x)
06107         if python3 or type(_x) == unicode:
06108           _x = _x.encode('utf-8')
06109           length = len(_x)
06110         buff.write(struct.pack('<I%ss'%length, length, _x))
06111         _v423 = _v420.pose
06112         _v424 = _v423.position
06113         _x = _v424
06114         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
06115         _v425 = _v423.orientation
06116         _x = _v425
06117         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
06118         _v426 = _v406.roi_box_dims
06119         _x = _v426
06120         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
06121         _x = val1.collision_name
06122         length = len(_x)
06123         if python3 or type(_x) == unicode:
06124           _x = _x.encode('utf-8')
06125           length = len(_x)
06126         buff.write(struct.pack('<I%ss'%length, length, _x))
06127       _x = self
06128       buff.write(_struct_f3I.pack(_x.action_goal.goal.max_contact_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
06129       _x = self.action_result.header.frame_id
06130       length = len(_x)
06131       if python3 or type(_x) == unicode:
06132         _x = _x.encode('utf-8')
06133         length = len(_x)
06134       buff.write(struct.pack('<I%ss'%length, length, _x))
06135       _x = self
06136       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
06137       _x = self.action_result.status.goal_id.id
06138       length = len(_x)
06139       if python3 or type(_x) == unicode:
06140         _x = _x.encode('utf-8')
06141         length = len(_x)
06142       buff.write(struct.pack('<I%ss'%length, length, _x))
06143       buff.write(_struct_B.pack(self.action_result.status.status))
06144       _x = self.action_result.status.text
06145       length = len(_x)
06146       if python3 or type(_x) == unicode:
06147         _x = _x.encode('utf-8')
06148         length = len(_x)
06149       buff.write(struct.pack('<I%ss'%length, length, _x))
06150       _x = self
06151       buff.write(_struct_i3I.pack(_x.action_result.result.manipulation_result.value, _x.action_result.result.grasp.pre_grasp_posture.header.seq, _x.action_result.result.grasp.pre_grasp_posture.header.stamp.secs, _x.action_result.result.grasp.pre_grasp_posture.header.stamp.nsecs))
06152       _x = self.action_result.result.grasp.pre_grasp_posture.header.frame_id
06153       length = len(_x)
06154       if python3 or type(_x) == unicode:
06155         _x = _x.encode('utf-8')
06156         length = len(_x)
06157       buff.write(struct.pack('<I%ss'%length, length, _x))
06158       length = len(self.action_result.result.grasp.pre_grasp_posture.name)
06159       buff.write(_struct_I.pack(length))
06160       for val1 in self.action_result.result.grasp.pre_grasp_posture.name:
06161         length = len(val1)
06162         if python3 or type(val1) == unicode:
06163           val1 = val1.encode('utf-8')
06164           length = len(val1)
06165         buff.write(struct.pack('<I%ss'%length, length, val1))
06166       length = len(self.action_result.result.grasp.pre_grasp_posture.position)
06167       buff.write(_struct_I.pack(length))
06168       pattern = '<%sd'%length
06169       buff.write(self.action_result.result.grasp.pre_grasp_posture.position.tostring())
06170       length = len(self.action_result.result.grasp.pre_grasp_posture.velocity)
06171       buff.write(_struct_I.pack(length))
06172       pattern = '<%sd'%length
06173       buff.write(self.action_result.result.grasp.pre_grasp_posture.velocity.tostring())
06174       length = len(self.action_result.result.grasp.pre_grasp_posture.effort)
06175       buff.write(_struct_I.pack(length))
06176       pattern = '<%sd'%length
06177       buff.write(self.action_result.result.grasp.pre_grasp_posture.effort.tostring())
06178       _x = self
06179       buff.write(_struct_3I.pack(_x.action_result.result.grasp.grasp_posture.header.seq, _x.action_result.result.grasp.grasp_posture.header.stamp.secs, _x.action_result.result.grasp.grasp_posture.header.stamp.nsecs))
06180       _x = self.action_result.result.grasp.grasp_posture.header.frame_id
06181       length = len(_x)
06182       if python3 or type(_x) == unicode:
06183         _x = _x.encode('utf-8')
06184         length = len(_x)
06185       buff.write(struct.pack('<I%ss'%length, length, _x))
06186       length = len(self.action_result.result.grasp.grasp_posture.name)
06187       buff.write(_struct_I.pack(length))
06188       for val1 in self.action_result.result.grasp.grasp_posture.name:
06189         length = len(val1)
06190         if python3 or type(val1) == unicode:
06191           val1 = val1.encode('utf-8')
06192           length = len(val1)
06193         buff.write(struct.pack('<I%ss'%length, length, val1))
06194       length = len(self.action_result.result.grasp.grasp_posture.position)
06195       buff.write(_struct_I.pack(length))
06196       pattern = '<%sd'%length
06197       buff.write(self.action_result.result.grasp.grasp_posture.position.tostring())
06198       length = len(self.action_result.result.grasp.grasp_posture.velocity)
06199       buff.write(_struct_I.pack(length))
06200       pattern = '<%sd'%length
06201       buff.write(self.action_result.result.grasp.grasp_posture.velocity.tostring())
06202       length = len(self.action_result.result.grasp.grasp_posture.effort)
06203       buff.write(_struct_I.pack(length))
06204       pattern = '<%sd'%length
06205       buff.write(self.action_result.result.grasp.grasp_posture.effort.tostring())
06206       _x = self
06207       buff.write(_struct_8dB2f.pack(_x.action_result.result.grasp.grasp_pose.position.x, _x.action_result.result.grasp.grasp_pose.position.y, _x.action_result.result.grasp.grasp_pose.position.z, _x.action_result.result.grasp.grasp_pose.orientation.x, _x.action_result.result.grasp.grasp_pose.orientation.y, _x.action_result.result.grasp.grasp_pose.orientation.z, _x.action_result.result.grasp.grasp_pose.orientation.w, _x.action_result.result.grasp.success_probability, _x.action_result.result.grasp.cluster_rep, _x.action_result.result.grasp.desired_approach_distance, _x.action_result.result.grasp.min_approach_distance))
06208       length = len(self.action_result.result.grasp.moved_obstacles)
06209       buff.write(_struct_I.pack(length))
06210       for val1 in self.action_result.result.grasp.moved_obstacles:
06211         _x = val1.reference_frame_id
06212         length = len(_x)
06213         if python3 or type(_x) == unicode:
06214           _x = _x.encode('utf-8')
06215           length = len(_x)
06216         buff.write(struct.pack('<I%ss'%length, length, _x))
06217         length = len(val1.potential_models)
06218         buff.write(_struct_I.pack(length))
06219         for val2 in val1.potential_models:
06220           buff.write(_struct_i.pack(val2.model_id))
06221           _v427 = val2.pose
06222           _v428 = _v427.header
06223           buff.write(_struct_I.pack(_v428.seq))
06224           _v429 = _v428.stamp
06225           _x = _v429
06226           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06227           _x = _v428.frame_id
06228           length = len(_x)
06229           if python3 or type(_x) == unicode:
06230             _x = _x.encode('utf-8')
06231             length = len(_x)
06232           buff.write(struct.pack('<I%ss'%length, length, _x))
06233           _v430 = _v427.pose
06234           _v431 = _v430.position
06235           _x = _v431
06236           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
06237           _v432 = _v430.orientation
06238           _x = _v432
06239           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
06240           buff.write(_struct_f.pack(val2.confidence))
06241           _x = val2.detector_name
06242           length = len(_x)
06243           if python3 or type(_x) == unicode:
06244             _x = _x.encode('utf-8')
06245             length = len(_x)
06246           buff.write(struct.pack('<I%ss'%length, length, _x))
06247         _v433 = val1.cluster
06248         _v434 = _v433.header
06249         buff.write(_struct_I.pack(_v434.seq))
06250         _v435 = _v434.stamp
06251         _x = _v435
06252         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06253         _x = _v434.frame_id
06254         length = len(_x)
06255         if python3 or type(_x) == unicode:
06256           _x = _x.encode('utf-8')
06257           length = len(_x)
06258         buff.write(struct.pack('<I%ss'%length, length, _x))
06259         length = len(_v433.points)
06260         buff.write(_struct_I.pack(length))
06261         for val3 in _v433.points:
06262           _x = val3
06263           buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
06264         length = len(_v433.channels)
06265         buff.write(_struct_I.pack(length))
06266         for val3 in _v433.channels:
06267           _x = val3.name
06268           length = len(_x)
06269           if python3 or type(_x) == unicode:
06270             _x = _x.encode('utf-8')
06271             length = len(_x)
06272           buff.write(struct.pack('<I%ss'%length, length, _x))
06273           length = len(val3.values)
06274           buff.write(_struct_I.pack(length))
06275           pattern = '<%sf'%length
06276           buff.write(val3.values.tostring())
06277         _v436 = val1.region
06278         _v437 = _v436.cloud
06279         _v438 = _v437.header
06280         buff.write(_struct_I.pack(_v438.seq))
06281         _v439 = _v438.stamp
06282         _x = _v439
06283         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06284         _x = _v438.frame_id
06285         length = len(_x)
06286         if python3 or type(_x) == unicode:
06287           _x = _x.encode('utf-8')
06288           length = len(_x)
06289         buff.write(struct.pack('<I%ss'%length, length, _x))
06290         _x = _v437
06291         buff.write(_struct_2I.pack(_x.height, _x.width))
06292         length = len(_v437.fields)
06293         buff.write(_struct_I.pack(length))
06294         for val4 in _v437.fields:
06295           _x = val4.name
06296           length = len(_x)
06297           if python3 or type(_x) == unicode:
06298             _x = _x.encode('utf-8')
06299             length = len(_x)
06300           buff.write(struct.pack('<I%ss'%length, length, _x))
06301           _x = val4
06302           buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
06303         _x = _v437
06304         buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
06305         _x = _v437.data
06306         length = len(_x)
06307         # - if encoded as a list instead, serialize as bytes instead of string
06308         if type(_x) in [list, tuple]:
06309           buff.write(struct.pack('<I%sB'%length, length, *_x))
06310         else:
06311           buff.write(struct.pack('<I%ss'%length, length, _x))
06312         buff.write(_struct_B.pack(_v437.is_dense))
06313         length = len(_v436.mask)
06314         buff.write(_struct_I.pack(length))
06315         pattern = '<%si'%length
06316         buff.write(_v436.mask.tostring())
06317         _v440 = _v436.image
06318         _v441 = _v440.header
06319         buff.write(_struct_I.pack(_v441.seq))
06320         _v442 = _v441.stamp
06321         _x = _v442
06322         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06323         _x = _v441.frame_id
06324         length = len(_x)
06325         if python3 or type(_x) == unicode:
06326           _x = _x.encode('utf-8')
06327           length = len(_x)
06328         buff.write(struct.pack('<I%ss'%length, length, _x))
06329         _x = _v440
06330         buff.write(_struct_2I.pack(_x.height, _x.width))
06331         _x = _v440.encoding
06332         length = len(_x)
06333         if python3 or type(_x) == unicode:
06334           _x = _x.encode('utf-8')
06335           length = len(_x)
06336         buff.write(struct.pack('<I%ss'%length, length, _x))
06337         _x = _v440
06338         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
06339         _x = _v440.data
06340         length = len(_x)
06341         # - if encoded as a list instead, serialize as bytes instead of string
06342         if type(_x) in [list, tuple]:
06343           buff.write(struct.pack('<I%sB'%length, length, *_x))
06344         else:
06345           buff.write(struct.pack('<I%ss'%length, length, _x))
06346         _v443 = _v436.disparity_image
06347         _v444 = _v443.header
06348         buff.write(_struct_I.pack(_v444.seq))
06349         _v445 = _v444.stamp
06350         _x = _v445
06351         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06352         _x = _v444.frame_id
06353         length = len(_x)
06354         if python3 or type(_x) == unicode:
06355           _x = _x.encode('utf-8')
06356           length = len(_x)
06357         buff.write(struct.pack('<I%ss'%length, length, _x))
06358         _x = _v443
06359         buff.write(_struct_2I.pack(_x.height, _x.width))
06360         _x = _v443.encoding
06361         length = len(_x)
06362         if python3 or type(_x) == unicode:
06363           _x = _x.encode('utf-8')
06364           length = len(_x)
06365         buff.write(struct.pack('<I%ss'%length, length, _x))
06366         _x = _v443
06367         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
06368         _x = _v443.data
06369         length = len(_x)
06370         # - if encoded as a list instead, serialize as bytes instead of string
06371         if type(_x) in [list, tuple]:
06372           buff.write(struct.pack('<I%sB'%length, length, *_x))
06373         else:
06374           buff.write(struct.pack('<I%ss'%length, length, _x))
06375         _v446 = _v436.cam_info
06376         _v447 = _v446.header
06377         buff.write(_struct_I.pack(_v447.seq))
06378         _v448 = _v447.stamp
06379         _x = _v448
06380         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06381         _x = _v447.frame_id
06382         length = len(_x)
06383         if python3 or type(_x) == unicode:
06384           _x = _x.encode('utf-8')
06385           length = len(_x)
06386         buff.write(struct.pack('<I%ss'%length, length, _x))
06387         _x = _v446
06388         buff.write(_struct_2I.pack(_x.height, _x.width))
06389         _x = _v446.distortion_model
06390         length = len(_x)
06391         if python3 or type(_x) == unicode:
06392           _x = _x.encode('utf-8')
06393           length = len(_x)
06394         buff.write(struct.pack('<I%ss'%length, length, _x))
06395         length = len(_v446.D)
06396         buff.write(_struct_I.pack(length))
06397         pattern = '<%sd'%length
06398         buff.write(_v446.D.tostring())
06399         buff.write(_v446.K.tostring())
06400         buff.write(_v446.R.tostring())
06401         buff.write(_v446.P.tostring())
06402         _x = _v446
06403         buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
06404         _v449 = _v446.roi
06405         _x = _v449
06406         buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
06407         _v450 = _v436.roi_box_pose
06408         _v451 = _v450.header
06409         buff.write(_struct_I.pack(_v451.seq))
06410         _v452 = _v451.stamp
06411         _x = _v452
06412         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06413         _x = _v451.frame_id
06414         length = len(_x)
06415         if python3 or type(_x) == unicode:
06416           _x = _x.encode('utf-8')
06417           length = len(_x)
06418         buff.write(struct.pack('<I%ss'%length, length, _x))
06419         _v453 = _v450.pose
06420         _v454 = _v453.position
06421         _x = _v454
06422         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
06423         _v455 = _v453.orientation
06424         _x = _v455
06425         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
06426         _v456 = _v436.roi_box_dims
06427         _x = _v456
06428         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
06429         _x = val1.collision_name
06430         length = len(_x)
06431         if python3 or type(_x) == unicode:
06432           _x = _x.encode('utf-8')
06433           length = len(_x)
06434         buff.write(struct.pack('<I%ss'%length, length, _x))
06435       length = len(self.action_result.result.attempted_grasps)
06436       buff.write(_struct_I.pack(length))
06437       for val1 in self.action_result.result.attempted_grasps:
06438         _v457 = val1.pre_grasp_posture
06439         _v458 = _v457.header
06440         buff.write(_struct_I.pack(_v458.seq))
06441         _v459 = _v458.stamp
06442         _x = _v459
06443         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06444         _x = _v458.frame_id
06445         length = len(_x)
06446         if python3 or type(_x) == unicode:
06447           _x = _x.encode('utf-8')
06448           length = len(_x)
06449         buff.write(struct.pack('<I%ss'%length, length, _x))
06450         length = len(_v457.name)
06451         buff.write(_struct_I.pack(length))
06452         for val3 in _v457.name:
06453           length = len(val3)
06454           if python3 or type(val3) == unicode:
06455             val3 = val3.encode('utf-8')
06456             length = len(val3)
06457           buff.write(struct.pack('<I%ss'%length, length, val3))
06458         length = len(_v457.position)
06459         buff.write(_struct_I.pack(length))
06460         pattern = '<%sd'%length
06461         buff.write(_v457.position.tostring())
06462         length = len(_v457.velocity)
06463         buff.write(_struct_I.pack(length))
06464         pattern = '<%sd'%length
06465         buff.write(_v457.velocity.tostring())
06466         length = len(_v457.effort)
06467         buff.write(_struct_I.pack(length))
06468         pattern = '<%sd'%length
06469         buff.write(_v457.effort.tostring())
06470         _v460 = val1.grasp_posture
06471         _v461 = _v460.header
06472         buff.write(_struct_I.pack(_v461.seq))
06473         _v462 = _v461.stamp
06474         _x = _v462
06475         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06476         _x = _v461.frame_id
06477         length = len(_x)
06478         if python3 or type(_x) == unicode:
06479           _x = _x.encode('utf-8')
06480           length = len(_x)
06481         buff.write(struct.pack('<I%ss'%length, length, _x))
06482         length = len(_v460.name)
06483         buff.write(_struct_I.pack(length))
06484         for val3 in _v460.name:
06485           length = len(val3)
06486           if python3 or type(val3) == unicode:
06487             val3 = val3.encode('utf-8')
06488             length = len(val3)
06489           buff.write(struct.pack('<I%ss'%length, length, val3))
06490         length = len(_v460.position)
06491         buff.write(_struct_I.pack(length))
06492         pattern = '<%sd'%length
06493         buff.write(_v460.position.tostring())
06494         length = len(_v460.velocity)
06495         buff.write(_struct_I.pack(length))
06496         pattern = '<%sd'%length
06497         buff.write(_v460.velocity.tostring())
06498         length = len(_v460.effort)
06499         buff.write(_struct_I.pack(length))
06500         pattern = '<%sd'%length
06501         buff.write(_v460.effort.tostring())
06502         _v463 = val1.grasp_pose
06503         _v464 = _v463.position
06504         _x = _v464
06505         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
06506         _v465 = _v463.orientation
06507         _x = _v465
06508         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
06509         _x = val1
06510         buff.write(_struct_dB2f.pack(_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance))
06511         length = len(val1.moved_obstacles)
06512         buff.write(_struct_I.pack(length))
06513         for val2 in val1.moved_obstacles:
06514           _x = val2.reference_frame_id
06515           length = len(_x)
06516           if python3 or type(_x) == unicode:
06517             _x = _x.encode('utf-8')
06518             length = len(_x)
06519           buff.write(struct.pack('<I%ss'%length, length, _x))
06520           length = len(val2.potential_models)
06521           buff.write(_struct_I.pack(length))
06522           for val3 in val2.potential_models:
06523             buff.write(_struct_i.pack(val3.model_id))
06524             _v466 = val3.pose
06525             _v467 = _v466.header
06526             buff.write(_struct_I.pack(_v467.seq))
06527             _v468 = _v467.stamp
06528             _x = _v468
06529             buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06530             _x = _v467.frame_id
06531             length = len(_x)
06532             if python3 or type(_x) == unicode:
06533               _x = _x.encode('utf-8')
06534               length = len(_x)
06535             buff.write(struct.pack('<I%ss'%length, length, _x))
06536             _v469 = _v466.pose
06537             _v470 = _v469.position
06538             _x = _v470
06539             buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
06540             _v471 = _v469.orientation
06541             _x = _v471
06542             buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
06543             buff.write(_struct_f.pack(val3.confidence))
06544             _x = val3.detector_name
06545             length = len(_x)
06546             if python3 or type(_x) == unicode:
06547               _x = _x.encode('utf-8')
06548               length = len(_x)
06549             buff.write(struct.pack('<I%ss'%length, length, _x))
06550           _v472 = val2.cluster
06551           _v473 = _v472.header
06552           buff.write(_struct_I.pack(_v473.seq))
06553           _v474 = _v473.stamp
06554           _x = _v474
06555           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06556           _x = _v473.frame_id
06557           length = len(_x)
06558           if python3 or type(_x) == unicode:
06559             _x = _x.encode('utf-8')
06560             length = len(_x)
06561           buff.write(struct.pack('<I%ss'%length, length, _x))
06562           length = len(_v472.points)
06563           buff.write(_struct_I.pack(length))
06564           for val4 in _v472.points:
06565             _x = val4
06566             buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
06567           length = len(_v472.channels)
06568           buff.write(_struct_I.pack(length))
06569           for val4 in _v472.channels:
06570             _x = val4.name
06571             length = len(_x)
06572             if python3 or type(_x) == unicode:
06573               _x = _x.encode('utf-8')
06574               length = len(_x)
06575             buff.write(struct.pack('<I%ss'%length, length, _x))
06576             length = len(val4.values)
06577             buff.write(_struct_I.pack(length))
06578             pattern = '<%sf'%length
06579             buff.write(val4.values.tostring())
06580           _v475 = val2.region
06581           _v476 = _v475.cloud
06582           _v477 = _v476.header
06583           buff.write(_struct_I.pack(_v477.seq))
06584           _v478 = _v477.stamp
06585           _x = _v478
06586           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06587           _x = _v477.frame_id
06588           length = len(_x)
06589           if python3 or type(_x) == unicode:
06590             _x = _x.encode('utf-8')
06591             length = len(_x)
06592           buff.write(struct.pack('<I%ss'%length, length, _x))
06593           _x = _v476
06594           buff.write(_struct_2I.pack(_x.height, _x.width))
06595           length = len(_v476.fields)
06596           buff.write(_struct_I.pack(length))
06597           for val5 in _v476.fields:
06598             _x = val5.name
06599             length = len(_x)
06600             if python3 or type(_x) == unicode:
06601               _x = _x.encode('utf-8')
06602               length = len(_x)
06603             buff.write(struct.pack('<I%ss'%length, length, _x))
06604             _x = val5
06605             buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
06606           _x = _v476
06607           buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
06608           _x = _v476.data
06609           length = len(_x)
06610           # - if encoded as a list instead, serialize as bytes instead of string
06611           if type(_x) in [list, tuple]:
06612             buff.write(struct.pack('<I%sB'%length, length, *_x))
06613           else:
06614             buff.write(struct.pack('<I%ss'%length, length, _x))
06615           buff.write(_struct_B.pack(_v476.is_dense))
06616           length = len(_v475.mask)
06617           buff.write(_struct_I.pack(length))
06618           pattern = '<%si'%length
06619           buff.write(_v475.mask.tostring())
06620           _v479 = _v475.image
06621           _v480 = _v479.header
06622           buff.write(_struct_I.pack(_v480.seq))
06623           _v481 = _v480.stamp
06624           _x = _v481
06625           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06626           _x = _v480.frame_id
06627           length = len(_x)
06628           if python3 or type(_x) == unicode:
06629             _x = _x.encode('utf-8')
06630             length = len(_x)
06631           buff.write(struct.pack('<I%ss'%length, length, _x))
06632           _x = _v479
06633           buff.write(_struct_2I.pack(_x.height, _x.width))
06634           _x = _v479.encoding
06635           length = len(_x)
06636           if python3 or type(_x) == unicode:
06637             _x = _x.encode('utf-8')
06638             length = len(_x)
06639           buff.write(struct.pack('<I%ss'%length, length, _x))
06640           _x = _v479
06641           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
06642           _x = _v479.data
06643           length = len(_x)
06644           # - if encoded as a list instead, serialize as bytes instead of string
06645           if type(_x) in [list, tuple]:
06646             buff.write(struct.pack('<I%sB'%length, length, *_x))
06647           else:
06648             buff.write(struct.pack('<I%ss'%length, length, _x))
06649           _v482 = _v475.disparity_image
06650           _v483 = _v482.header
06651           buff.write(_struct_I.pack(_v483.seq))
06652           _v484 = _v483.stamp
06653           _x = _v484
06654           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06655           _x = _v483.frame_id
06656           length = len(_x)
06657           if python3 or type(_x) == unicode:
06658             _x = _x.encode('utf-8')
06659             length = len(_x)
06660           buff.write(struct.pack('<I%ss'%length, length, _x))
06661           _x = _v482
06662           buff.write(_struct_2I.pack(_x.height, _x.width))
06663           _x = _v482.encoding
06664           length = len(_x)
06665           if python3 or type(_x) == unicode:
06666             _x = _x.encode('utf-8')
06667             length = len(_x)
06668           buff.write(struct.pack('<I%ss'%length, length, _x))
06669           _x = _v482
06670           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
06671           _x = _v482.data
06672           length = len(_x)
06673           # - if encoded as a list instead, serialize as bytes instead of string
06674           if type(_x) in [list, tuple]:
06675             buff.write(struct.pack('<I%sB'%length, length, *_x))
06676           else:
06677             buff.write(struct.pack('<I%ss'%length, length, _x))
06678           _v485 = _v475.cam_info
06679           _v486 = _v485.header
06680           buff.write(_struct_I.pack(_v486.seq))
06681           _v487 = _v486.stamp
06682           _x = _v487
06683           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06684           _x = _v486.frame_id
06685           length = len(_x)
06686           if python3 or type(_x) == unicode:
06687             _x = _x.encode('utf-8')
06688             length = len(_x)
06689           buff.write(struct.pack('<I%ss'%length, length, _x))
06690           _x = _v485
06691           buff.write(_struct_2I.pack(_x.height, _x.width))
06692           _x = _v485.distortion_model
06693           length = len(_x)
06694           if python3 or type(_x) == unicode:
06695             _x = _x.encode('utf-8')
06696             length = len(_x)
06697           buff.write(struct.pack('<I%ss'%length, length, _x))
06698           length = len(_v485.D)
06699           buff.write(_struct_I.pack(length))
06700           pattern = '<%sd'%length
06701           buff.write(_v485.D.tostring())
06702           buff.write(_v485.K.tostring())
06703           buff.write(_v485.R.tostring())
06704           buff.write(_v485.P.tostring())
06705           _x = _v485
06706           buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
06707           _v488 = _v485.roi
06708           _x = _v488
06709           buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
06710           _v489 = _v475.roi_box_pose
06711           _v490 = _v489.header
06712           buff.write(_struct_I.pack(_v490.seq))
06713           _v491 = _v490.stamp
06714           _x = _v491
06715           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
06716           _x = _v490.frame_id
06717           length = len(_x)
06718           if python3 or type(_x) == unicode:
06719             _x = _x.encode('utf-8')
06720             length = len(_x)
06721           buff.write(struct.pack('<I%ss'%length, length, _x))
06722           _v492 = _v489.pose
06723           _v493 = _v492.position
06724           _x = _v493
06725           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
06726           _v494 = _v492.orientation
06727           _x = _v494
06728           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
06729           _v495 = _v475.roi_box_dims
06730           _x = _v495
06731           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
06732           _x = val2.collision_name
06733           length = len(_x)
06734           if python3 or type(_x) == unicode:
06735             _x = _x.encode('utf-8')
06736             length = len(_x)
06737           buff.write(struct.pack('<I%ss'%length, length, _x))
06738       length = len(self.action_result.result.attempted_grasp_results)
06739       buff.write(_struct_I.pack(length))
06740       for val1 in self.action_result.result.attempted_grasp_results:
06741         _x = val1
06742         buff.write(_struct_iB.pack(_x.result_code, _x.continuation_possible))
06743       _x = self
06744       buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
06745       _x = self.action_feedback.header.frame_id
06746       length = len(_x)
06747       if python3 or type(_x) == unicode:
06748         _x = _x.encode('utf-8')
06749         length = len(_x)
06750       buff.write(struct.pack('<I%ss'%length, length, _x))
06751       _x = self
06752       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
06753       _x = self.action_feedback.status.goal_id.id
06754       length = len(_x)
06755       if python3 or type(_x) == unicode:
06756         _x = _x.encode('utf-8')
06757         length = len(_x)
06758       buff.write(struct.pack('<I%ss'%length, length, _x))
06759       buff.write(_struct_B.pack(self.action_feedback.status.status))
06760       _x = self.action_feedback.status.text
06761       length = len(_x)
06762       if python3 or type(_x) == unicode:
06763         _x = _x.encode('utf-8')
06764         length = len(_x)
06765       buff.write(struct.pack('<I%ss'%length, length, _x))
06766       _x = self
06767       buff.write(_struct_2i.pack(_x.action_feedback.feedback.current_grasp, _x.action_feedback.feedback.total_grasps))
06768     except struct.error as se: self._check_types(se)
06769     except TypeError as te: self._check_types(te)
06770 
06771   def deserialize_numpy(self, str, numpy):
06772     """
06773     unpack serialized message in str into this message instance using numpy for array types
06774     :param str: byte array of serialized message, ``str``
06775     :param numpy: numpy python module
06776     """
06777     try:
06778       if self.action_goal is None:
06779         self.action_goal = object_manipulation_msgs.msg.PickupActionGoal()
06780       if self.action_result is None:
06781         self.action_result = object_manipulation_msgs.msg.PickupActionResult()
06782       if self.action_feedback is None:
06783         self.action_feedback = object_manipulation_msgs.msg.PickupActionFeedback()
06784       end = 0
06785       _x = self
06786       start = end
06787       end += 12
06788       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
06789       start = end
06790       end += 4
06791       (length,) = _struct_I.unpack(str[start:end])
06792       start = end
06793       end += length
06794       if python3:
06795         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
06796       else:
06797         self.action_goal.header.frame_id = str[start:end]
06798       _x = self
06799       start = end
06800       end += 8
06801       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
06802       start = end
06803       end += 4
06804       (length,) = _struct_I.unpack(str[start:end])
06805       start = end
06806       end += length
06807       if python3:
06808         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
06809       else:
06810         self.action_goal.goal_id.id = str[start:end]
06811       start = end
06812       end += 4
06813       (length,) = _struct_I.unpack(str[start:end])
06814       start = end
06815       end += length
06816       if python3:
06817         self.action_goal.goal.arm_name = str[start:end].decode('utf-8')
06818       else:
06819         self.action_goal.goal.arm_name = str[start:end]
06820       start = end
06821       end += 4
06822       (length,) = _struct_I.unpack(str[start:end])
06823       start = end
06824       end += length
06825       if python3:
06826         self.action_goal.goal.target.reference_frame_id = str[start:end].decode('utf-8')
06827       else:
06828         self.action_goal.goal.target.reference_frame_id = str[start:end]
06829       start = end
06830       end += 4
06831       (length,) = _struct_I.unpack(str[start:end])
06832       self.action_goal.goal.target.potential_models = []
06833       for i in range(0, length):
06834         val1 = household_objects_database_msgs.msg.DatabaseModelPose()
06835         start = end
06836         end += 4
06837         (val1.model_id,) = _struct_i.unpack(str[start:end])
06838         _v496 = val1.pose
06839         _v497 = _v496.header
06840         start = end
06841         end += 4
06842         (_v497.seq,) = _struct_I.unpack(str[start:end])
06843         _v498 = _v497.stamp
06844         _x = _v498
06845         start = end
06846         end += 8
06847         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
06848         start = end
06849         end += 4
06850         (length,) = _struct_I.unpack(str[start:end])
06851         start = end
06852         end += length
06853         if python3:
06854           _v497.frame_id = str[start:end].decode('utf-8')
06855         else:
06856           _v497.frame_id = str[start:end]
06857         _v499 = _v496.pose
06858         _v500 = _v499.position
06859         _x = _v500
06860         start = end
06861         end += 24
06862         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
06863         _v501 = _v499.orientation
06864         _x = _v501
06865         start = end
06866         end += 32
06867         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
06868         start = end
06869         end += 4
06870         (val1.confidence,) = _struct_f.unpack(str[start:end])
06871         start = end
06872         end += 4
06873         (length,) = _struct_I.unpack(str[start:end])
06874         start = end
06875         end += length
06876         if python3:
06877           val1.detector_name = str[start:end].decode('utf-8')
06878         else:
06879           val1.detector_name = str[start:end]
06880         self.action_goal.goal.target.potential_models.append(val1)
06881       _x = self
06882       start = end
06883       end += 12
06884       (_x.action_goal.goal.target.cluster.header.seq, _x.action_goal.goal.target.cluster.header.stamp.secs, _x.action_goal.goal.target.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
06885       start = end
06886       end += 4
06887       (length,) = _struct_I.unpack(str[start:end])
06888       start = end
06889       end += length
06890       if python3:
06891         self.action_goal.goal.target.cluster.header.frame_id = str[start:end].decode('utf-8')
06892       else:
06893         self.action_goal.goal.target.cluster.header.frame_id = str[start:end]
06894       start = end
06895       end += 4
06896       (length,) = _struct_I.unpack(str[start:end])
06897       self.action_goal.goal.target.cluster.points = []
06898       for i in range(0, length):
06899         val1 = geometry_msgs.msg.Point32()
06900         _x = val1
06901         start = end
06902         end += 12
06903         (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
06904         self.action_goal.goal.target.cluster.points.append(val1)
06905       start = end
06906       end += 4
06907       (length,) = _struct_I.unpack(str[start:end])
06908       self.action_goal.goal.target.cluster.channels = []
06909       for i in range(0, length):
06910         val1 = sensor_msgs.msg.ChannelFloat32()
06911         start = end
06912         end += 4
06913         (length,) = _struct_I.unpack(str[start:end])
06914         start = end
06915         end += length
06916         if python3:
06917           val1.name = str[start:end].decode('utf-8')
06918         else:
06919           val1.name = str[start:end]
06920         start = end
06921         end += 4
06922         (length,) = _struct_I.unpack(str[start:end])
06923         pattern = '<%sf'%length
06924         start = end
06925         end += struct.calcsize(pattern)
06926         val1.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
06927         self.action_goal.goal.target.cluster.channels.append(val1)
06928       _x = self
06929       start = end
06930       end += 12
06931       (_x.action_goal.goal.target.region.cloud.header.seq, _x.action_goal.goal.target.region.cloud.header.stamp.secs, _x.action_goal.goal.target.region.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
06932       start = end
06933       end += 4
06934       (length,) = _struct_I.unpack(str[start:end])
06935       start = end
06936       end += length
06937       if python3:
06938         self.action_goal.goal.target.region.cloud.header.frame_id = str[start:end].decode('utf-8')
06939       else:
06940         self.action_goal.goal.target.region.cloud.header.frame_id = str[start:end]
06941       _x = self
06942       start = end
06943       end += 8
06944       (_x.action_goal.goal.target.region.cloud.height, _x.action_goal.goal.target.region.cloud.width,) = _struct_2I.unpack(str[start:end])
06945       start = end
06946       end += 4
06947       (length,) = _struct_I.unpack(str[start:end])
06948       self.action_goal.goal.target.region.cloud.fields = []
06949       for i in range(0, length):
06950         val1 = sensor_msgs.msg.PointField()
06951         start = end
06952         end += 4
06953         (length,) = _struct_I.unpack(str[start:end])
06954         start = end
06955         end += length
06956         if python3:
06957           val1.name = str[start:end].decode('utf-8')
06958         else:
06959           val1.name = str[start:end]
06960         _x = val1
06961         start = end
06962         end += 9
06963         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
06964         self.action_goal.goal.target.region.cloud.fields.append(val1)
06965       _x = self
06966       start = end
06967       end += 9
06968       (_x.action_goal.goal.target.region.cloud.is_bigendian, _x.action_goal.goal.target.region.cloud.point_step, _x.action_goal.goal.target.region.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
06969       self.action_goal.goal.target.region.cloud.is_bigendian = bool(self.action_goal.goal.target.region.cloud.is_bigendian)
06970       start = end
06971       end += 4
06972       (length,) = _struct_I.unpack(str[start:end])
06973       start = end
06974       end += length
06975       if python3:
06976         self.action_goal.goal.target.region.cloud.data = str[start:end].decode('utf-8')
06977       else:
06978         self.action_goal.goal.target.region.cloud.data = str[start:end]
06979       start = end
06980       end += 1
06981       (self.action_goal.goal.target.region.cloud.is_dense,) = _struct_B.unpack(str[start:end])
06982       self.action_goal.goal.target.region.cloud.is_dense = bool(self.action_goal.goal.target.region.cloud.is_dense)
06983       start = end
06984       end += 4
06985       (length,) = _struct_I.unpack(str[start:end])
06986       pattern = '<%si'%length
06987       start = end
06988       end += struct.calcsize(pattern)
06989       self.action_goal.goal.target.region.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
06990       _x = self
06991       start = end
06992       end += 12
06993       (_x.action_goal.goal.target.region.image.header.seq, _x.action_goal.goal.target.region.image.header.stamp.secs, _x.action_goal.goal.target.region.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
06994       start = end
06995       end += 4
06996       (length,) = _struct_I.unpack(str[start:end])
06997       start = end
06998       end += length
06999       if python3:
07000         self.action_goal.goal.target.region.image.header.frame_id = str[start:end].decode('utf-8')
07001       else:
07002         self.action_goal.goal.target.region.image.header.frame_id = str[start:end]
07003       _x = self
07004       start = end
07005       end += 8
07006       (_x.action_goal.goal.target.region.image.height, _x.action_goal.goal.target.region.image.width,) = _struct_2I.unpack(str[start:end])
07007       start = end
07008       end += 4
07009       (length,) = _struct_I.unpack(str[start:end])
07010       start = end
07011       end += length
07012       if python3:
07013         self.action_goal.goal.target.region.image.encoding = str[start:end].decode('utf-8')
07014       else:
07015         self.action_goal.goal.target.region.image.encoding = str[start:end]
07016       _x = self
07017       start = end
07018       end += 5
07019       (_x.action_goal.goal.target.region.image.is_bigendian, _x.action_goal.goal.target.region.image.step,) = _struct_BI.unpack(str[start:end])
07020       start = end
07021       end += 4
07022       (length,) = _struct_I.unpack(str[start:end])
07023       start = end
07024       end += length
07025       if python3:
07026         self.action_goal.goal.target.region.image.data = str[start:end].decode('utf-8')
07027       else:
07028         self.action_goal.goal.target.region.image.data = str[start:end]
07029       _x = self
07030       start = end
07031       end += 12
07032       (_x.action_goal.goal.target.region.disparity_image.header.seq, _x.action_goal.goal.target.region.disparity_image.header.stamp.secs, _x.action_goal.goal.target.region.disparity_image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
07033       start = end
07034       end += 4
07035       (length,) = _struct_I.unpack(str[start:end])
07036       start = end
07037       end += length
07038       if python3:
07039         self.action_goal.goal.target.region.disparity_image.header.frame_id = str[start:end].decode('utf-8')
07040       else:
07041         self.action_goal.goal.target.region.disparity_image.header.frame_id = str[start:end]
07042       _x = self
07043       start = end
07044       end += 8
07045       (_x.action_goal.goal.target.region.disparity_image.height, _x.action_goal.goal.target.region.disparity_image.width,) = _struct_2I.unpack(str[start:end])
07046       start = end
07047       end += 4
07048       (length,) = _struct_I.unpack(str[start:end])
07049       start = end
07050       end += length
07051       if python3:
07052         self.action_goal.goal.target.region.disparity_image.encoding = str[start:end].decode('utf-8')
07053       else:
07054         self.action_goal.goal.target.region.disparity_image.encoding = str[start:end]
07055       _x = self
07056       start = end
07057       end += 5
07058       (_x.action_goal.goal.target.region.disparity_image.is_bigendian, _x.action_goal.goal.target.region.disparity_image.step,) = _struct_BI.unpack(str[start:end])
07059       start = end
07060       end += 4
07061       (length,) = _struct_I.unpack(str[start:end])
07062       start = end
07063       end += length
07064       if python3:
07065         self.action_goal.goal.target.region.disparity_image.data = str[start:end].decode('utf-8')
07066       else:
07067         self.action_goal.goal.target.region.disparity_image.data = str[start:end]
07068       _x = self
07069       start = end
07070       end += 12
07071       (_x.action_goal.goal.target.region.cam_info.header.seq, _x.action_goal.goal.target.region.cam_info.header.stamp.secs, _x.action_goal.goal.target.region.cam_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
07072       start = end
07073       end += 4
07074       (length,) = _struct_I.unpack(str[start:end])
07075       start = end
07076       end += length
07077       if python3:
07078         self.action_goal.goal.target.region.cam_info.header.frame_id = str[start:end].decode('utf-8')
07079       else:
07080         self.action_goal.goal.target.region.cam_info.header.frame_id = str[start:end]
07081       _x = self
07082       start = end
07083       end += 8
07084       (_x.action_goal.goal.target.region.cam_info.height, _x.action_goal.goal.target.region.cam_info.width,) = _struct_2I.unpack(str[start:end])
07085       start = end
07086       end += 4
07087       (length,) = _struct_I.unpack(str[start:end])
07088       start = end
07089       end += length
07090       if python3:
07091         self.action_goal.goal.target.region.cam_info.distortion_model = str[start:end].decode('utf-8')
07092       else:
07093         self.action_goal.goal.target.region.cam_info.distortion_model = str[start:end]
07094       start = end
07095       end += 4
07096       (length,) = _struct_I.unpack(str[start:end])
07097       pattern = '<%sd'%length
07098       start = end
07099       end += struct.calcsize(pattern)
07100       self.action_goal.goal.target.region.cam_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
07101       start = end
07102       end += 72
07103       self.action_goal.goal.target.region.cam_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
07104       start = end
07105       end += 72
07106       self.action_goal.goal.target.region.cam_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
07107       start = end
07108       end += 96
07109       self.action_goal.goal.target.region.cam_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
07110       _x = self
07111       start = end
07112       end += 37
07113       (_x.action_goal.goal.target.region.cam_info.binning_x, _x.action_goal.goal.target.region.cam_info.binning_y, _x.action_goal.goal.target.region.cam_info.roi.x_offset, _x.action_goal.goal.target.region.cam_info.roi.y_offset, _x.action_goal.goal.target.region.cam_info.roi.height, _x.action_goal.goal.target.region.cam_info.roi.width, _x.action_goal.goal.target.region.cam_info.roi.do_rectify, _x.action_goal.goal.target.region.roi_box_pose.header.seq, _x.action_goal.goal.target.region.roi_box_pose.header.stamp.secs, _x.action_goal.goal.target.region.roi_box_pose.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
07114       self.action_goal.goal.target.region.cam_info.roi.do_rectify = bool(self.action_goal.goal.target.region.cam_info.roi.do_rectify)
07115       start = end
07116       end += 4
07117       (length,) = _struct_I.unpack(str[start:end])
07118       start = end
07119       end += length
07120       if python3:
07121         self.action_goal.goal.target.region.roi_box_pose.header.frame_id = str[start:end].decode('utf-8')
07122       else:
07123         self.action_goal.goal.target.region.roi_box_pose.header.frame_id = str[start:end]
07124       _x = self
07125       start = end
07126       end += 80
07127       (_x.action_goal.goal.target.region.roi_box_pose.pose.position.x, _x.action_goal.goal.target.region.roi_box_pose.pose.position.y, _x.action_goal.goal.target.region.roi_box_pose.pose.position.z, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.x, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.y, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.z, _x.action_goal.goal.target.region.roi_box_pose.pose.orientation.w, _x.action_goal.goal.target.region.roi_box_dims.x, _x.action_goal.goal.target.region.roi_box_dims.y, _x.action_goal.goal.target.region.roi_box_dims.z,) = _struct_10d.unpack(str[start:end])
07128       start = end
07129       end += 4
07130       (length,) = _struct_I.unpack(str[start:end])
07131       start = end
07132       end += length
07133       if python3:
07134         self.action_goal.goal.target.collision_name = str[start:end].decode('utf-8')
07135       else:
07136         self.action_goal.goal.target.collision_name = str[start:end]
07137       start = end
07138       end += 4
07139       (length,) = _struct_I.unpack(str[start:end])
07140       self.action_goal.goal.desired_grasps = []
07141       for i in range(0, length):
07142         val1 = object_manipulation_msgs.msg.Grasp()
07143         _v502 = val1.pre_grasp_posture
07144         _v503 = _v502.header
07145         start = end
07146         end += 4
07147         (_v503.seq,) = _struct_I.unpack(str[start:end])
07148         _v504 = _v503.stamp
07149         _x = _v504
07150         start = end
07151         end += 8
07152         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
07153         start = end
07154         end += 4
07155         (length,) = _struct_I.unpack(str[start:end])
07156         start = end
07157         end += length
07158         if python3:
07159           _v503.frame_id = str[start:end].decode('utf-8')
07160         else:
07161           _v503.frame_id = str[start:end]
07162         start = end
07163         end += 4
07164         (length,) = _struct_I.unpack(str[start:end])
07165         _v502.name = []
07166         for i in range(0, length):
07167           start = end
07168           end += 4
07169           (length,) = _struct_I.unpack(str[start:end])
07170           start = end
07171           end += length
07172           if python3:
07173             val3 = str[start:end].decode('utf-8')
07174           else:
07175             val3 = str[start:end]
07176           _v502.name.append(val3)
07177         start = end
07178         end += 4
07179         (length,) = _struct_I.unpack(str[start:end])
07180         pattern = '<%sd'%length
07181         start = end
07182         end += struct.calcsize(pattern)
07183         _v502.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
07184         start = end
07185         end += 4
07186         (length,) = _struct_I.unpack(str[start:end])
07187         pattern = '<%sd'%length
07188         start = end
07189         end += struct.calcsize(pattern)
07190         _v502.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
07191         start = end
07192         end += 4
07193         (length,) = _struct_I.unpack(str[start:end])
07194         pattern = '<%sd'%length
07195         start = end
07196         end += struct.calcsize(pattern)
07197         _v502.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
07198         _v505 = val1.grasp_posture
07199         _v506 = _v505.header
07200         start = end
07201         end += 4
07202         (_v506.seq,) = _struct_I.unpack(str[start:end])
07203         _v507 = _v506.stamp
07204         _x = _v507
07205         start = end
07206         end += 8
07207         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
07208         start = end
07209         end += 4
07210         (length,) = _struct_I.unpack(str[start:end])
07211         start = end
07212         end += length
07213         if python3:
07214           _v506.frame_id = str[start:end].decode('utf-8')
07215         else:
07216           _v506.frame_id = str[start:end]
07217         start = end
07218         end += 4
07219         (length,) = _struct_I.unpack(str[start:end])
07220         _v505.name = []
07221         for i in range(0, length):
07222           start = end
07223           end += 4
07224           (length,) = _struct_I.unpack(str[start:end])
07225           start = end
07226           end += length
07227           if python3:
07228             val3 = str[start:end].decode('utf-8')
07229           else:
07230             val3 = str[start:end]
07231           _v505.name.append(val3)
07232         start = end
07233         end += 4
07234         (length,) = _struct_I.unpack(str[start:end])
07235         pattern = '<%sd'%length
07236         start = end
07237         end += struct.calcsize(pattern)
07238         _v505.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
07239         start = end
07240         end += 4
07241         (length,) = _struct_I.unpack(str[start:end])
07242         pattern = '<%sd'%length
07243         start = end
07244         end += struct.calcsize(pattern)
07245         _v505.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
07246         start = end
07247         end += 4
07248         (length,) = _struct_I.unpack(str[start:end])
07249         pattern = '<%sd'%length
07250         start = end
07251         end += struct.calcsize(pattern)
07252         _v505.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
07253         _v508 = val1.grasp_pose
07254         _v509 = _v508.position
07255         _x = _v509
07256         start = end
07257         end += 24
07258         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
07259         _v510 = _v508.orientation
07260         _x = _v510
07261         start = end
07262         end += 32
07263         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
07264         _x = val1
07265         start = end
07266         end += 17
07267         (_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance,) = _struct_dB2f.unpack(str[start:end])
07268         val1.cluster_rep = bool(val1.cluster_rep)
07269         start = end
07270         end += 4
07271         (length,) = _struct_I.unpack(str[start:end])
07272         val1.moved_obstacles = []
07273         for i in range(0, length):
07274           val2 = object_manipulation_msgs.msg.GraspableObject()
07275           start = end
07276           end += 4
07277           (length,) = _struct_I.unpack(str[start:end])
07278           start = end
07279           end += length
07280           if python3:
07281             val2.reference_frame_id = str[start:end].decode('utf-8')
07282           else:
07283             val2.reference_frame_id = str[start:end]
07284           start = end
07285           end += 4
07286           (length,) = _struct_I.unpack(str[start:end])
07287           val2.potential_models = []
07288           for i in range(0, length):
07289             val3 = household_objects_database_msgs.msg.DatabaseModelPose()
07290             start = end
07291             end += 4
07292             (val3.model_id,) = _struct_i.unpack(str[start:end])
07293             _v511 = val3.pose
07294             _v512 = _v511.header
07295             start = end
07296             end += 4
07297             (_v512.seq,) = _struct_I.unpack(str[start:end])
07298             _v513 = _v512.stamp
07299             _x = _v513
07300             start = end
07301             end += 8
07302             (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
07303             start = end
07304             end += 4
07305             (length,) = _struct_I.unpack(str[start:end])
07306             start = end
07307             end += length
07308             if python3:
07309               _v512.frame_id = str[start:end].decode('utf-8')
07310             else:
07311               _v512.frame_id = str[start:end]
07312             _v514 = _v511.pose
07313             _v515 = _v514.position
07314             _x = _v515
07315             start = end
07316             end += 24
07317             (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
07318             _v516 = _v514.orientation
07319             _x = _v516
07320             start = end
07321             end += 32
07322             (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
07323             start = end
07324             end += 4
07325             (val3.confidence,) = _struct_f.unpack(str[start:end])
07326             start = end
07327             end += 4
07328             (length,) = _struct_I.unpack(str[start:end])
07329             start = end
07330             end += length
07331             if python3:
07332               val3.detector_name = str[start:end].decode('utf-8')
07333             else:
07334               val3.detector_name = str[start:end]
07335             val2.potential_models.append(val3)
07336           _v517 = val2.cluster
07337           _v518 = _v517.header
07338           start = end
07339           end += 4
07340           (_v518.seq,) = _struct_I.unpack(str[start:end])
07341           _v519 = _v518.stamp
07342           _x = _v519
07343           start = end
07344           end += 8
07345           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
07346           start = end
07347           end += 4
07348           (length,) = _struct_I.unpack(str[start:end])
07349           start = end
07350           end += length
07351           if python3:
07352             _v518.frame_id = str[start:end].decode('utf-8')
07353           else:
07354             _v518.frame_id = str[start:end]
07355           start = end
07356           end += 4
07357           (length,) = _struct_I.unpack(str[start:end])
07358           _v517.points = []
07359           for i in range(0, length):
07360             val4 = geometry_msgs.msg.Point32()
07361             _x = val4
07362             start = end
07363             end += 12
07364             (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
07365             _v517.points.append(val4)
07366           start = end
07367           end += 4
07368           (length,) = _struct_I.unpack(str[start:end])
07369           _v517.channels = []
07370           for i in range(0, length):
07371             val4 = sensor_msgs.msg.ChannelFloat32()
07372             start = end
07373             end += 4
07374             (length,) = _struct_I.unpack(str[start:end])
07375             start = end
07376             end += length
07377             if python3:
07378               val4.name = str[start:end].decode('utf-8')
07379             else:
07380               val4.name = str[start:end]
07381             start = end
07382             end += 4
07383             (length,) = _struct_I.unpack(str[start:end])
07384             pattern = '<%sf'%length
07385             start = end
07386             end += struct.calcsize(pattern)
07387             val4.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
07388             _v517.channels.append(val4)
07389           _v520 = val2.region
07390           _v521 = _v520.cloud
07391           _v522 = _v521.header
07392           start = end
07393           end += 4
07394           (_v522.seq,) = _struct_I.unpack(str[start:end])
07395           _v523 = _v522.stamp
07396           _x = _v523
07397           start = end
07398           end += 8
07399           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
07400           start = end
07401           end += 4
07402           (length,) = _struct_I.unpack(str[start:end])
07403           start = end
07404           end += length
07405           if python3:
07406             _v522.frame_id = str[start:end].decode('utf-8')
07407           else:
07408             _v522.frame_id = str[start:end]
07409           _x = _v521
07410           start = end
07411           end += 8
07412           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
07413           start = end
07414           end += 4
07415           (length,) = _struct_I.unpack(str[start:end])
07416           _v521.fields = []
07417           for i in range(0, length):
07418             val5 = sensor_msgs.msg.PointField()
07419             start = end
07420             end += 4
07421             (length,) = _struct_I.unpack(str[start:end])
07422             start = end
07423             end += length
07424             if python3:
07425               val5.name = str[start:end].decode('utf-8')
07426             else:
07427               val5.name = str[start:end]
07428             _x = val5
07429             start = end
07430             end += 9
07431             (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
07432             _v521.fields.append(val5)
07433           _x = _v521
07434           start = end
07435           end += 9
07436           (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
07437           _v521.is_bigendian = bool(_v521.is_bigendian)
07438           start = end
07439           end += 4
07440           (length,) = _struct_I.unpack(str[start:end])
07441           start = end
07442           end += length
07443           if python3:
07444             _v521.data = str[start:end].decode('utf-8')
07445           else:
07446             _v521.data = str[start:end]
07447           start = end
07448           end += 1
07449           (_v521.is_dense,) = _struct_B.unpack(str[start:end])
07450           _v521.is_dense = bool(_v521.is_dense)
07451           start = end
07452           end += 4
07453           (length,) = _struct_I.unpack(str[start:end])
07454           pattern = '<%si'%length
07455           start = end
07456           end += struct.calcsize(pattern)
07457           _v520.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
07458           _v524 = _v520.image
07459           _v525 = _v524.header
07460           start = end
07461           end += 4
07462           (_v525.seq,) = _struct_I.unpack(str[start:end])
07463           _v526 = _v525.stamp
07464           _x = _v526
07465           start = end
07466           end += 8
07467           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
07468           start = end
07469           end += 4
07470           (length,) = _struct_I.unpack(str[start:end])
07471           start = end
07472           end += length
07473           if python3:
07474             _v525.frame_id = str[start:end].decode('utf-8')
07475           else:
07476             _v525.frame_id = str[start:end]
07477           _x = _v524
07478           start = end
07479           end += 8
07480           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
07481           start = end
07482           end += 4
07483           (length,) = _struct_I.unpack(str[start:end])
07484           start = end
07485           end += length
07486           if python3:
07487             _v524.encoding = str[start:end].decode('utf-8')
07488           else:
07489             _v524.encoding = str[start:end]
07490           _x = _v524
07491           start = end
07492           end += 5
07493           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
07494           start = end
07495           end += 4
07496           (length,) = _struct_I.unpack(str[start:end])
07497           start = end
07498           end += length
07499           if python3:
07500             _v524.data = str[start:end].decode('utf-8')
07501           else:
07502             _v524.data = str[start:end]
07503           _v527 = _v520.disparity_image
07504           _v528 = _v527.header
07505           start = end
07506           end += 4
07507           (_v528.seq,) = _struct_I.unpack(str[start:end])
07508           _v529 = _v528.stamp
07509           _x = _v529
07510           start = end
07511           end += 8
07512           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
07513           start = end
07514           end += 4
07515           (length,) = _struct_I.unpack(str[start:end])
07516           start = end
07517           end += length
07518           if python3:
07519             _v528.frame_id = str[start:end].decode('utf-8')
07520           else:
07521             _v528.frame_id = str[start:end]
07522           _x = _v527
07523           start = end
07524           end += 8
07525           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
07526           start = end
07527           end += 4
07528           (length,) = _struct_I.unpack(str[start:end])
07529           start = end
07530           end += length
07531           if python3:
07532             _v527.encoding = str[start:end].decode('utf-8')
07533           else:
07534             _v527.encoding = str[start:end]
07535           _x = _v527
07536           start = end
07537           end += 5
07538           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
07539           start = end
07540           end += 4
07541           (length,) = _struct_I.unpack(str[start:end])
07542           start = end
07543           end += length
07544           if python3:
07545             _v527.data = str[start:end].decode('utf-8')
07546           else:
07547             _v527.data = str[start:end]
07548           _v530 = _v520.cam_info
07549           _v531 = _v530.header
07550           start = end
07551           end += 4
07552           (_v531.seq,) = _struct_I.unpack(str[start:end])
07553           _v532 = _v531.stamp
07554           _x = _v532
07555           start = end
07556           end += 8
07557           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
07558           start = end
07559           end += 4
07560           (length,) = _struct_I.unpack(str[start:end])
07561           start = end
07562           end += length
07563           if python3:
07564             _v531.frame_id = str[start:end].decode('utf-8')
07565           else:
07566             _v531.frame_id = str[start:end]
07567           _x = _v530
07568           start = end
07569           end += 8
07570           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
07571           start = end
07572           end += 4
07573           (length,) = _struct_I.unpack(str[start:end])
07574           start = end
07575           end += length
07576           if python3:
07577             _v530.distortion_model = str[start:end].decode('utf-8')
07578           else:
07579             _v530.distortion_model = str[start:end]
07580           start = end
07581           end += 4
07582           (length,) = _struct_I.unpack(str[start:end])
07583           pattern = '<%sd'%length
07584           start = end
07585           end += struct.calcsize(pattern)
07586           _v530.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
07587           start = end
07588           end += 72
07589           _v530.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
07590           start = end
07591           end += 72
07592           _v530.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
07593           start = end
07594           end += 96
07595           _v530.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
07596           _x = _v530
07597           start = end
07598           end += 8
07599           (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
07600           _v533 = _v530.roi
07601           _x = _v533
07602           start = end
07603           end += 17
07604           (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
07605           _v533.do_rectify = bool(_v533.do_rectify)
07606           _v534 = _v520.roi_box_pose
07607           _v535 = _v534.header
07608           start = end
07609           end += 4
07610           (_v535.seq,) = _struct_I.unpack(str[start:end])
07611           _v536 = _v535.stamp
07612           _x = _v536
07613           start = end
07614           end += 8
07615           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
07616           start = end
07617           end += 4
07618           (length,) = _struct_I.unpack(str[start:end])
07619           start = end
07620           end += length
07621           if python3:
07622             _v535.frame_id = str[start:end].decode('utf-8')
07623           else:
07624             _v535.frame_id = str[start:end]
07625           _v537 = _v534.pose
07626           _v538 = _v537.position
07627           _x = _v538
07628           start = end
07629           end += 24
07630           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
07631           _v539 = _v537.orientation
07632           _x = _v539
07633           start = end
07634           end += 32
07635           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
07636           _v540 = _v520.roi_box_dims
07637           _x = _v540
07638           start = end
07639           end += 24
07640           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
07641           start = end
07642           end += 4
07643           (length,) = _struct_I.unpack(str[start:end])
07644           start = end
07645           end += length
07646           if python3:
07647             val2.collision_name = str[start:end].decode('utf-8')
07648           else:
07649             val2.collision_name = str[start:end]
07650           val1.moved_obstacles.append(val2)
07651         self.action_goal.goal.desired_grasps.append(val1)
07652       _x = self
07653       start = end
07654       end += 12
07655       (_x.action_goal.goal.lift.direction.header.seq, _x.action_goal.goal.lift.direction.header.stamp.secs, _x.action_goal.goal.lift.direction.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
07656       start = end
07657       end += 4
07658       (length,) = _struct_I.unpack(str[start:end])
07659       start = end
07660       end += length
07661       if python3:
07662         self.action_goal.goal.lift.direction.header.frame_id = str[start:end].decode('utf-8')
07663       else:
07664         self.action_goal.goal.lift.direction.header.frame_id = str[start:end]
07665       _x = self
07666       start = end
07667       end += 32
07668       (_x.action_goal.goal.lift.direction.vector.x, _x.action_goal.goal.lift.direction.vector.y, _x.action_goal.goal.lift.direction.vector.z, _x.action_goal.goal.lift.desired_distance, _x.action_goal.goal.lift.min_distance,) = _struct_3d2f.unpack(str[start:end])
07669       start = end
07670       end += 4
07671       (length,) = _struct_I.unpack(str[start:end])
07672       start = end
07673       end += length
07674       if python3:
07675         self.action_goal.goal.collision_object_name = str[start:end].decode('utf-8')
07676       else:
07677         self.action_goal.goal.collision_object_name = str[start:end]
07678       start = end
07679       end += 4
07680       (length,) = _struct_I.unpack(str[start:end])
07681       start = end
07682       end += length
07683       if python3:
07684         self.action_goal.goal.collision_support_surface_name = str[start:end].decode('utf-8')
07685       else:
07686         self.action_goal.goal.collision_support_surface_name = str[start:end]
07687       _x = self
07688       start = end
07689       end += 5
07690       (_x.action_goal.goal.allow_gripper_support_collision, _x.action_goal.goal.use_reactive_execution, _x.action_goal.goal.use_reactive_lift, _x.action_goal.goal.only_perform_feasibility_test, _x.action_goal.goal.ignore_collisions,) = _struct_5B.unpack(str[start:end])
07691       self.action_goal.goal.allow_gripper_support_collision = bool(self.action_goal.goal.allow_gripper_support_collision)
07692       self.action_goal.goal.use_reactive_execution = bool(self.action_goal.goal.use_reactive_execution)
07693       self.action_goal.goal.use_reactive_lift = bool(self.action_goal.goal.use_reactive_lift)
07694       self.action_goal.goal.only_perform_feasibility_test = bool(self.action_goal.goal.only_perform_feasibility_test)
07695       self.action_goal.goal.ignore_collisions = bool(self.action_goal.goal.ignore_collisions)
07696       start = end
07697       end += 4
07698       (length,) = _struct_I.unpack(str[start:end])
07699       self.action_goal.goal.path_constraints.joint_constraints = []
07700       for i in range(0, length):
07701         val1 = arm_navigation_msgs.msg.JointConstraint()
07702         start = end
07703         end += 4
07704         (length,) = _struct_I.unpack(str[start:end])
07705         start = end
07706         end += length
07707         if python3:
07708           val1.joint_name = str[start:end].decode('utf-8')
07709         else:
07710           val1.joint_name = str[start:end]
07711         _x = val1
07712         start = end
07713         end += 32
07714         (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
07715         self.action_goal.goal.path_constraints.joint_constraints.append(val1)
07716       start = end
07717       end += 4
07718       (length,) = _struct_I.unpack(str[start:end])
07719       self.action_goal.goal.path_constraints.position_constraints = []
07720       for i in range(0, length):
07721         val1 = arm_navigation_msgs.msg.PositionConstraint()
07722         _v541 = val1.header
07723         start = end
07724         end += 4
07725         (_v541.seq,) = _struct_I.unpack(str[start:end])
07726         _v542 = _v541.stamp
07727         _x = _v542
07728         start = end
07729         end += 8
07730         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
07731         start = end
07732         end += 4
07733         (length,) = _struct_I.unpack(str[start:end])
07734         start = end
07735         end += length
07736         if python3:
07737           _v541.frame_id = str[start:end].decode('utf-8')
07738         else:
07739           _v541.frame_id = str[start:end]
07740         start = end
07741         end += 4
07742         (length,) = _struct_I.unpack(str[start:end])
07743         start = end
07744         end += length
07745         if python3:
07746           val1.link_name = str[start:end].decode('utf-8')
07747         else:
07748           val1.link_name = str[start:end]
07749         _v543 = val1.target_point_offset
07750         _x = _v543
07751         start = end
07752         end += 24
07753         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
07754         _v544 = val1.position
07755         _x = _v544
07756         start = end
07757         end += 24
07758         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
07759         _v545 = val1.constraint_region_shape
07760         start = end
07761         end += 1
07762         (_v545.type,) = _struct_b.unpack(str[start:end])
07763         start = end
07764         end += 4
07765         (length,) = _struct_I.unpack(str[start:end])
07766         pattern = '<%sd'%length
07767         start = end
07768         end += struct.calcsize(pattern)
07769         _v545.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
07770         start = end
07771         end += 4
07772         (length,) = _struct_I.unpack(str[start:end])
07773         pattern = '<%si'%length
07774         start = end
07775         end += struct.calcsize(pattern)
07776         _v545.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
07777         start = end
07778         end += 4
07779         (length,) = _struct_I.unpack(str[start:end])
07780         _v545.vertices = []
07781         for i in range(0, length):
07782           val3 = geometry_msgs.msg.Point()
07783           _x = val3
07784           start = end
07785           end += 24
07786           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
07787           _v545.vertices.append(val3)
07788         _v546 = val1.constraint_region_orientation
07789         _x = _v546
07790         start = end
07791         end += 32
07792         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
07793         start = end
07794         end += 8
07795         (val1.weight,) = _struct_d.unpack(str[start:end])
07796         self.action_goal.goal.path_constraints.position_constraints.append(val1)
07797       start = end
07798       end += 4
07799       (length,) = _struct_I.unpack(str[start:end])
07800       self.action_goal.goal.path_constraints.orientation_constraints = []
07801       for i in range(0, length):
07802         val1 = arm_navigation_msgs.msg.OrientationConstraint()
07803         _v547 = val1.header
07804         start = end
07805         end += 4
07806         (_v547.seq,) = _struct_I.unpack(str[start:end])
07807         _v548 = _v547.stamp
07808         _x = _v548
07809         start = end
07810         end += 8
07811         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
07812         start = end
07813         end += 4
07814         (length,) = _struct_I.unpack(str[start:end])
07815         start = end
07816         end += length
07817         if python3:
07818           _v547.frame_id = str[start:end].decode('utf-8')
07819         else:
07820           _v547.frame_id = str[start:end]
07821         start = end
07822         end += 4
07823         (length,) = _struct_I.unpack(str[start:end])
07824         start = end
07825         end += length
07826         if python3:
07827           val1.link_name = str[start:end].decode('utf-8')
07828         else:
07829           val1.link_name = str[start:end]
07830         start = end
07831         end += 4
07832         (val1.type,) = _struct_i.unpack(str[start:end])
07833         _v549 = val1.orientation
07834         _x = _v549
07835         start = end
07836         end += 32
07837         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
07838         _x = val1
07839         start = end
07840         end += 32
07841         (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
07842         self.action_goal.goal.path_constraints.orientation_constraints.append(val1)
07843       start = end
07844       end += 4
07845       (length,) = _struct_I.unpack(str[start:end])
07846       self.action_goal.goal.path_constraints.visibility_constraints = []
07847       for i in range(0, length):
07848         val1 = arm_navigation_msgs.msg.VisibilityConstraint()
07849         _v550 = val1.header
07850         start = end
07851         end += 4
07852         (_v550.seq,) = _struct_I.unpack(str[start:end])
07853         _v551 = _v550.stamp
07854         _x = _v551
07855         start = end
07856         end += 8
07857         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
07858         start = end
07859         end += 4
07860         (length,) = _struct_I.unpack(str[start:end])
07861         start = end
07862         end += length
07863         if python3:
07864           _v550.frame_id = str[start:end].decode('utf-8')
07865         else:
07866           _v550.frame_id = str[start:end]
07867         _v552 = val1.target
07868         _v553 = _v552.header
07869         start = end
07870         end += 4
07871         (_v553.seq,) = _struct_I.unpack(str[start:end])
07872         _v554 = _v553.stamp
07873         _x = _v554
07874         start = end
07875         end += 8
07876         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
07877         start = end
07878         end += 4
07879         (length,) = _struct_I.unpack(str[start:end])
07880         start = end
07881         end += length
07882         if python3:
07883           _v553.frame_id = str[start:end].decode('utf-8')
07884         else:
07885           _v553.frame_id = str[start:end]
07886         _v555 = _v552.point
07887         _x = _v555
07888         start = end
07889         end += 24
07890         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
07891         _v556 = val1.sensor_pose
07892         _v557 = _v556.header
07893         start = end
07894         end += 4
07895         (_v557.seq,) = _struct_I.unpack(str[start:end])
07896         _v558 = _v557.stamp
07897         _x = _v558
07898         start = end
07899         end += 8
07900         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
07901         start = end
07902         end += 4
07903         (length,) = _struct_I.unpack(str[start:end])
07904         start = end
07905         end += length
07906         if python3:
07907           _v557.frame_id = str[start:end].decode('utf-8')
07908         else:
07909           _v557.frame_id = str[start:end]
07910         _v559 = _v556.pose
07911         _v560 = _v559.position
07912         _x = _v560
07913         start = end
07914         end += 24
07915         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
07916         _v561 = _v559.orientation
07917         _x = _v561
07918         start = end
07919         end += 32
07920         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
07921         start = end
07922         end += 8
07923         (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
07924         self.action_goal.goal.path_constraints.visibility_constraints.append(val1)
07925       start = end
07926       end += 4
07927       (length,) = _struct_I.unpack(str[start:end])
07928       self.action_goal.goal.additional_collision_operations.collision_operations = []
07929       for i in range(0, length):
07930         val1 = arm_navigation_msgs.msg.CollisionOperation()
07931         start = end
07932         end += 4
07933         (length,) = _struct_I.unpack(str[start:end])
07934         start = end
07935         end += length
07936         if python3:
07937           val1.object1 = str[start:end].decode('utf-8')
07938         else:
07939           val1.object1 = str[start:end]
07940         start = end
07941         end += 4
07942         (length,) = _struct_I.unpack(str[start:end])
07943         start = end
07944         end += length
07945         if python3:
07946           val1.object2 = str[start:end].decode('utf-8')
07947         else:
07948           val1.object2 = str[start:end]
07949         _x = val1
07950         start = end
07951         end += 12
07952         (_x.penetration_distance, _x.operation,) = _struct_di.unpack(str[start:end])
07953         self.action_goal.goal.additional_collision_operations.collision_operations.append(val1)
07954       start = end
07955       end += 4
07956       (length,) = _struct_I.unpack(str[start:end])
07957       self.action_goal.goal.additional_link_padding = []
07958       for i in range(0, length):
07959         val1 = arm_navigation_msgs.msg.LinkPadding()
07960         start = end
07961         end += 4
07962         (length,) = _struct_I.unpack(str[start:end])
07963         start = end
07964         end += length
07965         if python3:
07966           val1.link_name = str[start:end].decode('utf-8')
07967         else:
07968           val1.link_name = str[start:end]
07969         start = end
07970         end += 8
07971         (val1.padding,) = _struct_d.unpack(str[start:end])
07972         self.action_goal.goal.additional_link_padding.append(val1)
07973       start = end
07974       end += 4
07975       (length,) = _struct_I.unpack(str[start:end])
07976       self.action_goal.goal.movable_obstacles = []
07977       for i in range(0, length):
07978         val1 = object_manipulation_msgs.msg.GraspableObject()
07979         start = end
07980         end += 4
07981         (length,) = _struct_I.unpack(str[start:end])
07982         start = end
07983         end += length
07984         if python3:
07985           val1.reference_frame_id = str[start:end].decode('utf-8')
07986         else:
07987           val1.reference_frame_id = str[start:end]
07988         start = end
07989         end += 4
07990         (length,) = _struct_I.unpack(str[start:end])
07991         val1.potential_models = []
07992         for i in range(0, length):
07993           val2 = household_objects_database_msgs.msg.DatabaseModelPose()
07994           start = end
07995           end += 4
07996           (val2.model_id,) = _struct_i.unpack(str[start:end])
07997           _v562 = val2.pose
07998           _v563 = _v562.header
07999           start = end
08000           end += 4
08001           (_v563.seq,) = _struct_I.unpack(str[start:end])
08002           _v564 = _v563.stamp
08003           _x = _v564
08004           start = end
08005           end += 8
08006           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08007           start = end
08008           end += 4
08009           (length,) = _struct_I.unpack(str[start:end])
08010           start = end
08011           end += length
08012           if python3:
08013             _v563.frame_id = str[start:end].decode('utf-8')
08014           else:
08015             _v563.frame_id = str[start:end]
08016           _v565 = _v562.pose
08017           _v566 = _v565.position
08018           _x = _v566
08019           start = end
08020           end += 24
08021           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
08022           _v567 = _v565.orientation
08023           _x = _v567
08024           start = end
08025           end += 32
08026           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
08027           start = end
08028           end += 4
08029           (val2.confidence,) = _struct_f.unpack(str[start:end])
08030           start = end
08031           end += 4
08032           (length,) = _struct_I.unpack(str[start:end])
08033           start = end
08034           end += length
08035           if python3:
08036             val2.detector_name = str[start:end].decode('utf-8')
08037           else:
08038             val2.detector_name = str[start:end]
08039           val1.potential_models.append(val2)
08040         _v568 = val1.cluster
08041         _v569 = _v568.header
08042         start = end
08043         end += 4
08044         (_v569.seq,) = _struct_I.unpack(str[start:end])
08045         _v570 = _v569.stamp
08046         _x = _v570
08047         start = end
08048         end += 8
08049         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08050         start = end
08051         end += 4
08052         (length,) = _struct_I.unpack(str[start:end])
08053         start = end
08054         end += length
08055         if python3:
08056           _v569.frame_id = str[start:end].decode('utf-8')
08057         else:
08058           _v569.frame_id = str[start:end]
08059         start = end
08060         end += 4
08061         (length,) = _struct_I.unpack(str[start:end])
08062         _v568.points = []
08063         for i in range(0, length):
08064           val3 = geometry_msgs.msg.Point32()
08065           _x = val3
08066           start = end
08067           end += 12
08068           (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
08069           _v568.points.append(val3)
08070         start = end
08071         end += 4
08072         (length,) = _struct_I.unpack(str[start:end])
08073         _v568.channels = []
08074         for i in range(0, length):
08075           val3 = sensor_msgs.msg.ChannelFloat32()
08076           start = end
08077           end += 4
08078           (length,) = _struct_I.unpack(str[start:end])
08079           start = end
08080           end += length
08081           if python3:
08082             val3.name = str[start:end].decode('utf-8')
08083           else:
08084             val3.name = str[start:end]
08085           start = end
08086           end += 4
08087           (length,) = _struct_I.unpack(str[start:end])
08088           pattern = '<%sf'%length
08089           start = end
08090           end += struct.calcsize(pattern)
08091           val3.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
08092           _v568.channels.append(val3)
08093         _v571 = val1.region
08094         _v572 = _v571.cloud
08095         _v573 = _v572.header
08096         start = end
08097         end += 4
08098         (_v573.seq,) = _struct_I.unpack(str[start:end])
08099         _v574 = _v573.stamp
08100         _x = _v574
08101         start = end
08102         end += 8
08103         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08104         start = end
08105         end += 4
08106         (length,) = _struct_I.unpack(str[start:end])
08107         start = end
08108         end += length
08109         if python3:
08110           _v573.frame_id = str[start:end].decode('utf-8')
08111         else:
08112           _v573.frame_id = str[start:end]
08113         _x = _v572
08114         start = end
08115         end += 8
08116         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
08117         start = end
08118         end += 4
08119         (length,) = _struct_I.unpack(str[start:end])
08120         _v572.fields = []
08121         for i in range(0, length):
08122           val4 = sensor_msgs.msg.PointField()
08123           start = end
08124           end += 4
08125           (length,) = _struct_I.unpack(str[start:end])
08126           start = end
08127           end += length
08128           if python3:
08129             val4.name = str[start:end].decode('utf-8')
08130           else:
08131             val4.name = str[start:end]
08132           _x = val4
08133           start = end
08134           end += 9
08135           (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
08136           _v572.fields.append(val4)
08137         _x = _v572
08138         start = end
08139         end += 9
08140         (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
08141         _v572.is_bigendian = bool(_v572.is_bigendian)
08142         start = end
08143         end += 4
08144         (length,) = _struct_I.unpack(str[start:end])
08145         start = end
08146         end += length
08147         if python3:
08148           _v572.data = str[start:end].decode('utf-8')
08149         else:
08150           _v572.data = str[start:end]
08151         start = end
08152         end += 1
08153         (_v572.is_dense,) = _struct_B.unpack(str[start:end])
08154         _v572.is_dense = bool(_v572.is_dense)
08155         start = end
08156         end += 4
08157         (length,) = _struct_I.unpack(str[start:end])
08158         pattern = '<%si'%length
08159         start = end
08160         end += struct.calcsize(pattern)
08161         _v571.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
08162         _v575 = _v571.image
08163         _v576 = _v575.header
08164         start = end
08165         end += 4
08166         (_v576.seq,) = _struct_I.unpack(str[start:end])
08167         _v577 = _v576.stamp
08168         _x = _v577
08169         start = end
08170         end += 8
08171         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08172         start = end
08173         end += 4
08174         (length,) = _struct_I.unpack(str[start:end])
08175         start = end
08176         end += length
08177         if python3:
08178           _v576.frame_id = str[start:end].decode('utf-8')
08179         else:
08180           _v576.frame_id = str[start:end]
08181         _x = _v575
08182         start = end
08183         end += 8
08184         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
08185         start = end
08186         end += 4
08187         (length,) = _struct_I.unpack(str[start:end])
08188         start = end
08189         end += length
08190         if python3:
08191           _v575.encoding = str[start:end].decode('utf-8')
08192         else:
08193           _v575.encoding = str[start:end]
08194         _x = _v575
08195         start = end
08196         end += 5
08197         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
08198         start = end
08199         end += 4
08200         (length,) = _struct_I.unpack(str[start:end])
08201         start = end
08202         end += length
08203         if python3:
08204           _v575.data = str[start:end].decode('utf-8')
08205         else:
08206           _v575.data = str[start:end]
08207         _v578 = _v571.disparity_image
08208         _v579 = _v578.header
08209         start = end
08210         end += 4
08211         (_v579.seq,) = _struct_I.unpack(str[start:end])
08212         _v580 = _v579.stamp
08213         _x = _v580
08214         start = end
08215         end += 8
08216         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08217         start = end
08218         end += 4
08219         (length,) = _struct_I.unpack(str[start:end])
08220         start = end
08221         end += length
08222         if python3:
08223           _v579.frame_id = str[start:end].decode('utf-8')
08224         else:
08225           _v579.frame_id = str[start:end]
08226         _x = _v578
08227         start = end
08228         end += 8
08229         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
08230         start = end
08231         end += 4
08232         (length,) = _struct_I.unpack(str[start:end])
08233         start = end
08234         end += length
08235         if python3:
08236           _v578.encoding = str[start:end].decode('utf-8')
08237         else:
08238           _v578.encoding = str[start:end]
08239         _x = _v578
08240         start = end
08241         end += 5
08242         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
08243         start = end
08244         end += 4
08245         (length,) = _struct_I.unpack(str[start:end])
08246         start = end
08247         end += length
08248         if python3:
08249           _v578.data = str[start:end].decode('utf-8')
08250         else:
08251           _v578.data = str[start:end]
08252         _v581 = _v571.cam_info
08253         _v582 = _v581.header
08254         start = end
08255         end += 4
08256         (_v582.seq,) = _struct_I.unpack(str[start:end])
08257         _v583 = _v582.stamp
08258         _x = _v583
08259         start = end
08260         end += 8
08261         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08262         start = end
08263         end += 4
08264         (length,) = _struct_I.unpack(str[start:end])
08265         start = end
08266         end += length
08267         if python3:
08268           _v582.frame_id = str[start:end].decode('utf-8')
08269         else:
08270           _v582.frame_id = str[start:end]
08271         _x = _v581
08272         start = end
08273         end += 8
08274         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
08275         start = end
08276         end += 4
08277         (length,) = _struct_I.unpack(str[start:end])
08278         start = end
08279         end += length
08280         if python3:
08281           _v581.distortion_model = str[start:end].decode('utf-8')
08282         else:
08283           _v581.distortion_model = str[start:end]
08284         start = end
08285         end += 4
08286         (length,) = _struct_I.unpack(str[start:end])
08287         pattern = '<%sd'%length
08288         start = end
08289         end += struct.calcsize(pattern)
08290         _v581.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
08291         start = end
08292         end += 72
08293         _v581.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
08294         start = end
08295         end += 72
08296         _v581.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
08297         start = end
08298         end += 96
08299         _v581.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
08300         _x = _v581
08301         start = end
08302         end += 8
08303         (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
08304         _v584 = _v581.roi
08305         _x = _v584
08306         start = end
08307         end += 17
08308         (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
08309         _v584.do_rectify = bool(_v584.do_rectify)
08310         _v585 = _v571.roi_box_pose
08311         _v586 = _v585.header
08312         start = end
08313         end += 4
08314         (_v586.seq,) = _struct_I.unpack(str[start:end])
08315         _v587 = _v586.stamp
08316         _x = _v587
08317         start = end
08318         end += 8
08319         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08320         start = end
08321         end += 4
08322         (length,) = _struct_I.unpack(str[start:end])
08323         start = end
08324         end += length
08325         if python3:
08326           _v586.frame_id = str[start:end].decode('utf-8')
08327         else:
08328           _v586.frame_id = str[start:end]
08329         _v588 = _v585.pose
08330         _v589 = _v588.position
08331         _x = _v589
08332         start = end
08333         end += 24
08334         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
08335         _v590 = _v588.orientation
08336         _x = _v590
08337         start = end
08338         end += 32
08339         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
08340         _v591 = _v571.roi_box_dims
08341         _x = _v591
08342         start = end
08343         end += 24
08344         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
08345         start = end
08346         end += 4
08347         (length,) = _struct_I.unpack(str[start:end])
08348         start = end
08349         end += length
08350         if python3:
08351           val1.collision_name = str[start:end].decode('utf-8')
08352         else:
08353           val1.collision_name = str[start:end]
08354         self.action_goal.goal.movable_obstacles.append(val1)
08355       _x = self
08356       start = end
08357       end += 16
08358       (_x.action_goal.goal.max_contact_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_f3I.unpack(str[start:end])
08359       start = end
08360       end += 4
08361       (length,) = _struct_I.unpack(str[start:end])
08362       start = end
08363       end += length
08364       if python3:
08365         self.action_result.header.frame_id = str[start:end].decode('utf-8')
08366       else:
08367         self.action_result.header.frame_id = str[start:end]
08368       _x = self
08369       start = end
08370       end += 8
08371       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
08372       start = end
08373       end += 4
08374       (length,) = _struct_I.unpack(str[start:end])
08375       start = end
08376       end += length
08377       if python3:
08378         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
08379       else:
08380         self.action_result.status.goal_id.id = str[start:end]
08381       start = end
08382       end += 1
08383       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
08384       start = end
08385       end += 4
08386       (length,) = _struct_I.unpack(str[start:end])
08387       start = end
08388       end += length
08389       if python3:
08390         self.action_result.status.text = str[start:end].decode('utf-8')
08391       else:
08392         self.action_result.status.text = str[start:end]
08393       _x = self
08394       start = end
08395       end += 16
08396       (_x.action_result.result.manipulation_result.value, _x.action_result.result.grasp.pre_grasp_posture.header.seq, _x.action_result.result.grasp.pre_grasp_posture.header.stamp.secs, _x.action_result.result.grasp.pre_grasp_posture.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
08397       start = end
08398       end += 4
08399       (length,) = _struct_I.unpack(str[start:end])
08400       start = end
08401       end += length
08402       if python3:
08403         self.action_result.result.grasp.pre_grasp_posture.header.frame_id = str[start:end].decode('utf-8')
08404       else:
08405         self.action_result.result.grasp.pre_grasp_posture.header.frame_id = str[start:end]
08406       start = end
08407       end += 4
08408       (length,) = _struct_I.unpack(str[start:end])
08409       self.action_result.result.grasp.pre_grasp_posture.name = []
08410       for i in range(0, length):
08411         start = end
08412         end += 4
08413         (length,) = _struct_I.unpack(str[start:end])
08414         start = end
08415         end += length
08416         if python3:
08417           val1 = str[start:end].decode('utf-8')
08418         else:
08419           val1 = str[start:end]
08420         self.action_result.result.grasp.pre_grasp_posture.name.append(val1)
08421       start = end
08422       end += 4
08423       (length,) = _struct_I.unpack(str[start:end])
08424       pattern = '<%sd'%length
08425       start = end
08426       end += struct.calcsize(pattern)
08427       self.action_result.result.grasp.pre_grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
08428       start = end
08429       end += 4
08430       (length,) = _struct_I.unpack(str[start:end])
08431       pattern = '<%sd'%length
08432       start = end
08433       end += struct.calcsize(pattern)
08434       self.action_result.result.grasp.pre_grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
08435       start = end
08436       end += 4
08437       (length,) = _struct_I.unpack(str[start:end])
08438       pattern = '<%sd'%length
08439       start = end
08440       end += struct.calcsize(pattern)
08441       self.action_result.result.grasp.pre_grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
08442       _x = self
08443       start = end
08444       end += 12
08445       (_x.action_result.result.grasp.grasp_posture.header.seq, _x.action_result.result.grasp.grasp_posture.header.stamp.secs, _x.action_result.result.grasp.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
08446       start = end
08447       end += 4
08448       (length,) = _struct_I.unpack(str[start:end])
08449       start = end
08450       end += length
08451       if python3:
08452         self.action_result.result.grasp.grasp_posture.header.frame_id = str[start:end].decode('utf-8')
08453       else:
08454         self.action_result.result.grasp.grasp_posture.header.frame_id = str[start:end]
08455       start = end
08456       end += 4
08457       (length,) = _struct_I.unpack(str[start:end])
08458       self.action_result.result.grasp.grasp_posture.name = []
08459       for i in range(0, length):
08460         start = end
08461         end += 4
08462         (length,) = _struct_I.unpack(str[start:end])
08463         start = end
08464         end += length
08465         if python3:
08466           val1 = str[start:end].decode('utf-8')
08467         else:
08468           val1 = str[start:end]
08469         self.action_result.result.grasp.grasp_posture.name.append(val1)
08470       start = end
08471       end += 4
08472       (length,) = _struct_I.unpack(str[start:end])
08473       pattern = '<%sd'%length
08474       start = end
08475       end += struct.calcsize(pattern)
08476       self.action_result.result.grasp.grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
08477       start = end
08478       end += 4
08479       (length,) = _struct_I.unpack(str[start:end])
08480       pattern = '<%sd'%length
08481       start = end
08482       end += struct.calcsize(pattern)
08483       self.action_result.result.grasp.grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
08484       start = end
08485       end += 4
08486       (length,) = _struct_I.unpack(str[start:end])
08487       pattern = '<%sd'%length
08488       start = end
08489       end += struct.calcsize(pattern)
08490       self.action_result.result.grasp.grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
08491       _x = self
08492       start = end
08493       end += 73
08494       (_x.action_result.result.grasp.grasp_pose.position.x, _x.action_result.result.grasp.grasp_pose.position.y, _x.action_result.result.grasp.grasp_pose.position.z, _x.action_result.result.grasp.grasp_pose.orientation.x, _x.action_result.result.grasp.grasp_pose.orientation.y, _x.action_result.result.grasp.grasp_pose.orientation.z, _x.action_result.result.grasp.grasp_pose.orientation.w, _x.action_result.result.grasp.success_probability, _x.action_result.result.grasp.cluster_rep, _x.action_result.result.grasp.desired_approach_distance, _x.action_result.result.grasp.min_approach_distance,) = _struct_8dB2f.unpack(str[start:end])
08495       self.action_result.result.grasp.cluster_rep = bool(self.action_result.result.grasp.cluster_rep)
08496       start = end
08497       end += 4
08498       (length,) = _struct_I.unpack(str[start:end])
08499       self.action_result.result.grasp.moved_obstacles = []
08500       for i in range(0, length):
08501         val1 = object_manipulation_msgs.msg.GraspableObject()
08502         start = end
08503         end += 4
08504         (length,) = _struct_I.unpack(str[start:end])
08505         start = end
08506         end += length
08507         if python3:
08508           val1.reference_frame_id = str[start:end].decode('utf-8')
08509         else:
08510           val1.reference_frame_id = str[start:end]
08511         start = end
08512         end += 4
08513         (length,) = _struct_I.unpack(str[start:end])
08514         val1.potential_models = []
08515         for i in range(0, length):
08516           val2 = household_objects_database_msgs.msg.DatabaseModelPose()
08517           start = end
08518           end += 4
08519           (val2.model_id,) = _struct_i.unpack(str[start:end])
08520           _v592 = val2.pose
08521           _v593 = _v592.header
08522           start = end
08523           end += 4
08524           (_v593.seq,) = _struct_I.unpack(str[start:end])
08525           _v594 = _v593.stamp
08526           _x = _v594
08527           start = end
08528           end += 8
08529           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08530           start = end
08531           end += 4
08532           (length,) = _struct_I.unpack(str[start:end])
08533           start = end
08534           end += length
08535           if python3:
08536             _v593.frame_id = str[start:end].decode('utf-8')
08537           else:
08538             _v593.frame_id = str[start:end]
08539           _v595 = _v592.pose
08540           _v596 = _v595.position
08541           _x = _v596
08542           start = end
08543           end += 24
08544           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
08545           _v597 = _v595.orientation
08546           _x = _v597
08547           start = end
08548           end += 32
08549           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
08550           start = end
08551           end += 4
08552           (val2.confidence,) = _struct_f.unpack(str[start:end])
08553           start = end
08554           end += 4
08555           (length,) = _struct_I.unpack(str[start:end])
08556           start = end
08557           end += length
08558           if python3:
08559             val2.detector_name = str[start:end].decode('utf-8')
08560           else:
08561             val2.detector_name = str[start:end]
08562           val1.potential_models.append(val2)
08563         _v598 = val1.cluster
08564         _v599 = _v598.header
08565         start = end
08566         end += 4
08567         (_v599.seq,) = _struct_I.unpack(str[start:end])
08568         _v600 = _v599.stamp
08569         _x = _v600
08570         start = end
08571         end += 8
08572         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08573         start = end
08574         end += 4
08575         (length,) = _struct_I.unpack(str[start:end])
08576         start = end
08577         end += length
08578         if python3:
08579           _v599.frame_id = str[start:end].decode('utf-8')
08580         else:
08581           _v599.frame_id = str[start:end]
08582         start = end
08583         end += 4
08584         (length,) = _struct_I.unpack(str[start:end])
08585         _v598.points = []
08586         for i in range(0, length):
08587           val3 = geometry_msgs.msg.Point32()
08588           _x = val3
08589           start = end
08590           end += 12
08591           (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
08592           _v598.points.append(val3)
08593         start = end
08594         end += 4
08595         (length,) = _struct_I.unpack(str[start:end])
08596         _v598.channels = []
08597         for i in range(0, length):
08598           val3 = sensor_msgs.msg.ChannelFloat32()
08599           start = end
08600           end += 4
08601           (length,) = _struct_I.unpack(str[start:end])
08602           start = end
08603           end += length
08604           if python3:
08605             val3.name = str[start:end].decode('utf-8')
08606           else:
08607             val3.name = str[start:end]
08608           start = end
08609           end += 4
08610           (length,) = _struct_I.unpack(str[start:end])
08611           pattern = '<%sf'%length
08612           start = end
08613           end += struct.calcsize(pattern)
08614           val3.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
08615           _v598.channels.append(val3)
08616         _v601 = val1.region
08617         _v602 = _v601.cloud
08618         _v603 = _v602.header
08619         start = end
08620         end += 4
08621         (_v603.seq,) = _struct_I.unpack(str[start:end])
08622         _v604 = _v603.stamp
08623         _x = _v604
08624         start = end
08625         end += 8
08626         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08627         start = end
08628         end += 4
08629         (length,) = _struct_I.unpack(str[start:end])
08630         start = end
08631         end += length
08632         if python3:
08633           _v603.frame_id = str[start:end].decode('utf-8')
08634         else:
08635           _v603.frame_id = str[start:end]
08636         _x = _v602
08637         start = end
08638         end += 8
08639         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
08640         start = end
08641         end += 4
08642         (length,) = _struct_I.unpack(str[start:end])
08643         _v602.fields = []
08644         for i in range(0, length):
08645           val4 = sensor_msgs.msg.PointField()
08646           start = end
08647           end += 4
08648           (length,) = _struct_I.unpack(str[start:end])
08649           start = end
08650           end += length
08651           if python3:
08652             val4.name = str[start:end].decode('utf-8')
08653           else:
08654             val4.name = str[start:end]
08655           _x = val4
08656           start = end
08657           end += 9
08658           (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
08659           _v602.fields.append(val4)
08660         _x = _v602
08661         start = end
08662         end += 9
08663         (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
08664         _v602.is_bigendian = bool(_v602.is_bigendian)
08665         start = end
08666         end += 4
08667         (length,) = _struct_I.unpack(str[start:end])
08668         start = end
08669         end += length
08670         if python3:
08671           _v602.data = str[start:end].decode('utf-8')
08672         else:
08673           _v602.data = str[start:end]
08674         start = end
08675         end += 1
08676         (_v602.is_dense,) = _struct_B.unpack(str[start:end])
08677         _v602.is_dense = bool(_v602.is_dense)
08678         start = end
08679         end += 4
08680         (length,) = _struct_I.unpack(str[start:end])
08681         pattern = '<%si'%length
08682         start = end
08683         end += struct.calcsize(pattern)
08684         _v601.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
08685         _v605 = _v601.image
08686         _v606 = _v605.header
08687         start = end
08688         end += 4
08689         (_v606.seq,) = _struct_I.unpack(str[start:end])
08690         _v607 = _v606.stamp
08691         _x = _v607
08692         start = end
08693         end += 8
08694         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08695         start = end
08696         end += 4
08697         (length,) = _struct_I.unpack(str[start:end])
08698         start = end
08699         end += length
08700         if python3:
08701           _v606.frame_id = str[start:end].decode('utf-8')
08702         else:
08703           _v606.frame_id = str[start:end]
08704         _x = _v605
08705         start = end
08706         end += 8
08707         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
08708         start = end
08709         end += 4
08710         (length,) = _struct_I.unpack(str[start:end])
08711         start = end
08712         end += length
08713         if python3:
08714           _v605.encoding = str[start:end].decode('utf-8')
08715         else:
08716           _v605.encoding = str[start:end]
08717         _x = _v605
08718         start = end
08719         end += 5
08720         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
08721         start = end
08722         end += 4
08723         (length,) = _struct_I.unpack(str[start:end])
08724         start = end
08725         end += length
08726         if python3:
08727           _v605.data = str[start:end].decode('utf-8')
08728         else:
08729           _v605.data = str[start:end]
08730         _v608 = _v601.disparity_image
08731         _v609 = _v608.header
08732         start = end
08733         end += 4
08734         (_v609.seq,) = _struct_I.unpack(str[start:end])
08735         _v610 = _v609.stamp
08736         _x = _v610
08737         start = end
08738         end += 8
08739         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08740         start = end
08741         end += 4
08742         (length,) = _struct_I.unpack(str[start:end])
08743         start = end
08744         end += length
08745         if python3:
08746           _v609.frame_id = str[start:end].decode('utf-8')
08747         else:
08748           _v609.frame_id = str[start:end]
08749         _x = _v608
08750         start = end
08751         end += 8
08752         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
08753         start = end
08754         end += 4
08755         (length,) = _struct_I.unpack(str[start:end])
08756         start = end
08757         end += length
08758         if python3:
08759           _v608.encoding = str[start:end].decode('utf-8')
08760         else:
08761           _v608.encoding = str[start:end]
08762         _x = _v608
08763         start = end
08764         end += 5
08765         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
08766         start = end
08767         end += 4
08768         (length,) = _struct_I.unpack(str[start:end])
08769         start = end
08770         end += length
08771         if python3:
08772           _v608.data = str[start:end].decode('utf-8')
08773         else:
08774           _v608.data = str[start:end]
08775         _v611 = _v601.cam_info
08776         _v612 = _v611.header
08777         start = end
08778         end += 4
08779         (_v612.seq,) = _struct_I.unpack(str[start:end])
08780         _v613 = _v612.stamp
08781         _x = _v613
08782         start = end
08783         end += 8
08784         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08785         start = end
08786         end += 4
08787         (length,) = _struct_I.unpack(str[start:end])
08788         start = end
08789         end += length
08790         if python3:
08791           _v612.frame_id = str[start:end].decode('utf-8')
08792         else:
08793           _v612.frame_id = str[start:end]
08794         _x = _v611
08795         start = end
08796         end += 8
08797         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
08798         start = end
08799         end += 4
08800         (length,) = _struct_I.unpack(str[start:end])
08801         start = end
08802         end += length
08803         if python3:
08804           _v611.distortion_model = str[start:end].decode('utf-8')
08805         else:
08806           _v611.distortion_model = str[start:end]
08807         start = end
08808         end += 4
08809         (length,) = _struct_I.unpack(str[start:end])
08810         pattern = '<%sd'%length
08811         start = end
08812         end += struct.calcsize(pattern)
08813         _v611.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
08814         start = end
08815         end += 72
08816         _v611.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
08817         start = end
08818         end += 72
08819         _v611.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
08820         start = end
08821         end += 96
08822         _v611.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
08823         _x = _v611
08824         start = end
08825         end += 8
08826         (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
08827         _v614 = _v611.roi
08828         _x = _v614
08829         start = end
08830         end += 17
08831         (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
08832         _v614.do_rectify = bool(_v614.do_rectify)
08833         _v615 = _v601.roi_box_pose
08834         _v616 = _v615.header
08835         start = end
08836         end += 4
08837         (_v616.seq,) = _struct_I.unpack(str[start:end])
08838         _v617 = _v616.stamp
08839         _x = _v617
08840         start = end
08841         end += 8
08842         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08843         start = end
08844         end += 4
08845         (length,) = _struct_I.unpack(str[start:end])
08846         start = end
08847         end += length
08848         if python3:
08849           _v616.frame_id = str[start:end].decode('utf-8')
08850         else:
08851           _v616.frame_id = str[start:end]
08852         _v618 = _v615.pose
08853         _v619 = _v618.position
08854         _x = _v619
08855         start = end
08856         end += 24
08857         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
08858         _v620 = _v618.orientation
08859         _x = _v620
08860         start = end
08861         end += 32
08862         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
08863         _v621 = _v601.roi_box_dims
08864         _x = _v621
08865         start = end
08866         end += 24
08867         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
08868         start = end
08869         end += 4
08870         (length,) = _struct_I.unpack(str[start:end])
08871         start = end
08872         end += length
08873         if python3:
08874           val1.collision_name = str[start:end].decode('utf-8')
08875         else:
08876           val1.collision_name = str[start:end]
08877         self.action_result.result.grasp.moved_obstacles.append(val1)
08878       start = end
08879       end += 4
08880       (length,) = _struct_I.unpack(str[start:end])
08881       self.action_result.result.attempted_grasps = []
08882       for i in range(0, length):
08883         val1 = object_manipulation_msgs.msg.Grasp()
08884         _v622 = val1.pre_grasp_posture
08885         _v623 = _v622.header
08886         start = end
08887         end += 4
08888         (_v623.seq,) = _struct_I.unpack(str[start:end])
08889         _v624 = _v623.stamp
08890         _x = _v624
08891         start = end
08892         end += 8
08893         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08894         start = end
08895         end += 4
08896         (length,) = _struct_I.unpack(str[start:end])
08897         start = end
08898         end += length
08899         if python3:
08900           _v623.frame_id = str[start:end].decode('utf-8')
08901         else:
08902           _v623.frame_id = str[start:end]
08903         start = end
08904         end += 4
08905         (length,) = _struct_I.unpack(str[start:end])
08906         _v622.name = []
08907         for i in range(0, length):
08908           start = end
08909           end += 4
08910           (length,) = _struct_I.unpack(str[start:end])
08911           start = end
08912           end += length
08913           if python3:
08914             val3 = str[start:end].decode('utf-8')
08915           else:
08916             val3 = str[start:end]
08917           _v622.name.append(val3)
08918         start = end
08919         end += 4
08920         (length,) = _struct_I.unpack(str[start:end])
08921         pattern = '<%sd'%length
08922         start = end
08923         end += struct.calcsize(pattern)
08924         _v622.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
08925         start = end
08926         end += 4
08927         (length,) = _struct_I.unpack(str[start:end])
08928         pattern = '<%sd'%length
08929         start = end
08930         end += struct.calcsize(pattern)
08931         _v622.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
08932         start = end
08933         end += 4
08934         (length,) = _struct_I.unpack(str[start:end])
08935         pattern = '<%sd'%length
08936         start = end
08937         end += struct.calcsize(pattern)
08938         _v622.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
08939         _v625 = val1.grasp_posture
08940         _v626 = _v625.header
08941         start = end
08942         end += 4
08943         (_v626.seq,) = _struct_I.unpack(str[start:end])
08944         _v627 = _v626.stamp
08945         _x = _v627
08946         start = end
08947         end += 8
08948         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
08949         start = end
08950         end += 4
08951         (length,) = _struct_I.unpack(str[start:end])
08952         start = end
08953         end += length
08954         if python3:
08955           _v626.frame_id = str[start:end].decode('utf-8')
08956         else:
08957           _v626.frame_id = str[start:end]
08958         start = end
08959         end += 4
08960         (length,) = _struct_I.unpack(str[start:end])
08961         _v625.name = []
08962         for i in range(0, length):
08963           start = end
08964           end += 4
08965           (length,) = _struct_I.unpack(str[start:end])
08966           start = end
08967           end += length
08968           if python3:
08969             val3 = str[start:end].decode('utf-8')
08970           else:
08971             val3 = str[start:end]
08972           _v625.name.append(val3)
08973         start = end
08974         end += 4
08975         (length,) = _struct_I.unpack(str[start:end])
08976         pattern = '<%sd'%length
08977         start = end
08978         end += struct.calcsize(pattern)
08979         _v625.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
08980         start = end
08981         end += 4
08982         (length,) = _struct_I.unpack(str[start:end])
08983         pattern = '<%sd'%length
08984         start = end
08985         end += struct.calcsize(pattern)
08986         _v625.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
08987         start = end
08988         end += 4
08989         (length,) = _struct_I.unpack(str[start:end])
08990         pattern = '<%sd'%length
08991         start = end
08992         end += struct.calcsize(pattern)
08993         _v625.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
08994         _v628 = val1.grasp_pose
08995         _v629 = _v628.position
08996         _x = _v629
08997         start = end
08998         end += 24
08999         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
09000         _v630 = _v628.orientation
09001         _x = _v630
09002         start = end
09003         end += 32
09004         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
09005         _x = val1
09006         start = end
09007         end += 17
09008         (_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance,) = _struct_dB2f.unpack(str[start:end])
09009         val1.cluster_rep = bool(val1.cluster_rep)
09010         start = end
09011         end += 4
09012         (length,) = _struct_I.unpack(str[start:end])
09013         val1.moved_obstacles = []
09014         for i in range(0, length):
09015           val2 = object_manipulation_msgs.msg.GraspableObject()
09016           start = end
09017           end += 4
09018           (length,) = _struct_I.unpack(str[start:end])
09019           start = end
09020           end += length
09021           if python3:
09022             val2.reference_frame_id = str[start:end].decode('utf-8')
09023           else:
09024             val2.reference_frame_id = str[start:end]
09025           start = end
09026           end += 4
09027           (length,) = _struct_I.unpack(str[start:end])
09028           val2.potential_models = []
09029           for i in range(0, length):
09030             val3 = household_objects_database_msgs.msg.DatabaseModelPose()
09031             start = end
09032             end += 4
09033             (val3.model_id,) = _struct_i.unpack(str[start:end])
09034             _v631 = val3.pose
09035             _v632 = _v631.header
09036             start = end
09037             end += 4
09038             (_v632.seq,) = _struct_I.unpack(str[start:end])
09039             _v633 = _v632.stamp
09040             _x = _v633
09041             start = end
09042             end += 8
09043             (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
09044             start = end
09045             end += 4
09046             (length,) = _struct_I.unpack(str[start:end])
09047             start = end
09048             end += length
09049             if python3:
09050               _v632.frame_id = str[start:end].decode('utf-8')
09051             else:
09052               _v632.frame_id = str[start:end]
09053             _v634 = _v631.pose
09054             _v635 = _v634.position
09055             _x = _v635
09056             start = end
09057             end += 24
09058             (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
09059             _v636 = _v634.orientation
09060             _x = _v636
09061             start = end
09062             end += 32
09063             (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
09064             start = end
09065             end += 4
09066             (val3.confidence,) = _struct_f.unpack(str[start:end])
09067             start = end
09068             end += 4
09069             (length,) = _struct_I.unpack(str[start:end])
09070             start = end
09071             end += length
09072             if python3:
09073               val3.detector_name = str[start:end].decode('utf-8')
09074             else:
09075               val3.detector_name = str[start:end]
09076             val2.potential_models.append(val3)
09077           _v637 = val2.cluster
09078           _v638 = _v637.header
09079           start = end
09080           end += 4
09081           (_v638.seq,) = _struct_I.unpack(str[start:end])
09082           _v639 = _v638.stamp
09083           _x = _v639
09084           start = end
09085           end += 8
09086           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
09087           start = end
09088           end += 4
09089           (length,) = _struct_I.unpack(str[start:end])
09090           start = end
09091           end += length
09092           if python3:
09093             _v638.frame_id = str[start:end].decode('utf-8')
09094           else:
09095             _v638.frame_id = str[start:end]
09096           start = end
09097           end += 4
09098           (length,) = _struct_I.unpack(str[start:end])
09099           _v637.points = []
09100           for i in range(0, length):
09101             val4 = geometry_msgs.msg.Point32()
09102             _x = val4
09103             start = end
09104             end += 12
09105             (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
09106             _v637.points.append(val4)
09107           start = end
09108           end += 4
09109           (length,) = _struct_I.unpack(str[start:end])
09110           _v637.channels = []
09111           for i in range(0, length):
09112             val4 = sensor_msgs.msg.ChannelFloat32()
09113             start = end
09114             end += 4
09115             (length,) = _struct_I.unpack(str[start:end])
09116             start = end
09117             end += length
09118             if python3:
09119               val4.name = str[start:end].decode('utf-8')
09120             else:
09121               val4.name = str[start:end]
09122             start = end
09123             end += 4
09124             (length,) = _struct_I.unpack(str[start:end])
09125             pattern = '<%sf'%length
09126             start = end
09127             end += struct.calcsize(pattern)
09128             val4.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
09129             _v637.channels.append(val4)
09130           _v640 = val2.region
09131           _v641 = _v640.cloud
09132           _v642 = _v641.header
09133           start = end
09134           end += 4
09135           (_v642.seq,) = _struct_I.unpack(str[start:end])
09136           _v643 = _v642.stamp
09137           _x = _v643
09138           start = end
09139           end += 8
09140           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
09141           start = end
09142           end += 4
09143           (length,) = _struct_I.unpack(str[start:end])
09144           start = end
09145           end += length
09146           if python3:
09147             _v642.frame_id = str[start:end].decode('utf-8')
09148           else:
09149             _v642.frame_id = str[start:end]
09150           _x = _v641
09151           start = end
09152           end += 8
09153           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
09154           start = end
09155           end += 4
09156           (length,) = _struct_I.unpack(str[start:end])
09157           _v641.fields = []
09158           for i in range(0, length):
09159             val5 = sensor_msgs.msg.PointField()
09160             start = end
09161             end += 4
09162             (length,) = _struct_I.unpack(str[start:end])
09163             start = end
09164             end += length
09165             if python3:
09166               val5.name = str[start:end].decode('utf-8')
09167             else:
09168               val5.name = str[start:end]
09169             _x = val5
09170             start = end
09171             end += 9
09172             (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
09173             _v641.fields.append(val5)
09174           _x = _v641
09175           start = end
09176           end += 9
09177           (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
09178           _v641.is_bigendian = bool(_v641.is_bigendian)
09179           start = end
09180           end += 4
09181           (length,) = _struct_I.unpack(str[start:end])
09182           start = end
09183           end += length
09184           if python3:
09185             _v641.data = str[start:end].decode('utf-8')
09186           else:
09187             _v641.data = str[start:end]
09188           start = end
09189           end += 1
09190           (_v641.is_dense,) = _struct_B.unpack(str[start:end])
09191           _v641.is_dense = bool(_v641.is_dense)
09192           start = end
09193           end += 4
09194           (length,) = _struct_I.unpack(str[start:end])
09195           pattern = '<%si'%length
09196           start = end
09197           end += struct.calcsize(pattern)
09198           _v640.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
09199           _v644 = _v640.image
09200           _v645 = _v644.header
09201           start = end
09202           end += 4
09203           (_v645.seq,) = _struct_I.unpack(str[start:end])
09204           _v646 = _v645.stamp
09205           _x = _v646
09206           start = end
09207           end += 8
09208           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
09209           start = end
09210           end += 4
09211           (length,) = _struct_I.unpack(str[start:end])
09212           start = end
09213           end += length
09214           if python3:
09215             _v645.frame_id = str[start:end].decode('utf-8')
09216           else:
09217             _v645.frame_id = str[start:end]
09218           _x = _v644
09219           start = end
09220           end += 8
09221           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
09222           start = end
09223           end += 4
09224           (length,) = _struct_I.unpack(str[start:end])
09225           start = end
09226           end += length
09227           if python3:
09228             _v644.encoding = str[start:end].decode('utf-8')
09229           else:
09230             _v644.encoding = str[start:end]
09231           _x = _v644
09232           start = end
09233           end += 5
09234           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
09235           start = end
09236           end += 4
09237           (length,) = _struct_I.unpack(str[start:end])
09238           start = end
09239           end += length
09240           if python3:
09241             _v644.data = str[start:end].decode('utf-8')
09242           else:
09243             _v644.data = str[start:end]
09244           _v647 = _v640.disparity_image
09245           _v648 = _v647.header
09246           start = end
09247           end += 4
09248           (_v648.seq,) = _struct_I.unpack(str[start:end])
09249           _v649 = _v648.stamp
09250           _x = _v649
09251           start = end
09252           end += 8
09253           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
09254           start = end
09255           end += 4
09256           (length,) = _struct_I.unpack(str[start:end])
09257           start = end
09258           end += length
09259           if python3:
09260             _v648.frame_id = str[start:end].decode('utf-8')
09261           else:
09262             _v648.frame_id = str[start:end]
09263           _x = _v647
09264           start = end
09265           end += 8
09266           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
09267           start = end
09268           end += 4
09269           (length,) = _struct_I.unpack(str[start:end])
09270           start = end
09271           end += length
09272           if python3:
09273             _v647.encoding = str[start:end].decode('utf-8')
09274           else:
09275             _v647.encoding = str[start:end]
09276           _x = _v647
09277           start = end
09278           end += 5
09279           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
09280           start = end
09281           end += 4
09282           (length,) = _struct_I.unpack(str[start:end])
09283           start = end
09284           end += length
09285           if python3:
09286             _v647.data = str[start:end].decode('utf-8')
09287           else:
09288             _v647.data = str[start:end]
09289           _v650 = _v640.cam_info
09290           _v651 = _v650.header
09291           start = end
09292           end += 4
09293           (_v651.seq,) = _struct_I.unpack(str[start:end])
09294           _v652 = _v651.stamp
09295           _x = _v652
09296           start = end
09297           end += 8
09298           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
09299           start = end
09300           end += 4
09301           (length,) = _struct_I.unpack(str[start:end])
09302           start = end
09303           end += length
09304           if python3:
09305             _v651.frame_id = str[start:end].decode('utf-8')
09306           else:
09307             _v651.frame_id = str[start:end]
09308           _x = _v650
09309           start = end
09310           end += 8
09311           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
09312           start = end
09313           end += 4
09314           (length,) = _struct_I.unpack(str[start:end])
09315           start = end
09316           end += length
09317           if python3:
09318             _v650.distortion_model = str[start:end].decode('utf-8')
09319           else:
09320             _v650.distortion_model = str[start:end]
09321           start = end
09322           end += 4
09323           (length,) = _struct_I.unpack(str[start:end])
09324           pattern = '<%sd'%length
09325           start = end
09326           end += struct.calcsize(pattern)
09327           _v650.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
09328           start = end
09329           end += 72
09330           _v650.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
09331           start = end
09332           end += 72
09333           _v650.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
09334           start = end
09335           end += 96
09336           _v650.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
09337           _x = _v650
09338           start = end
09339           end += 8
09340           (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
09341           _v653 = _v650.roi
09342           _x = _v653
09343           start = end
09344           end += 17
09345           (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
09346           _v653.do_rectify = bool(_v653.do_rectify)
09347           _v654 = _v640.roi_box_pose
09348           _v655 = _v654.header
09349           start = end
09350           end += 4
09351           (_v655.seq,) = _struct_I.unpack(str[start:end])
09352           _v656 = _v655.stamp
09353           _x = _v656
09354           start = end
09355           end += 8
09356           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
09357           start = end
09358           end += 4
09359           (length,) = _struct_I.unpack(str[start:end])
09360           start = end
09361           end += length
09362           if python3:
09363             _v655.frame_id = str[start:end].decode('utf-8')
09364           else:
09365             _v655.frame_id = str[start:end]
09366           _v657 = _v654.pose
09367           _v658 = _v657.position
09368           _x = _v658
09369           start = end
09370           end += 24
09371           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
09372           _v659 = _v657.orientation
09373           _x = _v659
09374           start = end
09375           end += 32
09376           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
09377           _v660 = _v640.roi_box_dims
09378           _x = _v660
09379           start = end
09380           end += 24
09381           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
09382           start = end
09383           end += 4
09384           (length,) = _struct_I.unpack(str[start:end])
09385           start = end
09386           end += length
09387           if python3:
09388             val2.collision_name = str[start:end].decode('utf-8')
09389           else:
09390             val2.collision_name = str[start:end]
09391           val1.moved_obstacles.append(val2)
09392         self.action_result.result.attempted_grasps.append(val1)
09393       start = end
09394       end += 4
09395       (length,) = _struct_I.unpack(str[start:end])
09396       self.action_result.result.attempted_grasp_results = []
09397       for i in range(0, length):
09398         val1 = object_manipulation_msgs.msg.GraspResult()
09399         _x = val1
09400         start = end
09401         end += 5
09402         (_x.result_code, _x.continuation_possible,) = _struct_iB.unpack(str[start:end])
09403         val1.continuation_possible = bool(val1.continuation_possible)
09404         self.action_result.result.attempted_grasp_results.append(val1)
09405       _x = self
09406       start = end
09407       end += 12
09408       (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
09409       start = end
09410       end += 4
09411       (length,) = _struct_I.unpack(str[start:end])
09412       start = end
09413       end += length
09414       if python3:
09415         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
09416       else:
09417         self.action_feedback.header.frame_id = str[start:end]
09418       _x = self
09419       start = end
09420       end += 8
09421       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
09422       start = end
09423       end += 4
09424       (length,) = _struct_I.unpack(str[start:end])
09425       start = end
09426       end += length
09427       if python3:
09428         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
09429       else:
09430         self.action_feedback.status.goal_id.id = str[start:end]
09431       start = end
09432       end += 1
09433       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
09434       start = end
09435       end += 4
09436       (length,) = _struct_I.unpack(str[start:end])
09437       start = end
09438       end += length
09439       if python3:
09440         self.action_feedback.status.text = str[start:end].decode('utf-8')
09441       else:
09442         self.action_feedback.status.text = str[start:end]
09443       _x = self
09444       start = end
09445       end += 8
09446       (_x.action_feedback.feedback.current_grasp, _x.action_feedback.feedback.total_grasps,) = _struct_2i.unpack(str[start:end])
09447       return self
09448     except struct.error as e:
09449       raise genpy.DeserializationError(e) #most likely buffer underfill
09450 
09451 _struct_I = genpy.struct_I
09452 _struct_IBI = struct.Struct("<IBI")
09453 _struct_12d = struct.Struct("<12d")
09454 _struct_f3I = struct.Struct("<f3I")
09455 _struct_dB2f = struct.Struct("<dB2f")
09456 _struct_BI = struct.Struct("<BI")
09457 _struct_10d = struct.Struct("<10d")
09458 _struct_3I = struct.Struct("<3I")
09459 _struct_B2I = struct.Struct("<B2I")
09460 _struct_5B = struct.Struct("<5B")
09461 _struct_8dB2f = struct.Struct("<8dB2f")
09462 _struct_i3I = struct.Struct("<i3I")
09463 _struct_iB = struct.Struct("<iB")
09464 _struct_3f = struct.Struct("<3f")
09465 _struct_3d = struct.Struct("<3d")
09466 _struct_B = struct.Struct("<B")
09467 _struct_di = struct.Struct("<di")
09468 _struct_9d = struct.Struct("<9d")
09469 _struct_2I = struct.Struct("<2I")
09470 _struct_6IB3I = struct.Struct("<6IB3I")
09471 _struct_b = struct.Struct("<b")
09472 _struct_d = struct.Struct("<d")
09473 _struct_f = struct.Struct("<f")
09474 _struct_i = struct.Struct("<i")
09475 _struct_3d2f = struct.Struct("<3d2f")
09476 _struct_4d = struct.Struct("<4d")
09477 _struct_2i = struct.Struct("<2i")
09478 _struct_4IB = struct.Struct("<4IB")


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