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


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