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


pr2_object_manipulation_msgs
Author(s): Matei Ciocarlie
autogenerated on Fri Jan 3 2014 11:59:12