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


object_manipulation_msgs
Author(s): Matei Ciocarlie
autogenerated on Mon Oct 6 2014 02:58:11