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


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