_GraspAdjustAction.py
Go to the documentation of this file.
00001 """autogenerated by genpy from pr2_grasp_adjust/GraspAdjustAction.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 object_manipulation_msgs.msg
00008 import actionlib_msgs.msg
00009 import geometry_msgs.msg
00010 import sensor_msgs.msg
00011 import pr2_grasp_adjust.msg
00012 import household_objects_database_msgs.msg
00013 import genpy
00014 import std_msgs.msg
00015 
00016 class GraspAdjustAction(genpy.Message):
00017   _md5sum = "f0e5bb32c517b402aa57198a61487538"
00018   _type = "pr2_grasp_adjust/GraspAdjustAction"
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 GraspAdjustActionGoal action_goal
00023 GraspAdjustActionResult action_result
00024 GraspAdjustActionFeedback action_feedback
00025 
00026 ================================================================================
00027 MSG: pr2_grasp_adjust/GraspAdjustActionGoal
00028 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00029 
00030 Header header
00031 actionlib_msgs/GoalID goal_id
00032 GraspAdjustGoal 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_grasp_adjust/GraspAdjustGoal
00067 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00068 #goal definition
00069 
00070 sensor_msgs/PointCloud2 cloud
00071 geometry_msgs/PoseStamped pose_stamped
00072 bool use_orientation
00073 int32 seed_index
00074 uint8 search_mode
00075 
00076 int32 GLOBAL_SEARCH = 0
00077 int32 LOCAL_SEARCH = 1
00078 int32 SINGLE_POSE = 2
00079 
00080 
00081 ================================================================================
00082 MSG: sensor_msgs/PointCloud2
00083 # This message holds a collection of N-dimensional points, which may
00084 # contain additional information such as normals, intensity, etc. The
00085 # point data is stored as a binary blob, its layout described by the
00086 # contents of the "fields" array.
00087 
00088 # The point cloud data may be organized 2d (image-like) or 1d
00089 # (unordered). Point clouds organized as 2d images may be produced by
00090 # camera depth sensors such as stereo or time-of-flight.
00091 
00092 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00093 # points).
00094 Header header
00095 
00096 # 2D structure of the point cloud. If the cloud is unordered, height is
00097 # 1 and width is the length of the point cloud.
00098 uint32 height
00099 uint32 width
00100 
00101 # Describes the channels and their layout in the binary data blob.
00102 PointField[] fields
00103 
00104 bool    is_bigendian # Is this data bigendian?
00105 uint32  point_step   # Length of a point in bytes
00106 uint32  row_step     # Length of a row in bytes
00107 uint8[] data         # Actual point data, size is (row_step*height)
00108 
00109 bool is_dense        # True if there are no invalid points
00110 
00111 ================================================================================
00112 MSG: sensor_msgs/PointField
00113 # This message holds the description of one point entry in the
00114 # PointCloud2 message format.
00115 uint8 INT8    = 1
00116 uint8 UINT8   = 2
00117 uint8 INT16   = 3
00118 uint8 UINT16  = 4
00119 uint8 INT32   = 5
00120 uint8 UINT32  = 6
00121 uint8 FLOAT32 = 7
00122 uint8 FLOAT64 = 8
00123 
00124 string name      # Name of field
00125 uint32 offset    # Offset from start of point struct
00126 uint8  datatype  # Datatype enumeration, see above
00127 uint32 count     # How many elements in the field
00128 
00129 ================================================================================
00130 MSG: geometry_msgs/PoseStamped
00131 # A Pose with reference coordinate frame and timestamp
00132 Header header
00133 Pose pose
00134 
00135 ================================================================================
00136 MSG: geometry_msgs/Pose
00137 # A representation of pose in free space, composed of postion and orientation. 
00138 Point position
00139 Quaternion orientation
00140 
00141 ================================================================================
00142 MSG: geometry_msgs/Point
00143 # This contains the position of a point in free space
00144 float64 x
00145 float64 y
00146 float64 z
00147 
00148 ================================================================================
00149 MSG: geometry_msgs/Quaternion
00150 # This represents an orientation in free space in quaternion form.
00151 
00152 float64 x
00153 float64 y
00154 float64 z
00155 float64 w
00156 
00157 ================================================================================
00158 MSG: pr2_grasp_adjust/GraspAdjustActionResult
00159 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00160 
00161 Header header
00162 actionlib_msgs/GoalStatus status
00163 GraspAdjustResult result
00164 
00165 ================================================================================
00166 MSG: actionlib_msgs/GoalStatus
00167 GoalID goal_id
00168 uint8 status
00169 uint8 PENDING         = 0   # The goal has yet to be processed by the action server
00170 uint8 ACTIVE          = 1   # The goal is currently being processed by the action server
00171 uint8 PREEMPTED       = 2   # The goal received a cancel request after it started executing
00172                             #   and has since completed its execution (Terminal State)
00173 uint8 SUCCEEDED       = 3   # The goal was achieved successfully by the action server (Terminal State)
00174 uint8 ABORTED         = 4   # The goal was aborted during execution by the action server due
00175                             #    to some failure (Terminal State)
00176 uint8 REJECTED        = 5   # The goal was rejected by the action server without being processed,
00177                             #    because the goal was unattainable or invalid (Terminal State)
00178 uint8 PREEMPTING      = 6   # The goal received a cancel request after it started executing
00179                             #    and has not yet completed execution
00180 uint8 RECALLING       = 7   # The goal received a cancel request before it started executing,
00181                             #    but the action server has not yet confirmed that the goal is canceled
00182 uint8 RECALLED        = 8   # The goal received a cancel request before it started executing
00183                             #    and was successfully cancelled (Terminal State)
00184 uint8 LOST            = 9   # An action client can determine that a goal is LOST. This should not be
00185                             #    sent over the wire by an action server
00186 
00187 #Allow for the user to associate a string with GoalStatus for debugging
00188 string text
00189 
00190 
00191 ================================================================================
00192 MSG: pr2_grasp_adjust/GraspAdjustResult
00193 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00194 #result definition
00195 
00196 object_manipulation_msgs/Grasp[] grasps
00197 object_manipulation_msgs/GraspPlanningErrorCode result
00198 
00199 
00200 ================================================================================
00201 MSG: object_manipulation_msgs/Grasp
00202 
00203 # The internal posture of the hand for the pre-grasp
00204 # only positions are used
00205 sensor_msgs/JointState pre_grasp_posture
00206 
00207 # The internal posture of the hand for the grasp
00208 # positions and efforts are used
00209 sensor_msgs/JointState grasp_posture
00210 
00211 # The position of the end-effector for the grasp relative to a reference frame 
00212 # (that is always specified elsewhere, not in this message)
00213 geometry_msgs/Pose grasp_pose
00214 
00215 # The estimated probability of success for this grasp
00216 float64 success_probability
00217 
00218 # Debug flag to indicate that this grasp would be the best in its cluster
00219 bool cluster_rep
00220 
00221 # how far the pre-grasp should ideally be away from the grasp
00222 float32 desired_approach_distance
00223 
00224 # how much distance between pre-grasp and grasp must actually be feasible 
00225 # for the grasp not to be rejected
00226 float32 min_approach_distance
00227 
00228 # an optional list of obstacles that we have semantic information about
00229 # and that we expect might move in the course of executing this grasp
00230 # the grasp planner is expected to make sure they move in an OK way; during
00231 # execution, grasp executors will not check for collisions against these objects
00232 GraspableObject[] moved_obstacles
00233 
00234 ================================================================================
00235 MSG: sensor_msgs/JointState
00236 # This is a message that holds data to describe the state of a set of torque controlled joints. 
00237 #
00238 # The state of each joint (revolute or prismatic) is defined by:
00239 #  * the position of the joint (rad or m),
00240 #  * the velocity of the joint (rad/s or m/s) and 
00241 #  * the effort that is applied in the joint (Nm or N).
00242 #
00243 # Each joint is uniquely identified by its name
00244 # The header specifies the time at which the joint states were recorded. All the joint states
00245 # in one message have to be recorded at the same time.
00246 #
00247 # This message consists of a multiple arrays, one for each part of the joint state. 
00248 # The goal is to make each of the fields optional. When e.g. your joints have no
00249 # effort associated with them, you can leave the effort array empty. 
00250 #
00251 # All arrays in this message should have the same size, or be empty.
00252 # This is the only way to uniquely associate the joint name with the correct
00253 # states.
00254 
00255 
00256 Header header
00257 
00258 string[] name
00259 float64[] position
00260 float64[] velocity
00261 float64[] effort
00262 
00263 ================================================================================
00264 MSG: object_manipulation_msgs/GraspableObject
00265 # an object that the object_manipulator can work on
00266 
00267 # a graspable object can be represented in multiple ways. This message
00268 # can contain all of them. Which one is actually used is up to the receiver
00269 # of this message. When adding new representations, one must be careful that
00270 # they have reasonable lightweight defaults indicating that that particular
00271 # representation is not available.
00272 
00273 # the tf frame to be used as a reference frame when combining information from
00274 # the different representations below
00275 string reference_frame_id
00276 
00277 # potential recognition results from a database of models
00278 # all poses are relative to the object reference pose
00279 household_objects_database_msgs/DatabaseModelPose[] potential_models
00280 
00281 # the point cloud itself
00282 sensor_msgs/PointCloud cluster
00283 
00284 # a region of a PointCloud2 of interest
00285 object_manipulation_msgs/SceneRegion region
00286 
00287 # the name that this object has in the collision environment
00288 string collision_name
00289 ================================================================================
00290 MSG: household_objects_database_msgs/DatabaseModelPose
00291 # Informs that a specific model from the Model Database has been 
00292 # identified at a certain location
00293 
00294 # the database id of the model
00295 int32 model_id
00296 
00297 # the pose that it can be found in
00298 geometry_msgs/PoseStamped pose
00299 
00300 # a measure of the confidence level in this detection result
00301 float32 confidence
00302 
00303 # the name of the object detector that generated this detection result
00304 string detector_name
00305 
00306 ================================================================================
00307 MSG: sensor_msgs/PointCloud
00308 # This message holds a collection of 3d points, plus optional additional
00309 # information about each point.
00310 
00311 # Time of sensor data acquisition, coordinate frame ID.
00312 Header header
00313 
00314 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00315 # in the frame given in the header.
00316 geometry_msgs/Point32[] points
00317 
00318 # Each channel should have the same number of elements as points array,
00319 # and the data in each channel should correspond 1:1 with each point.
00320 # Channel names in common practice are listed in ChannelFloat32.msg.
00321 ChannelFloat32[] channels
00322 
00323 ================================================================================
00324 MSG: geometry_msgs/Point32
00325 # This contains the position of a point in free space(with 32 bits of precision).
00326 # It is recommeded to use Point wherever possible instead of Point32.  
00327 # 
00328 # This recommendation is to promote interoperability.  
00329 #
00330 # This message is designed to take up less space when sending
00331 # lots of points at once, as in the case of a PointCloud.  
00332 
00333 float32 x
00334 float32 y
00335 float32 z
00336 ================================================================================
00337 MSG: sensor_msgs/ChannelFloat32
00338 # This message is used by the PointCloud message to hold optional data
00339 # associated with each point in the cloud. The length of the values
00340 # array should be the same as the length of the points array in the
00341 # PointCloud, and each value should be associated with the corresponding
00342 # point.
00343 
00344 # Channel names in existing practice include:
00345 #   "u", "v" - row and column (respectively) in the left stereo image.
00346 #              This is opposite to usual conventions but remains for
00347 #              historical reasons. The newer PointCloud2 message has no
00348 #              such problem.
00349 #   "rgb" - For point clouds produced by color stereo cameras. uint8
00350 #           (R,G,B) values packed into the least significant 24 bits,
00351 #           in order.
00352 #   "intensity" - laser or pixel intensity.
00353 #   "distance"
00354 
00355 # The channel name should give semantics of the channel (e.g.
00356 # "intensity" instead of "value").
00357 string name
00358 
00359 # The values array should be 1-1 with the elements of the associated
00360 # PointCloud.
00361 float32[] values
00362 
00363 ================================================================================
00364 MSG: object_manipulation_msgs/SceneRegion
00365 # Point cloud
00366 sensor_msgs/PointCloud2 cloud
00367 
00368 # Indices for the region of interest
00369 int32[] mask
00370 
00371 # One of the corresponding 2D images, if applicable
00372 sensor_msgs/Image image
00373 
00374 # The disparity image, if applicable
00375 sensor_msgs/Image disparity_image
00376 
00377 # Camera info for the camera that took the image
00378 sensor_msgs/CameraInfo cam_info
00379 
00380 # a 3D region of interest for grasp planning
00381 geometry_msgs/PoseStamped  roi_box_pose
00382 geometry_msgs/Vector3      roi_box_dims
00383 
00384 ================================================================================
00385 MSG: sensor_msgs/Image
00386 # This message contains an uncompressed image
00387 # (0, 0) is at top-left corner of image
00388 #
00389 
00390 Header header        # Header timestamp should be acquisition time of image
00391                      # Header frame_id should be optical frame of camera
00392                      # origin of frame should be optical center of cameara
00393                      # +x should point to the right in the image
00394                      # +y should point down in the image
00395                      # +z should point into to plane of the image
00396                      # If the frame_id here and the frame_id of the CameraInfo
00397                      # message associated with the image conflict
00398                      # the behavior is undefined
00399 
00400 uint32 height         # image height, that is, number of rows
00401 uint32 width          # image width, that is, number of columns
00402 
00403 # The legal values for encoding are in file src/image_encodings.cpp
00404 # If you want to standardize a new string format, join
00405 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00406 
00407 string encoding       # Encoding of pixels -- channel meaning, ordering, size
00408                       # taken from the list of strings in src/image_encodings.cpp
00409 
00410 uint8 is_bigendian    # is this data bigendian?
00411 uint32 step           # Full row length in bytes
00412 uint8[] data          # actual matrix data, size is (step * rows)
00413 
00414 ================================================================================
00415 MSG: sensor_msgs/CameraInfo
00416 # This message defines meta information for a camera. It should be in a
00417 # camera namespace on topic "camera_info" and accompanied by up to five
00418 # image topics named:
00419 #
00420 #   image_raw - raw data from the camera driver, possibly Bayer encoded
00421 #   image            - monochrome, distorted
00422 #   image_color      - color, distorted
00423 #   image_rect       - monochrome, rectified
00424 #   image_rect_color - color, rectified
00425 #
00426 # The image_pipeline contains packages (image_proc, stereo_image_proc)
00427 # for producing the four processed image topics from image_raw and
00428 # camera_info. The meaning of the camera parameters are described in
00429 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
00430 #
00431 # The image_geometry package provides a user-friendly interface to
00432 # common operations using this meta information. If you want to, e.g.,
00433 # project a 3d point into image coordinates, we strongly recommend
00434 # using image_geometry.
00435 #
00436 # If the camera is uncalibrated, the matrices D, K, R, P should be left
00437 # zeroed out. In particular, clients may assume that K[0] == 0.0
00438 # indicates an uncalibrated camera.
00439 
00440 #######################################################################
00441 #                     Image acquisition info                          #
00442 #######################################################################
00443 
00444 # Time of image acquisition, camera coordinate frame ID
00445 Header header    # Header timestamp should be acquisition time of image
00446                  # Header frame_id should be optical frame of camera
00447                  # origin of frame should be optical center of camera
00448                  # +x should point to the right in the image
00449                  # +y should point down in the image
00450                  # +z should point into the plane of the image
00451 
00452 
00453 #######################################################################
00454 #                      Calibration Parameters                         #
00455 #######################################################################
00456 # These are fixed during camera calibration. Their values will be the #
00457 # same in all messages until the camera is recalibrated. Note that    #
00458 # self-calibrating systems may "recalibrate" frequently.              #
00459 #                                                                     #
00460 # The internal parameters can be used to warp a raw (distorted) image #
00461 # to:                                                                 #
00462 #   1. An undistorted image (requires D and K)                        #
00463 #   2. A rectified image (requires D, K, R)                           #
00464 # The projection matrix P projects 3D points into the rectified image.#
00465 #######################################################################
00466 
00467 # The image dimensions with which the camera was calibrated. Normally
00468 # this will be the full camera resolution in pixels.
00469 uint32 height
00470 uint32 width
00471 
00472 # The distortion model used. Supported models are listed in
00473 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
00474 # simple model of radial and tangential distortion - is sufficent.
00475 string distortion_model
00476 
00477 # The distortion parameters, size depending on the distortion model.
00478 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
00479 float64[] D
00480 
00481 # Intrinsic camera matrix for the raw (distorted) images.
00482 #     [fx  0 cx]
00483 # K = [ 0 fy cy]
00484 #     [ 0  0  1]
00485 # Projects 3D points in the camera coordinate frame to 2D pixel
00486 # coordinates using the focal lengths (fx, fy) and principal point
00487 # (cx, cy).
00488 float64[9]  K # 3x3 row-major matrix
00489 
00490 # Rectification matrix (stereo cameras only)
00491 # A rotation matrix aligning the camera coordinate system to the ideal
00492 # stereo image plane so that epipolar lines in both stereo images are
00493 # parallel.
00494 float64[9]  R # 3x3 row-major matrix
00495 
00496 # Projection/camera matrix
00497 #     [fx'  0  cx' Tx]
00498 # P = [ 0  fy' cy' Ty]
00499 #     [ 0   0   1   0]
00500 # By convention, this matrix specifies the intrinsic (camera) matrix
00501 #  of the processed (rectified) image. That is, the left 3x3 portion
00502 #  is the normal camera intrinsic matrix for the rectified image.
00503 # It projects 3D points in the camera coordinate frame to 2D pixel
00504 #  coordinates using the focal lengths (fx', fy') and principal point
00505 #  (cx', cy') - these may differ from the values in K.
00506 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
00507 #  also have R = the identity and P[1:3,1:3] = K.
00508 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
00509 #  position of the optical center of the second camera in the first
00510 #  camera's frame. We assume Tz = 0 so both cameras are in the same
00511 #  stereo image plane. The first camera always has Tx = Ty = 0. For
00512 #  the right (second) camera of a horizontal stereo pair, Ty = 0 and
00513 #  Tx = -fx' * B, where B is the baseline between the cameras.
00514 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
00515 #  the rectified image is given by:
00516 #  [u v w]' = P * [X Y Z 1]'
00517 #         x = u / w
00518 #         y = v / w
00519 #  This holds for both images of a stereo pair.
00520 float64[12] P # 3x4 row-major matrix
00521 
00522 
00523 #######################################################################
00524 #                      Operational Parameters                         #
00525 #######################################################################
00526 # These define the image region actually captured by the camera       #
00527 # driver. Although they affect the geometry of the output image, they #
00528 # may be changed freely without recalibrating the camera.             #
00529 #######################################################################
00530 
00531 # Binning refers here to any camera setting which combines rectangular
00532 #  neighborhoods of pixels into larger "super-pixels." It reduces the
00533 #  resolution of the output image to
00534 #  (width / binning_x) x (height / binning_y).
00535 # The default values binning_x = binning_y = 0 is considered the same
00536 #  as binning_x = binning_y = 1 (no subsampling).
00537 uint32 binning_x
00538 uint32 binning_y
00539 
00540 # Region of interest (subwindow of full camera resolution), given in
00541 #  full resolution (unbinned) image coordinates. A particular ROI
00542 #  always denotes the same window of pixels on the camera sensor,
00543 #  regardless of binning settings.
00544 # The default setting of roi (all values 0) is considered the same as
00545 #  full resolution (roi.width = width, roi.height = height).
00546 RegionOfInterest roi
00547 
00548 ================================================================================
00549 MSG: sensor_msgs/RegionOfInterest
00550 # This message is used to specify a region of interest within an image.
00551 #
00552 # When used to specify the ROI setting of the camera when the image was
00553 # taken, the height and width fields should either match the height and
00554 # width fields for the associated image; or height = width = 0
00555 # indicates that the full resolution image was captured.
00556 
00557 uint32 x_offset  # Leftmost pixel of the ROI
00558                  # (0 if the ROI includes the left edge of the image)
00559 uint32 y_offset  # Topmost pixel of the ROI
00560                  # (0 if the ROI includes the top edge of the image)
00561 uint32 height    # Height of ROI
00562 uint32 width     # Width of ROI
00563 
00564 # True if a distinct rectified ROI should be calculated from the "raw"
00565 # ROI in this message. Typically this should be False if the full image
00566 # is captured (ROI not used), and True if a subwindow is captured (ROI
00567 # used).
00568 bool do_rectify
00569 
00570 ================================================================================
00571 MSG: geometry_msgs/Vector3
00572 # This represents a vector in free space. 
00573 
00574 float64 x
00575 float64 y
00576 float64 z
00577 ================================================================================
00578 MSG: object_manipulation_msgs/GraspPlanningErrorCode
00579 # Error codes for grasp and place planning
00580 
00581 # plan completed as expected
00582 int32 SUCCESS = 0
00583 
00584 # tf error encountered while transforming
00585 int32 TF_ERROR = 1 
00586 
00587 # some other error
00588 int32 OTHER_ERROR = 2
00589 
00590 # the actual value of this error code
00591 int32 value
00592 ================================================================================
00593 MSG: pr2_grasp_adjust/GraspAdjustActionFeedback
00594 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00595 
00596 Header header
00597 actionlib_msgs/GoalStatus status
00598 GraspAdjustFeedback feedback
00599 
00600 ================================================================================
00601 MSG: pr2_grasp_adjust/GraspAdjustFeedback
00602 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00603 #feedback
00604 
00605 
00606 
00607 """
00608   __slots__ = ['action_goal','action_result','action_feedback']
00609   _slot_types = ['pr2_grasp_adjust/GraspAdjustActionGoal','pr2_grasp_adjust/GraspAdjustActionResult','pr2_grasp_adjust/GraspAdjustActionFeedback']
00610 
00611   def __init__(self, *args, **kwds):
00612     """
00613     Constructor. Any message fields that are implicitly/explicitly
00614     set to None will be assigned a default value. The recommend
00615     use is keyword arguments as this is more robust to future message
00616     changes.  You cannot mix in-order arguments and keyword arguments.
00617 
00618     The available fields are:
00619        action_goal,action_result,action_feedback
00620 
00621     :param args: complete set of field values, in .msg order
00622     :param kwds: use keyword arguments corresponding to message field names
00623     to set specific fields.
00624     """
00625     if args or kwds:
00626       super(GraspAdjustAction, self).__init__(*args, **kwds)
00627       #message fields cannot be None, assign default values for those that are
00628       if self.action_goal is None:
00629         self.action_goal = pr2_grasp_adjust.msg.GraspAdjustActionGoal()
00630       if self.action_result is None:
00631         self.action_result = pr2_grasp_adjust.msg.GraspAdjustActionResult()
00632       if self.action_feedback is None:
00633         self.action_feedback = pr2_grasp_adjust.msg.GraspAdjustActionFeedback()
00634     else:
00635       self.action_goal = pr2_grasp_adjust.msg.GraspAdjustActionGoal()
00636       self.action_result = pr2_grasp_adjust.msg.GraspAdjustActionResult()
00637       self.action_feedback = pr2_grasp_adjust.msg.GraspAdjustActionFeedback()
00638 
00639   def _get_types(self):
00640     """
00641     internal API method
00642     """
00643     return self._slot_types
00644 
00645   def serialize(self, buff):
00646     """
00647     serialize message into buffer
00648     :param buff: buffer, ``StringIO``
00649     """
00650     try:
00651       _x = self
00652       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00653       _x = self.action_goal.header.frame_id
00654       length = len(_x)
00655       if python3 or type(_x) == unicode:
00656         _x = _x.encode('utf-8')
00657         length = len(_x)
00658       buff.write(struct.pack('<I%ss'%length, length, _x))
00659       _x = self
00660       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00661       _x = self.action_goal.goal_id.id
00662       length = len(_x)
00663       if python3 or type(_x) == unicode:
00664         _x = _x.encode('utf-8')
00665         length = len(_x)
00666       buff.write(struct.pack('<I%ss'%length, length, _x))
00667       _x = self
00668       buff.write(_struct_3I.pack(_x.action_goal.goal.cloud.header.seq, _x.action_goal.goal.cloud.header.stamp.secs, _x.action_goal.goal.cloud.header.stamp.nsecs))
00669       _x = self.action_goal.goal.cloud.header.frame_id
00670       length = len(_x)
00671       if python3 or type(_x) == unicode:
00672         _x = _x.encode('utf-8')
00673         length = len(_x)
00674       buff.write(struct.pack('<I%ss'%length, length, _x))
00675       _x = self
00676       buff.write(_struct_2I.pack(_x.action_goal.goal.cloud.height, _x.action_goal.goal.cloud.width))
00677       length = len(self.action_goal.goal.cloud.fields)
00678       buff.write(_struct_I.pack(length))
00679       for val1 in self.action_goal.goal.cloud.fields:
00680         _x = val1.name
00681         length = len(_x)
00682         if python3 or type(_x) == unicode:
00683           _x = _x.encode('utf-8')
00684           length = len(_x)
00685         buff.write(struct.pack('<I%ss'%length, length, _x))
00686         _x = val1
00687         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00688       _x = self
00689       buff.write(_struct_B2I.pack(_x.action_goal.goal.cloud.is_bigendian, _x.action_goal.goal.cloud.point_step, _x.action_goal.goal.cloud.row_step))
00690       _x = self.action_goal.goal.cloud.data
00691       length = len(_x)
00692       # - if encoded as a list instead, serialize as bytes instead of string
00693       if type(_x) in [list, tuple]:
00694         buff.write(struct.pack('<I%sB'%length, length, *_x))
00695       else:
00696         buff.write(struct.pack('<I%ss'%length, length, _x))
00697       _x = self
00698       buff.write(_struct_B3I.pack(_x.action_goal.goal.cloud.is_dense, _x.action_goal.goal.pose_stamped.header.seq, _x.action_goal.goal.pose_stamped.header.stamp.secs, _x.action_goal.goal.pose_stamped.header.stamp.nsecs))
00699       _x = self.action_goal.goal.pose_stamped.header.frame_id
00700       length = len(_x)
00701       if python3 or type(_x) == unicode:
00702         _x = _x.encode('utf-8')
00703         length = len(_x)
00704       buff.write(struct.pack('<I%ss'%length, length, _x))
00705       _x = self
00706       buff.write(_struct_7dBiB3I.pack(_x.action_goal.goal.pose_stamped.pose.position.x, _x.action_goal.goal.pose_stamped.pose.position.y, _x.action_goal.goal.pose_stamped.pose.position.z, _x.action_goal.goal.pose_stamped.pose.orientation.x, _x.action_goal.goal.pose_stamped.pose.orientation.y, _x.action_goal.goal.pose_stamped.pose.orientation.z, _x.action_goal.goal.pose_stamped.pose.orientation.w, _x.action_goal.goal.use_orientation, _x.action_goal.goal.seed_index, _x.action_goal.goal.search_mode, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00707       _x = self.action_result.header.frame_id
00708       length = len(_x)
00709       if python3 or type(_x) == unicode:
00710         _x = _x.encode('utf-8')
00711         length = len(_x)
00712       buff.write(struct.pack('<I%ss'%length, length, _x))
00713       _x = self
00714       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00715       _x = self.action_result.status.goal_id.id
00716       length = len(_x)
00717       if python3 or type(_x) == unicode:
00718         _x = _x.encode('utf-8')
00719         length = len(_x)
00720       buff.write(struct.pack('<I%ss'%length, length, _x))
00721       buff.write(_struct_B.pack(self.action_result.status.status))
00722       _x = self.action_result.status.text
00723       length = len(_x)
00724       if python3 or type(_x) == unicode:
00725         _x = _x.encode('utf-8')
00726         length = len(_x)
00727       buff.write(struct.pack('<I%ss'%length, length, _x))
00728       length = len(self.action_result.result.grasps)
00729       buff.write(_struct_I.pack(length))
00730       for val1 in self.action_result.result.grasps:
00731         _v1 = val1.pre_grasp_posture
00732         _v2 = _v1.header
00733         buff.write(_struct_I.pack(_v2.seq))
00734         _v3 = _v2.stamp
00735         _x = _v3
00736         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00737         _x = _v2.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         length = len(_v1.name)
00744         buff.write(_struct_I.pack(length))
00745         for val3 in _v1.name:
00746           length = len(val3)
00747           if python3 or type(val3) == unicode:
00748             val3 = val3.encode('utf-8')
00749             length = len(val3)
00750           buff.write(struct.pack('<I%ss'%length, length, val3))
00751         length = len(_v1.position)
00752         buff.write(_struct_I.pack(length))
00753         pattern = '<%sd'%length
00754         buff.write(struct.pack(pattern, *_v1.position))
00755         length = len(_v1.velocity)
00756         buff.write(_struct_I.pack(length))
00757         pattern = '<%sd'%length
00758         buff.write(struct.pack(pattern, *_v1.velocity))
00759         length = len(_v1.effort)
00760         buff.write(_struct_I.pack(length))
00761         pattern = '<%sd'%length
00762         buff.write(struct.pack(pattern, *_v1.effort))
00763         _v4 = val1.grasp_posture
00764         _v5 = _v4.header
00765         buff.write(_struct_I.pack(_v5.seq))
00766         _v6 = _v5.stamp
00767         _x = _v6
00768         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00769         _x = _v5.frame_id
00770         length = len(_x)
00771         if python3 or type(_x) == unicode:
00772           _x = _x.encode('utf-8')
00773           length = len(_x)
00774         buff.write(struct.pack('<I%ss'%length, length, _x))
00775         length = len(_v4.name)
00776         buff.write(_struct_I.pack(length))
00777         for val3 in _v4.name:
00778           length = len(val3)
00779           if python3 or type(val3) == unicode:
00780             val3 = val3.encode('utf-8')
00781             length = len(val3)
00782           buff.write(struct.pack('<I%ss'%length, length, val3))
00783         length = len(_v4.position)
00784         buff.write(_struct_I.pack(length))
00785         pattern = '<%sd'%length
00786         buff.write(struct.pack(pattern, *_v4.position))
00787         length = len(_v4.velocity)
00788         buff.write(_struct_I.pack(length))
00789         pattern = '<%sd'%length
00790         buff.write(struct.pack(pattern, *_v4.velocity))
00791         length = len(_v4.effort)
00792         buff.write(_struct_I.pack(length))
00793         pattern = '<%sd'%length
00794         buff.write(struct.pack(pattern, *_v4.effort))
00795         _v7 = val1.grasp_pose
00796         _v8 = _v7.position
00797         _x = _v8
00798         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00799         _v9 = _v7.orientation
00800         _x = _v9
00801         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00802         _x = val1
00803         buff.write(_struct_dB2f.pack(_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance))
00804         length = len(val1.moved_obstacles)
00805         buff.write(_struct_I.pack(length))
00806         for val2 in val1.moved_obstacles:
00807           _x = val2.reference_frame_id
00808           length = len(_x)
00809           if python3 or type(_x) == unicode:
00810             _x = _x.encode('utf-8')
00811             length = len(_x)
00812           buff.write(struct.pack('<I%ss'%length, length, _x))
00813           length = len(val2.potential_models)
00814           buff.write(_struct_I.pack(length))
00815           for val3 in val2.potential_models:
00816             buff.write(_struct_i.pack(val3.model_id))
00817             _v10 = val3.pose
00818             _v11 = _v10.header
00819             buff.write(_struct_I.pack(_v11.seq))
00820             _v12 = _v11.stamp
00821             _x = _v12
00822             buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00823             _x = _v11.frame_id
00824             length = len(_x)
00825             if python3 or type(_x) == unicode:
00826               _x = _x.encode('utf-8')
00827               length = len(_x)
00828             buff.write(struct.pack('<I%ss'%length, length, _x))
00829             _v13 = _v10.pose
00830             _v14 = _v13.position
00831             _x = _v14
00832             buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00833             _v15 = _v13.orientation
00834             _x = _v15
00835             buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00836             buff.write(_struct_f.pack(val3.confidence))
00837             _x = val3.detector_name
00838             length = len(_x)
00839             if python3 or type(_x) == unicode:
00840               _x = _x.encode('utf-8')
00841               length = len(_x)
00842             buff.write(struct.pack('<I%ss'%length, length, _x))
00843           _v16 = val2.cluster
00844           _v17 = _v16.header
00845           buff.write(_struct_I.pack(_v17.seq))
00846           _v18 = _v17.stamp
00847           _x = _v18
00848           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00849           _x = _v17.frame_id
00850           length = len(_x)
00851           if python3 or type(_x) == unicode:
00852             _x = _x.encode('utf-8')
00853             length = len(_x)
00854           buff.write(struct.pack('<I%ss'%length, length, _x))
00855           length = len(_v16.points)
00856           buff.write(_struct_I.pack(length))
00857           for val4 in _v16.points:
00858             _x = val4
00859             buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00860           length = len(_v16.channels)
00861           buff.write(_struct_I.pack(length))
00862           for val4 in _v16.channels:
00863             _x = val4.name
00864             length = len(_x)
00865             if python3 or type(_x) == unicode:
00866               _x = _x.encode('utf-8')
00867               length = len(_x)
00868             buff.write(struct.pack('<I%ss'%length, length, _x))
00869             length = len(val4.values)
00870             buff.write(_struct_I.pack(length))
00871             pattern = '<%sf'%length
00872             buff.write(struct.pack(pattern, *val4.values))
00873           _v19 = val2.region
00874           _v20 = _v19.cloud
00875           _v21 = _v20.header
00876           buff.write(_struct_I.pack(_v21.seq))
00877           _v22 = _v21.stamp
00878           _x = _v22
00879           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00880           _x = _v21.frame_id
00881           length = len(_x)
00882           if python3 or type(_x) == unicode:
00883             _x = _x.encode('utf-8')
00884             length = len(_x)
00885           buff.write(struct.pack('<I%ss'%length, length, _x))
00886           _x = _v20
00887           buff.write(_struct_2I.pack(_x.height, _x.width))
00888           length = len(_v20.fields)
00889           buff.write(_struct_I.pack(length))
00890           for val5 in _v20.fields:
00891             _x = val5.name
00892             length = len(_x)
00893             if python3 or type(_x) == unicode:
00894               _x = _x.encode('utf-8')
00895               length = len(_x)
00896             buff.write(struct.pack('<I%ss'%length, length, _x))
00897             _x = val5
00898             buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00899           _x = _v20
00900           buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
00901           _x = _v20.data
00902           length = len(_x)
00903           # - if encoded as a list instead, serialize as bytes instead of string
00904           if type(_x) in [list, tuple]:
00905             buff.write(struct.pack('<I%sB'%length, length, *_x))
00906           else:
00907             buff.write(struct.pack('<I%ss'%length, length, _x))
00908           buff.write(_struct_B.pack(_v20.is_dense))
00909           length = len(_v19.mask)
00910           buff.write(_struct_I.pack(length))
00911           pattern = '<%si'%length
00912           buff.write(struct.pack(pattern, *_v19.mask))
00913           _v23 = _v19.image
00914           _v24 = _v23.header
00915           buff.write(_struct_I.pack(_v24.seq))
00916           _v25 = _v24.stamp
00917           _x = _v25
00918           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00919           _x = _v24.frame_id
00920           length = len(_x)
00921           if python3 or type(_x) == unicode:
00922             _x = _x.encode('utf-8')
00923             length = len(_x)
00924           buff.write(struct.pack('<I%ss'%length, length, _x))
00925           _x = _v23
00926           buff.write(_struct_2I.pack(_x.height, _x.width))
00927           _x = _v23.encoding
00928           length = len(_x)
00929           if python3 or type(_x) == unicode:
00930             _x = _x.encode('utf-8')
00931             length = len(_x)
00932           buff.write(struct.pack('<I%ss'%length, length, _x))
00933           _x = _v23
00934           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
00935           _x = _v23.data
00936           length = len(_x)
00937           # - if encoded as a list instead, serialize as bytes instead of string
00938           if type(_x) in [list, tuple]:
00939             buff.write(struct.pack('<I%sB'%length, length, *_x))
00940           else:
00941             buff.write(struct.pack('<I%ss'%length, length, _x))
00942           _v26 = _v19.disparity_image
00943           _v27 = _v26.header
00944           buff.write(_struct_I.pack(_v27.seq))
00945           _v28 = _v27.stamp
00946           _x = _v28
00947           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00948           _x = _v27.frame_id
00949           length = len(_x)
00950           if python3 or type(_x) == unicode:
00951             _x = _x.encode('utf-8')
00952             length = len(_x)
00953           buff.write(struct.pack('<I%ss'%length, length, _x))
00954           _x = _v26
00955           buff.write(_struct_2I.pack(_x.height, _x.width))
00956           _x = _v26.encoding
00957           length = len(_x)
00958           if python3 or type(_x) == unicode:
00959             _x = _x.encode('utf-8')
00960             length = len(_x)
00961           buff.write(struct.pack('<I%ss'%length, length, _x))
00962           _x = _v26
00963           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
00964           _x = _v26.data
00965           length = len(_x)
00966           # - if encoded as a list instead, serialize as bytes instead of string
00967           if type(_x) in [list, tuple]:
00968             buff.write(struct.pack('<I%sB'%length, length, *_x))
00969           else:
00970             buff.write(struct.pack('<I%ss'%length, length, _x))
00971           _v29 = _v19.cam_info
00972           _v30 = _v29.header
00973           buff.write(_struct_I.pack(_v30.seq))
00974           _v31 = _v30.stamp
00975           _x = _v31
00976           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00977           _x = _v30.frame_id
00978           length = len(_x)
00979           if python3 or type(_x) == unicode:
00980             _x = _x.encode('utf-8')
00981             length = len(_x)
00982           buff.write(struct.pack('<I%ss'%length, length, _x))
00983           _x = _v29
00984           buff.write(_struct_2I.pack(_x.height, _x.width))
00985           _x = _v29.distortion_model
00986           length = len(_x)
00987           if python3 or type(_x) == unicode:
00988             _x = _x.encode('utf-8')
00989             length = len(_x)
00990           buff.write(struct.pack('<I%ss'%length, length, _x))
00991           length = len(_v29.D)
00992           buff.write(_struct_I.pack(length))
00993           pattern = '<%sd'%length
00994           buff.write(struct.pack(pattern, *_v29.D))
00995           buff.write(_struct_9d.pack(*_v29.K))
00996           buff.write(_struct_9d.pack(*_v29.R))
00997           buff.write(_struct_12d.pack(*_v29.P))
00998           _x = _v29
00999           buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
01000           _v32 = _v29.roi
01001           _x = _v32
01002           buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
01003           _v33 = _v19.roi_box_pose
01004           _v34 = _v33.header
01005           buff.write(_struct_I.pack(_v34.seq))
01006           _v35 = _v34.stamp
01007           _x = _v35
01008           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01009           _x = _v34.frame_id
01010           length = len(_x)
01011           if python3 or type(_x) == unicode:
01012             _x = _x.encode('utf-8')
01013             length = len(_x)
01014           buff.write(struct.pack('<I%ss'%length, length, _x))
01015           _v36 = _v33.pose
01016           _v37 = _v36.position
01017           _x = _v37
01018           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01019           _v38 = _v36.orientation
01020           _x = _v38
01021           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01022           _v39 = _v19.roi_box_dims
01023           _x = _v39
01024           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01025           _x = val2.collision_name
01026           length = len(_x)
01027           if python3 or type(_x) == unicode:
01028             _x = _x.encode('utf-8')
01029             length = len(_x)
01030           buff.write(struct.pack('<I%ss'%length, length, _x))
01031       _x = self
01032       buff.write(_struct_i3I.pack(_x.action_result.result.result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
01033       _x = self.action_feedback.header.frame_id
01034       length = len(_x)
01035       if python3 or type(_x) == unicode:
01036         _x = _x.encode('utf-8')
01037         length = len(_x)
01038       buff.write(struct.pack('<I%ss'%length, length, _x))
01039       _x = self
01040       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
01041       _x = self.action_feedback.status.goal_id.id
01042       length = len(_x)
01043       if python3 or type(_x) == unicode:
01044         _x = _x.encode('utf-8')
01045         length = len(_x)
01046       buff.write(struct.pack('<I%ss'%length, length, _x))
01047       buff.write(_struct_B.pack(self.action_feedback.status.status))
01048       _x = self.action_feedback.status.text
01049       length = len(_x)
01050       if python3 or type(_x) == unicode:
01051         _x = _x.encode('utf-8')
01052         length = len(_x)
01053       buff.write(struct.pack('<I%ss'%length, length, _x))
01054     except struct.error as se: self._check_types(se)
01055     except TypeError as te: self._check_types(te)
01056 
01057   def deserialize(self, str):
01058     """
01059     unpack serialized message in str into this message instance
01060     :param str: byte array of serialized message, ``str``
01061     """
01062     try:
01063       if self.action_goal is None:
01064         self.action_goal = pr2_grasp_adjust.msg.GraspAdjustActionGoal()
01065       if self.action_result is None:
01066         self.action_result = pr2_grasp_adjust.msg.GraspAdjustActionResult()
01067       if self.action_feedback is None:
01068         self.action_feedback = pr2_grasp_adjust.msg.GraspAdjustActionFeedback()
01069       end = 0
01070       _x = self
01071       start = end
01072       end += 12
01073       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01074       start = end
01075       end += 4
01076       (length,) = _struct_I.unpack(str[start:end])
01077       start = end
01078       end += length
01079       if python3:
01080         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
01081       else:
01082         self.action_goal.header.frame_id = str[start:end]
01083       _x = self
01084       start = end
01085       end += 8
01086       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01087       start = end
01088       end += 4
01089       (length,) = _struct_I.unpack(str[start:end])
01090       start = end
01091       end += length
01092       if python3:
01093         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
01094       else:
01095         self.action_goal.goal_id.id = str[start:end]
01096       _x = self
01097       start = end
01098       end += 12
01099       (_x.action_goal.goal.cloud.header.seq, _x.action_goal.goal.cloud.header.stamp.secs, _x.action_goal.goal.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01100       start = end
01101       end += 4
01102       (length,) = _struct_I.unpack(str[start:end])
01103       start = end
01104       end += length
01105       if python3:
01106         self.action_goal.goal.cloud.header.frame_id = str[start:end].decode('utf-8')
01107       else:
01108         self.action_goal.goal.cloud.header.frame_id = str[start:end]
01109       _x = self
01110       start = end
01111       end += 8
01112       (_x.action_goal.goal.cloud.height, _x.action_goal.goal.cloud.width,) = _struct_2I.unpack(str[start:end])
01113       start = end
01114       end += 4
01115       (length,) = _struct_I.unpack(str[start:end])
01116       self.action_goal.goal.cloud.fields = []
01117       for i in range(0, length):
01118         val1 = sensor_msgs.msg.PointField()
01119         start = end
01120         end += 4
01121         (length,) = _struct_I.unpack(str[start:end])
01122         start = end
01123         end += length
01124         if python3:
01125           val1.name = str[start:end].decode('utf-8')
01126         else:
01127           val1.name = str[start:end]
01128         _x = val1
01129         start = end
01130         end += 9
01131         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01132         self.action_goal.goal.cloud.fields.append(val1)
01133       _x = self
01134       start = end
01135       end += 9
01136       (_x.action_goal.goal.cloud.is_bigendian, _x.action_goal.goal.cloud.point_step, _x.action_goal.goal.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
01137       self.action_goal.goal.cloud.is_bigendian = bool(self.action_goal.goal.cloud.is_bigendian)
01138       start = end
01139       end += 4
01140       (length,) = _struct_I.unpack(str[start:end])
01141       start = end
01142       end += length
01143       if python3:
01144         self.action_goal.goal.cloud.data = str[start:end].decode('utf-8')
01145       else:
01146         self.action_goal.goal.cloud.data = str[start:end]
01147       _x = self
01148       start = end
01149       end += 13
01150       (_x.action_goal.goal.cloud.is_dense, _x.action_goal.goal.pose_stamped.header.seq, _x.action_goal.goal.pose_stamped.header.stamp.secs, _x.action_goal.goal.pose_stamped.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
01151       self.action_goal.goal.cloud.is_dense = bool(self.action_goal.goal.cloud.is_dense)
01152       start = end
01153       end += 4
01154       (length,) = _struct_I.unpack(str[start:end])
01155       start = end
01156       end += length
01157       if python3:
01158         self.action_goal.goal.pose_stamped.header.frame_id = str[start:end].decode('utf-8')
01159       else:
01160         self.action_goal.goal.pose_stamped.header.frame_id = str[start:end]
01161       _x = self
01162       start = end
01163       end += 74
01164       (_x.action_goal.goal.pose_stamped.pose.position.x, _x.action_goal.goal.pose_stamped.pose.position.y, _x.action_goal.goal.pose_stamped.pose.position.z, _x.action_goal.goal.pose_stamped.pose.orientation.x, _x.action_goal.goal.pose_stamped.pose.orientation.y, _x.action_goal.goal.pose_stamped.pose.orientation.z, _x.action_goal.goal.pose_stamped.pose.orientation.w, _x.action_goal.goal.use_orientation, _x.action_goal.goal.seed_index, _x.action_goal.goal.search_mode, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_7dBiB3I.unpack(str[start:end])
01165       self.action_goal.goal.use_orientation = bool(self.action_goal.goal.use_orientation)
01166       start = end
01167       end += 4
01168       (length,) = _struct_I.unpack(str[start:end])
01169       start = end
01170       end += length
01171       if python3:
01172         self.action_result.header.frame_id = str[start:end].decode('utf-8')
01173       else:
01174         self.action_result.header.frame_id = str[start:end]
01175       _x = self
01176       start = end
01177       end += 8
01178       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01179       start = end
01180       end += 4
01181       (length,) = _struct_I.unpack(str[start:end])
01182       start = end
01183       end += length
01184       if python3:
01185         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
01186       else:
01187         self.action_result.status.goal_id.id = str[start:end]
01188       start = end
01189       end += 1
01190       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
01191       start = end
01192       end += 4
01193       (length,) = _struct_I.unpack(str[start:end])
01194       start = end
01195       end += length
01196       if python3:
01197         self.action_result.status.text = str[start:end].decode('utf-8')
01198       else:
01199         self.action_result.status.text = str[start:end]
01200       start = end
01201       end += 4
01202       (length,) = _struct_I.unpack(str[start:end])
01203       self.action_result.result.grasps = []
01204       for i in range(0, length):
01205         val1 = object_manipulation_msgs.msg.Grasp()
01206         _v40 = val1.pre_grasp_posture
01207         _v41 = _v40.header
01208         start = end
01209         end += 4
01210         (_v41.seq,) = _struct_I.unpack(str[start:end])
01211         _v42 = _v41.stamp
01212         _x = _v42
01213         start = end
01214         end += 8
01215         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01216         start = end
01217         end += 4
01218         (length,) = _struct_I.unpack(str[start:end])
01219         start = end
01220         end += length
01221         if python3:
01222           _v41.frame_id = str[start:end].decode('utf-8')
01223         else:
01224           _v41.frame_id = str[start:end]
01225         start = end
01226         end += 4
01227         (length,) = _struct_I.unpack(str[start:end])
01228         _v40.name = []
01229         for i in range(0, length):
01230           start = end
01231           end += 4
01232           (length,) = _struct_I.unpack(str[start:end])
01233           start = end
01234           end += length
01235           if python3:
01236             val3 = str[start:end].decode('utf-8')
01237           else:
01238             val3 = str[start:end]
01239           _v40.name.append(val3)
01240         start = end
01241         end += 4
01242         (length,) = _struct_I.unpack(str[start:end])
01243         pattern = '<%sd'%length
01244         start = end
01245         end += struct.calcsize(pattern)
01246         _v40.position = struct.unpack(pattern, str[start:end])
01247         start = end
01248         end += 4
01249         (length,) = _struct_I.unpack(str[start:end])
01250         pattern = '<%sd'%length
01251         start = end
01252         end += struct.calcsize(pattern)
01253         _v40.velocity = struct.unpack(pattern, str[start:end])
01254         start = end
01255         end += 4
01256         (length,) = _struct_I.unpack(str[start:end])
01257         pattern = '<%sd'%length
01258         start = end
01259         end += struct.calcsize(pattern)
01260         _v40.effort = struct.unpack(pattern, str[start:end])
01261         _v43 = val1.grasp_posture
01262         _v44 = _v43.header
01263         start = end
01264         end += 4
01265         (_v44.seq,) = _struct_I.unpack(str[start:end])
01266         _v45 = _v44.stamp
01267         _x = _v45
01268         start = end
01269         end += 8
01270         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01271         start = end
01272         end += 4
01273         (length,) = _struct_I.unpack(str[start:end])
01274         start = end
01275         end += length
01276         if python3:
01277           _v44.frame_id = str[start:end].decode('utf-8')
01278         else:
01279           _v44.frame_id = str[start:end]
01280         start = end
01281         end += 4
01282         (length,) = _struct_I.unpack(str[start:end])
01283         _v43.name = []
01284         for i in range(0, length):
01285           start = end
01286           end += 4
01287           (length,) = _struct_I.unpack(str[start:end])
01288           start = end
01289           end += length
01290           if python3:
01291             val3 = str[start:end].decode('utf-8')
01292           else:
01293             val3 = str[start:end]
01294           _v43.name.append(val3)
01295         start = end
01296         end += 4
01297         (length,) = _struct_I.unpack(str[start:end])
01298         pattern = '<%sd'%length
01299         start = end
01300         end += struct.calcsize(pattern)
01301         _v43.position = struct.unpack(pattern, str[start:end])
01302         start = end
01303         end += 4
01304         (length,) = _struct_I.unpack(str[start:end])
01305         pattern = '<%sd'%length
01306         start = end
01307         end += struct.calcsize(pattern)
01308         _v43.velocity = struct.unpack(pattern, str[start:end])
01309         start = end
01310         end += 4
01311         (length,) = _struct_I.unpack(str[start:end])
01312         pattern = '<%sd'%length
01313         start = end
01314         end += struct.calcsize(pattern)
01315         _v43.effort = struct.unpack(pattern, str[start:end])
01316         _v46 = val1.grasp_pose
01317         _v47 = _v46.position
01318         _x = _v47
01319         start = end
01320         end += 24
01321         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01322         _v48 = _v46.orientation
01323         _x = _v48
01324         start = end
01325         end += 32
01326         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01327         _x = val1
01328         start = end
01329         end += 17
01330         (_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance,) = _struct_dB2f.unpack(str[start:end])
01331         val1.cluster_rep = bool(val1.cluster_rep)
01332         start = end
01333         end += 4
01334         (length,) = _struct_I.unpack(str[start:end])
01335         val1.moved_obstacles = []
01336         for i in range(0, length):
01337           val2 = object_manipulation_msgs.msg.GraspableObject()
01338           start = end
01339           end += 4
01340           (length,) = _struct_I.unpack(str[start:end])
01341           start = end
01342           end += length
01343           if python3:
01344             val2.reference_frame_id = str[start:end].decode('utf-8')
01345           else:
01346             val2.reference_frame_id = str[start:end]
01347           start = end
01348           end += 4
01349           (length,) = _struct_I.unpack(str[start:end])
01350           val2.potential_models = []
01351           for i in range(0, length):
01352             val3 = household_objects_database_msgs.msg.DatabaseModelPose()
01353             start = end
01354             end += 4
01355             (val3.model_id,) = _struct_i.unpack(str[start:end])
01356             _v49 = val3.pose
01357             _v50 = _v49.header
01358             start = end
01359             end += 4
01360             (_v50.seq,) = _struct_I.unpack(str[start:end])
01361             _v51 = _v50.stamp
01362             _x = _v51
01363             start = end
01364             end += 8
01365             (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01366             start = end
01367             end += 4
01368             (length,) = _struct_I.unpack(str[start:end])
01369             start = end
01370             end += length
01371             if python3:
01372               _v50.frame_id = str[start:end].decode('utf-8')
01373             else:
01374               _v50.frame_id = str[start:end]
01375             _v52 = _v49.pose
01376             _v53 = _v52.position
01377             _x = _v53
01378             start = end
01379             end += 24
01380             (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01381             _v54 = _v52.orientation
01382             _x = _v54
01383             start = end
01384             end += 32
01385             (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01386             start = end
01387             end += 4
01388             (val3.confidence,) = _struct_f.unpack(str[start:end])
01389             start = end
01390             end += 4
01391             (length,) = _struct_I.unpack(str[start:end])
01392             start = end
01393             end += length
01394             if python3:
01395               val3.detector_name = str[start:end].decode('utf-8')
01396             else:
01397               val3.detector_name = str[start:end]
01398             val2.potential_models.append(val3)
01399           _v55 = val2.cluster
01400           _v56 = _v55.header
01401           start = end
01402           end += 4
01403           (_v56.seq,) = _struct_I.unpack(str[start:end])
01404           _v57 = _v56.stamp
01405           _x = _v57
01406           start = end
01407           end += 8
01408           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01409           start = end
01410           end += 4
01411           (length,) = _struct_I.unpack(str[start:end])
01412           start = end
01413           end += length
01414           if python3:
01415             _v56.frame_id = str[start:end].decode('utf-8')
01416           else:
01417             _v56.frame_id = str[start:end]
01418           start = end
01419           end += 4
01420           (length,) = _struct_I.unpack(str[start:end])
01421           _v55.points = []
01422           for i in range(0, length):
01423             val4 = geometry_msgs.msg.Point32()
01424             _x = val4
01425             start = end
01426             end += 12
01427             (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01428             _v55.points.append(val4)
01429           start = end
01430           end += 4
01431           (length,) = _struct_I.unpack(str[start:end])
01432           _v55.channels = []
01433           for i in range(0, length):
01434             val4 = sensor_msgs.msg.ChannelFloat32()
01435             start = end
01436             end += 4
01437             (length,) = _struct_I.unpack(str[start:end])
01438             start = end
01439             end += length
01440             if python3:
01441               val4.name = str[start:end].decode('utf-8')
01442             else:
01443               val4.name = str[start:end]
01444             start = end
01445             end += 4
01446             (length,) = _struct_I.unpack(str[start:end])
01447             pattern = '<%sf'%length
01448             start = end
01449             end += struct.calcsize(pattern)
01450             val4.values = struct.unpack(pattern, str[start:end])
01451             _v55.channels.append(val4)
01452           _v58 = val2.region
01453           _v59 = _v58.cloud
01454           _v60 = _v59.header
01455           start = end
01456           end += 4
01457           (_v60.seq,) = _struct_I.unpack(str[start:end])
01458           _v61 = _v60.stamp
01459           _x = _v61
01460           start = end
01461           end += 8
01462           (_x.secs, _x.nsecs,) = _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             _v60.frame_id = str[start:end].decode('utf-8')
01470           else:
01471             _v60.frame_id = str[start:end]
01472           _x = _v59
01473           start = end
01474           end += 8
01475           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01476           start = end
01477           end += 4
01478           (length,) = _struct_I.unpack(str[start:end])
01479           _v59.fields = []
01480           for i in range(0, length):
01481             val5 = sensor_msgs.msg.PointField()
01482             start = end
01483             end += 4
01484             (length,) = _struct_I.unpack(str[start:end])
01485             start = end
01486             end += length
01487             if python3:
01488               val5.name = str[start:end].decode('utf-8')
01489             else:
01490               val5.name = str[start:end]
01491             _x = val5
01492             start = end
01493             end += 9
01494             (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01495             _v59.fields.append(val5)
01496           _x = _v59
01497           start = end
01498           end += 9
01499           (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
01500           _v59.is_bigendian = bool(_v59.is_bigendian)
01501           start = end
01502           end += 4
01503           (length,) = _struct_I.unpack(str[start:end])
01504           start = end
01505           end += length
01506           if python3:
01507             _v59.data = str[start:end].decode('utf-8')
01508           else:
01509             _v59.data = str[start:end]
01510           start = end
01511           end += 1
01512           (_v59.is_dense,) = _struct_B.unpack(str[start:end])
01513           _v59.is_dense = bool(_v59.is_dense)
01514           start = end
01515           end += 4
01516           (length,) = _struct_I.unpack(str[start:end])
01517           pattern = '<%si'%length
01518           start = end
01519           end += struct.calcsize(pattern)
01520           _v58.mask = struct.unpack(pattern, str[start:end])
01521           _v62 = _v58.image
01522           _v63 = _v62.header
01523           start = end
01524           end += 4
01525           (_v63.seq,) = _struct_I.unpack(str[start:end])
01526           _v64 = _v63.stamp
01527           _x = _v64
01528           start = end
01529           end += 8
01530           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01531           start = end
01532           end += 4
01533           (length,) = _struct_I.unpack(str[start:end])
01534           start = end
01535           end += length
01536           if python3:
01537             _v63.frame_id = str[start:end].decode('utf-8')
01538           else:
01539             _v63.frame_id = str[start:end]
01540           _x = _v62
01541           start = end
01542           end += 8
01543           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01544           start = end
01545           end += 4
01546           (length,) = _struct_I.unpack(str[start:end])
01547           start = end
01548           end += length
01549           if python3:
01550             _v62.encoding = str[start:end].decode('utf-8')
01551           else:
01552             _v62.encoding = str[start:end]
01553           _x = _v62
01554           start = end
01555           end += 5
01556           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
01557           start = end
01558           end += 4
01559           (length,) = _struct_I.unpack(str[start:end])
01560           start = end
01561           end += length
01562           if python3:
01563             _v62.data = str[start:end].decode('utf-8')
01564           else:
01565             _v62.data = str[start:end]
01566           _v65 = _v58.disparity_image
01567           _v66 = _v65.header
01568           start = end
01569           end += 4
01570           (_v66.seq,) = _struct_I.unpack(str[start:end])
01571           _v67 = _v66.stamp
01572           _x = _v67
01573           start = end
01574           end += 8
01575           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01576           start = end
01577           end += 4
01578           (length,) = _struct_I.unpack(str[start:end])
01579           start = end
01580           end += length
01581           if python3:
01582             _v66.frame_id = str[start:end].decode('utf-8')
01583           else:
01584             _v66.frame_id = str[start:end]
01585           _x = _v65
01586           start = end
01587           end += 8
01588           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01589           start = end
01590           end += 4
01591           (length,) = _struct_I.unpack(str[start:end])
01592           start = end
01593           end += length
01594           if python3:
01595             _v65.encoding = str[start:end].decode('utf-8')
01596           else:
01597             _v65.encoding = str[start:end]
01598           _x = _v65
01599           start = end
01600           end += 5
01601           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
01602           start = end
01603           end += 4
01604           (length,) = _struct_I.unpack(str[start:end])
01605           start = end
01606           end += length
01607           if python3:
01608             _v65.data = str[start:end].decode('utf-8')
01609           else:
01610             _v65.data = str[start:end]
01611           _v68 = _v58.cam_info
01612           _v69 = _v68.header
01613           start = end
01614           end += 4
01615           (_v69.seq,) = _struct_I.unpack(str[start:end])
01616           _v70 = _v69.stamp
01617           _x = _v70
01618           start = end
01619           end += 8
01620           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01621           start = end
01622           end += 4
01623           (length,) = _struct_I.unpack(str[start:end])
01624           start = end
01625           end += length
01626           if python3:
01627             _v69.frame_id = str[start:end].decode('utf-8')
01628           else:
01629             _v69.frame_id = str[start:end]
01630           _x = _v68
01631           start = end
01632           end += 8
01633           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01634           start = end
01635           end += 4
01636           (length,) = _struct_I.unpack(str[start:end])
01637           start = end
01638           end += length
01639           if python3:
01640             _v68.distortion_model = str[start:end].decode('utf-8')
01641           else:
01642             _v68.distortion_model = str[start:end]
01643           start = end
01644           end += 4
01645           (length,) = _struct_I.unpack(str[start:end])
01646           pattern = '<%sd'%length
01647           start = end
01648           end += struct.calcsize(pattern)
01649           _v68.D = struct.unpack(pattern, str[start:end])
01650           start = end
01651           end += 72
01652           _v68.K = _struct_9d.unpack(str[start:end])
01653           start = end
01654           end += 72
01655           _v68.R = _struct_9d.unpack(str[start:end])
01656           start = end
01657           end += 96
01658           _v68.P = _struct_12d.unpack(str[start:end])
01659           _x = _v68
01660           start = end
01661           end += 8
01662           (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
01663           _v71 = _v68.roi
01664           _x = _v71
01665           start = end
01666           end += 17
01667           (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
01668           _v71.do_rectify = bool(_v71.do_rectify)
01669           _v72 = _v58.roi_box_pose
01670           _v73 = _v72.header
01671           start = end
01672           end += 4
01673           (_v73.seq,) = _struct_I.unpack(str[start:end])
01674           _v74 = _v73.stamp
01675           _x = _v74
01676           start = end
01677           end += 8
01678           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01679           start = end
01680           end += 4
01681           (length,) = _struct_I.unpack(str[start:end])
01682           start = end
01683           end += length
01684           if python3:
01685             _v73.frame_id = str[start:end].decode('utf-8')
01686           else:
01687             _v73.frame_id = str[start:end]
01688           _v75 = _v72.pose
01689           _v76 = _v75.position
01690           _x = _v76
01691           start = end
01692           end += 24
01693           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01694           _v77 = _v75.orientation
01695           _x = _v77
01696           start = end
01697           end += 32
01698           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01699           _v78 = _v58.roi_box_dims
01700           _x = _v78
01701           start = end
01702           end += 24
01703           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01704           start = end
01705           end += 4
01706           (length,) = _struct_I.unpack(str[start:end])
01707           start = end
01708           end += length
01709           if python3:
01710             val2.collision_name = str[start:end].decode('utf-8')
01711           else:
01712             val2.collision_name = str[start:end]
01713           val1.moved_obstacles.append(val2)
01714         self.action_result.result.grasps.append(val1)
01715       _x = self
01716       start = end
01717       end += 16
01718       (_x.action_result.result.result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
01719       start = end
01720       end += 4
01721       (length,) = _struct_I.unpack(str[start:end])
01722       start = end
01723       end += length
01724       if python3:
01725         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
01726       else:
01727         self.action_feedback.header.frame_id = str[start:end]
01728       _x = self
01729       start = end
01730       end += 8
01731       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01732       start = end
01733       end += 4
01734       (length,) = _struct_I.unpack(str[start:end])
01735       start = end
01736       end += length
01737       if python3:
01738         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
01739       else:
01740         self.action_feedback.status.goal_id.id = str[start:end]
01741       start = end
01742       end += 1
01743       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
01744       start = end
01745       end += 4
01746       (length,) = _struct_I.unpack(str[start:end])
01747       start = end
01748       end += length
01749       if python3:
01750         self.action_feedback.status.text = str[start:end].decode('utf-8')
01751       else:
01752         self.action_feedback.status.text = str[start:end]
01753       return self
01754     except struct.error as e:
01755       raise genpy.DeserializationError(e) #most likely buffer underfill
01756 
01757 
01758   def serialize_numpy(self, buff, numpy):
01759     """
01760     serialize message with numpy array types into buffer
01761     :param buff: buffer, ``StringIO``
01762     :param numpy: numpy python module
01763     """
01764     try:
01765       _x = self
01766       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
01767       _x = self.action_goal.header.frame_id
01768       length = len(_x)
01769       if python3 or type(_x) == unicode:
01770         _x = _x.encode('utf-8')
01771         length = len(_x)
01772       buff.write(struct.pack('<I%ss'%length, length, _x))
01773       _x = self
01774       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
01775       _x = self.action_goal.goal_id.id
01776       length = len(_x)
01777       if python3 or type(_x) == unicode:
01778         _x = _x.encode('utf-8')
01779         length = len(_x)
01780       buff.write(struct.pack('<I%ss'%length, length, _x))
01781       _x = self
01782       buff.write(_struct_3I.pack(_x.action_goal.goal.cloud.header.seq, _x.action_goal.goal.cloud.header.stamp.secs, _x.action_goal.goal.cloud.header.stamp.nsecs))
01783       _x = self.action_goal.goal.cloud.header.frame_id
01784       length = len(_x)
01785       if python3 or type(_x) == unicode:
01786         _x = _x.encode('utf-8')
01787         length = len(_x)
01788       buff.write(struct.pack('<I%ss'%length, length, _x))
01789       _x = self
01790       buff.write(_struct_2I.pack(_x.action_goal.goal.cloud.height, _x.action_goal.goal.cloud.width))
01791       length = len(self.action_goal.goal.cloud.fields)
01792       buff.write(_struct_I.pack(length))
01793       for val1 in self.action_goal.goal.cloud.fields:
01794         _x = val1.name
01795         length = len(_x)
01796         if python3 or type(_x) == unicode:
01797           _x = _x.encode('utf-8')
01798           length = len(_x)
01799         buff.write(struct.pack('<I%ss'%length, length, _x))
01800         _x = val1
01801         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
01802       _x = self
01803       buff.write(_struct_B2I.pack(_x.action_goal.goal.cloud.is_bigendian, _x.action_goal.goal.cloud.point_step, _x.action_goal.goal.cloud.row_step))
01804       _x = self.action_goal.goal.cloud.data
01805       length = len(_x)
01806       # - if encoded as a list instead, serialize as bytes instead of string
01807       if type(_x) in [list, tuple]:
01808         buff.write(struct.pack('<I%sB'%length, length, *_x))
01809       else:
01810         buff.write(struct.pack('<I%ss'%length, length, _x))
01811       _x = self
01812       buff.write(_struct_B3I.pack(_x.action_goal.goal.cloud.is_dense, _x.action_goal.goal.pose_stamped.header.seq, _x.action_goal.goal.pose_stamped.header.stamp.secs, _x.action_goal.goal.pose_stamped.header.stamp.nsecs))
01813       _x = self.action_goal.goal.pose_stamped.header.frame_id
01814       length = len(_x)
01815       if python3 or type(_x) == unicode:
01816         _x = _x.encode('utf-8')
01817         length = len(_x)
01818       buff.write(struct.pack('<I%ss'%length, length, _x))
01819       _x = self
01820       buff.write(_struct_7dBiB3I.pack(_x.action_goal.goal.pose_stamped.pose.position.x, _x.action_goal.goal.pose_stamped.pose.position.y, _x.action_goal.goal.pose_stamped.pose.position.z, _x.action_goal.goal.pose_stamped.pose.orientation.x, _x.action_goal.goal.pose_stamped.pose.orientation.y, _x.action_goal.goal.pose_stamped.pose.orientation.z, _x.action_goal.goal.pose_stamped.pose.orientation.w, _x.action_goal.goal.use_orientation, _x.action_goal.goal.seed_index, _x.action_goal.goal.search_mode, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
01821       _x = self.action_result.header.frame_id
01822       length = len(_x)
01823       if python3 or type(_x) == unicode:
01824         _x = _x.encode('utf-8')
01825         length = len(_x)
01826       buff.write(struct.pack('<I%ss'%length, length, _x))
01827       _x = self
01828       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
01829       _x = self.action_result.status.goal_id.id
01830       length = len(_x)
01831       if python3 or type(_x) == unicode:
01832         _x = _x.encode('utf-8')
01833         length = len(_x)
01834       buff.write(struct.pack('<I%ss'%length, length, _x))
01835       buff.write(_struct_B.pack(self.action_result.status.status))
01836       _x = self.action_result.status.text
01837       length = len(_x)
01838       if python3 or type(_x) == unicode:
01839         _x = _x.encode('utf-8')
01840         length = len(_x)
01841       buff.write(struct.pack('<I%ss'%length, length, _x))
01842       length = len(self.action_result.result.grasps)
01843       buff.write(_struct_I.pack(length))
01844       for val1 in self.action_result.result.grasps:
01845         _v79 = val1.pre_grasp_posture
01846         _v80 = _v79.header
01847         buff.write(_struct_I.pack(_v80.seq))
01848         _v81 = _v80.stamp
01849         _x = _v81
01850         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01851         _x = _v80.frame_id
01852         length = len(_x)
01853         if python3 or type(_x) == unicode:
01854           _x = _x.encode('utf-8')
01855           length = len(_x)
01856         buff.write(struct.pack('<I%ss'%length, length, _x))
01857         length = len(_v79.name)
01858         buff.write(_struct_I.pack(length))
01859         for val3 in _v79.name:
01860           length = len(val3)
01861           if python3 or type(val3) == unicode:
01862             val3 = val3.encode('utf-8')
01863             length = len(val3)
01864           buff.write(struct.pack('<I%ss'%length, length, val3))
01865         length = len(_v79.position)
01866         buff.write(_struct_I.pack(length))
01867         pattern = '<%sd'%length
01868         buff.write(_v79.position.tostring())
01869         length = len(_v79.velocity)
01870         buff.write(_struct_I.pack(length))
01871         pattern = '<%sd'%length
01872         buff.write(_v79.velocity.tostring())
01873         length = len(_v79.effort)
01874         buff.write(_struct_I.pack(length))
01875         pattern = '<%sd'%length
01876         buff.write(_v79.effort.tostring())
01877         _v82 = val1.grasp_posture
01878         _v83 = _v82.header
01879         buff.write(_struct_I.pack(_v83.seq))
01880         _v84 = _v83.stamp
01881         _x = _v84
01882         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01883         _x = _v83.frame_id
01884         length = len(_x)
01885         if python3 or type(_x) == unicode:
01886           _x = _x.encode('utf-8')
01887           length = len(_x)
01888         buff.write(struct.pack('<I%ss'%length, length, _x))
01889         length = len(_v82.name)
01890         buff.write(_struct_I.pack(length))
01891         for val3 in _v82.name:
01892           length = len(val3)
01893           if python3 or type(val3) == unicode:
01894             val3 = val3.encode('utf-8')
01895             length = len(val3)
01896           buff.write(struct.pack('<I%ss'%length, length, val3))
01897         length = len(_v82.position)
01898         buff.write(_struct_I.pack(length))
01899         pattern = '<%sd'%length
01900         buff.write(_v82.position.tostring())
01901         length = len(_v82.velocity)
01902         buff.write(_struct_I.pack(length))
01903         pattern = '<%sd'%length
01904         buff.write(_v82.velocity.tostring())
01905         length = len(_v82.effort)
01906         buff.write(_struct_I.pack(length))
01907         pattern = '<%sd'%length
01908         buff.write(_v82.effort.tostring())
01909         _v85 = val1.grasp_pose
01910         _v86 = _v85.position
01911         _x = _v86
01912         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01913         _v87 = _v85.orientation
01914         _x = _v87
01915         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01916         _x = val1
01917         buff.write(_struct_dB2f.pack(_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance))
01918         length = len(val1.moved_obstacles)
01919         buff.write(_struct_I.pack(length))
01920         for val2 in val1.moved_obstacles:
01921           _x = val2.reference_frame_id
01922           length = len(_x)
01923           if python3 or type(_x) == unicode:
01924             _x = _x.encode('utf-8')
01925             length = len(_x)
01926           buff.write(struct.pack('<I%ss'%length, length, _x))
01927           length = len(val2.potential_models)
01928           buff.write(_struct_I.pack(length))
01929           for val3 in val2.potential_models:
01930             buff.write(_struct_i.pack(val3.model_id))
01931             _v88 = val3.pose
01932             _v89 = _v88.header
01933             buff.write(_struct_I.pack(_v89.seq))
01934             _v90 = _v89.stamp
01935             _x = _v90
01936             buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01937             _x = _v89.frame_id
01938             length = len(_x)
01939             if python3 or type(_x) == unicode:
01940               _x = _x.encode('utf-8')
01941               length = len(_x)
01942             buff.write(struct.pack('<I%ss'%length, length, _x))
01943             _v91 = _v88.pose
01944             _v92 = _v91.position
01945             _x = _v92
01946             buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01947             _v93 = _v91.orientation
01948             _x = _v93
01949             buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01950             buff.write(_struct_f.pack(val3.confidence))
01951             _x = val3.detector_name
01952             length = len(_x)
01953             if python3 or type(_x) == unicode:
01954               _x = _x.encode('utf-8')
01955               length = len(_x)
01956             buff.write(struct.pack('<I%ss'%length, length, _x))
01957           _v94 = val2.cluster
01958           _v95 = _v94.header
01959           buff.write(_struct_I.pack(_v95.seq))
01960           _v96 = _v95.stamp
01961           _x = _v96
01962           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01963           _x = _v95.frame_id
01964           length = len(_x)
01965           if python3 or type(_x) == unicode:
01966             _x = _x.encode('utf-8')
01967             length = len(_x)
01968           buff.write(struct.pack('<I%ss'%length, length, _x))
01969           length = len(_v94.points)
01970           buff.write(_struct_I.pack(length))
01971           for val4 in _v94.points:
01972             _x = val4
01973             buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
01974           length = len(_v94.channels)
01975           buff.write(_struct_I.pack(length))
01976           for val4 in _v94.channels:
01977             _x = val4.name
01978             length = len(_x)
01979             if python3 or type(_x) == unicode:
01980               _x = _x.encode('utf-8')
01981               length = len(_x)
01982             buff.write(struct.pack('<I%ss'%length, length, _x))
01983             length = len(val4.values)
01984             buff.write(_struct_I.pack(length))
01985             pattern = '<%sf'%length
01986             buff.write(val4.values.tostring())
01987           _v97 = val2.region
01988           _v98 = _v97.cloud
01989           _v99 = _v98.header
01990           buff.write(_struct_I.pack(_v99.seq))
01991           _v100 = _v99.stamp
01992           _x = _v100
01993           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01994           _x = _v99.frame_id
01995           length = len(_x)
01996           if python3 or type(_x) == unicode:
01997             _x = _x.encode('utf-8')
01998             length = len(_x)
01999           buff.write(struct.pack('<I%ss'%length, length, _x))
02000           _x = _v98
02001           buff.write(_struct_2I.pack(_x.height, _x.width))
02002           length = len(_v98.fields)
02003           buff.write(_struct_I.pack(length))
02004           for val5 in _v98.fields:
02005             _x = val5.name
02006             length = len(_x)
02007             if python3 or type(_x) == unicode:
02008               _x = _x.encode('utf-8')
02009               length = len(_x)
02010             buff.write(struct.pack('<I%ss'%length, length, _x))
02011             _x = val5
02012             buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
02013           _x = _v98
02014           buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
02015           _x = _v98.data
02016           length = len(_x)
02017           # - if encoded as a list instead, serialize as bytes instead of string
02018           if type(_x) in [list, tuple]:
02019             buff.write(struct.pack('<I%sB'%length, length, *_x))
02020           else:
02021             buff.write(struct.pack('<I%ss'%length, length, _x))
02022           buff.write(_struct_B.pack(_v98.is_dense))
02023           length = len(_v97.mask)
02024           buff.write(_struct_I.pack(length))
02025           pattern = '<%si'%length
02026           buff.write(_v97.mask.tostring())
02027           _v101 = _v97.image
02028           _v102 = _v101.header
02029           buff.write(_struct_I.pack(_v102.seq))
02030           _v103 = _v102.stamp
02031           _x = _v103
02032           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02033           _x = _v102.frame_id
02034           length = len(_x)
02035           if python3 or type(_x) == unicode:
02036             _x = _x.encode('utf-8')
02037             length = len(_x)
02038           buff.write(struct.pack('<I%ss'%length, length, _x))
02039           _x = _v101
02040           buff.write(_struct_2I.pack(_x.height, _x.width))
02041           _x = _v101.encoding
02042           length = len(_x)
02043           if python3 or type(_x) == unicode:
02044             _x = _x.encode('utf-8')
02045             length = len(_x)
02046           buff.write(struct.pack('<I%ss'%length, length, _x))
02047           _x = _v101
02048           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
02049           _x = _v101.data
02050           length = len(_x)
02051           # - if encoded as a list instead, serialize as bytes instead of string
02052           if type(_x) in [list, tuple]:
02053             buff.write(struct.pack('<I%sB'%length, length, *_x))
02054           else:
02055             buff.write(struct.pack('<I%ss'%length, length, _x))
02056           _v104 = _v97.disparity_image
02057           _v105 = _v104.header
02058           buff.write(_struct_I.pack(_v105.seq))
02059           _v106 = _v105.stamp
02060           _x = _v106
02061           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02062           _x = _v105.frame_id
02063           length = len(_x)
02064           if python3 or type(_x) == unicode:
02065             _x = _x.encode('utf-8')
02066             length = len(_x)
02067           buff.write(struct.pack('<I%ss'%length, length, _x))
02068           _x = _v104
02069           buff.write(_struct_2I.pack(_x.height, _x.width))
02070           _x = _v104.encoding
02071           length = len(_x)
02072           if python3 or type(_x) == unicode:
02073             _x = _x.encode('utf-8')
02074             length = len(_x)
02075           buff.write(struct.pack('<I%ss'%length, length, _x))
02076           _x = _v104
02077           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
02078           _x = _v104.data
02079           length = len(_x)
02080           # - if encoded as a list instead, serialize as bytes instead of string
02081           if type(_x) in [list, tuple]:
02082             buff.write(struct.pack('<I%sB'%length, length, *_x))
02083           else:
02084             buff.write(struct.pack('<I%ss'%length, length, _x))
02085           _v107 = _v97.cam_info
02086           _v108 = _v107.header
02087           buff.write(_struct_I.pack(_v108.seq))
02088           _v109 = _v108.stamp
02089           _x = _v109
02090           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02091           _x = _v108.frame_id
02092           length = len(_x)
02093           if python3 or type(_x) == unicode:
02094             _x = _x.encode('utf-8')
02095             length = len(_x)
02096           buff.write(struct.pack('<I%ss'%length, length, _x))
02097           _x = _v107
02098           buff.write(_struct_2I.pack(_x.height, _x.width))
02099           _x = _v107.distortion_model
02100           length = len(_x)
02101           if python3 or type(_x) == unicode:
02102             _x = _x.encode('utf-8')
02103             length = len(_x)
02104           buff.write(struct.pack('<I%ss'%length, length, _x))
02105           length = len(_v107.D)
02106           buff.write(_struct_I.pack(length))
02107           pattern = '<%sd'%length
02108           buff.write(_v107.D.tostring())
02109           buff.write(_v107.K.tostring())
02110           buff.write(_v107.R.tostring())
02111           buff.write(_v107.P.tostring())
02112           _x = _v107
02113           buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
02114           _v110 = _v107.roi
02115           _x = _v110
02116           buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
02117           _v111 = _v97.roi_box_pose
02118           _v112 = _v111.header
02119           buff.write(_struct_I.pack(_v112.seq))
02120           _v113 = _v112.stamp
02121           _x = _v113
02122           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02123           _x = _v112.frame_id
02124           length = len(_x)
02125           if python3 or type(_x) == unicode:
02126             _x = _x.encode('utf-8')
02127             length = len(_x)
02128           buff.write(struct.pack('<I%ss'%length, length, _x))
02129           _v114 = _v111.pose
02130           _v115 = _v114.position
02131           _x = _v115
02132           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02133           _v116 = _v114.orientation
02134           _x = _v116
02135           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02136           _v117 = _v97.roi_box_dims
02137           _x = _v117
02138           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02139           _x = val2.collision_name
02140           length = len(_x)
02141           if python3 or type(_x) == unicode:
02142             _x = _x.encode('utf-8')
02143             length = len(_x)
02144           buff.write(struct.pack('<I%ss'%length, length, _x))
02145       _x = self
02146       buff.write(_struct_i3I.pack(_x.action_result.result.result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
02147       _x = self.action_feedback.header.frame_id
02148       length = len(_x)
02149       if python3 or type(_x) == unicode:
02150         _x = _x.encode('utf-8')
02151         length = len(_x)
02152       buff.write(struct.pack('<I%ss'%length, length, _x))
02153       _x = self
02154       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
02155       _x = self.action_feedback.status.goal_id.id
02156       length = len(_x)
02157       if python3 or type(_x) == unicode:
02158         _x = _x.encode('utf-8')
02159         length = len(_x)
02160       buff.write(struct.pack('<I%ss'%length, length, _x))
02161       buff.write(_struct_B.pack(self.action_feedback.status.status))
02162       _x = self.action_feedback.status.text
02163       length = len(_x)
02164       if python3 or type(_x) == unicode:
02165         _x = _x.encode('utf-8')
02166         length = len(_x)
02167       buff.write(struct.pack('<I%ss'%length, length, _x))
02168     except struct.error as se: self._check_types(se)
02169     except TypeError as te: self._check_types(te)
02170 
02171   def deserialize_numpy(self, str, numpy):
02172     """
02173     unpack serialized message in str into this message instance using numpy for array types
02174     :param str: byte array of serialized message, ``str``
02175     :param numpy: numpy python module
02176     """
02177     try:
02178       if self.action_goal is None:
02179         self.action_goal = pr2_grasp_adjust.msg.GraspAdjustActionGoal()
02180       if self.action_result is None:
02181         self.action_result = pr2_grasp_adjust.msg.GraspAdjustActionResult()
02182       if self.action_feedback is None:
02183         self.action_feedback = pr2_grasp_adjust.msg.GraspAdjustActionFeedback()
02184       end = 0
02185       _x = self
02186       start = end
02187       end += 12
02188       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02189       start = end
02190       end += 4
02191       (length,) = _struct_I.unpack(str[start:end])
02192       start = end
02193       end += length
02194       if python3:
02195         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
02196       else:
02197         self.action_goal.header.frame_id = str[start:end]
02198       _x = self
02199       start = end
02200       end += 8
02201       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
02202       start = end
02203       end += 4
02204       (length,) = _struct_I.unpack(str[start:end])
02205       start = end
02206       end += length
02207       if python3:
02208         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
02209       else:
02210         self.action_goal.goal_id.id = str[start:end]
02211       _x = self
02212       start = end
02213       end += 12
02214       (_x.action_goal.goal.cloud.header.seq, _x.action_goal.goal.cloud.header.stamp.secs, _x.action_goal.goal.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02215       start = end
02216       end += 4
02217       (length,) = _struct_I.unpack(str[start:end])
02218       start = end
02219       end += length
02220       if python3:
02221         self.action_goal.goal.cloud.header.frame_id = str[start:end].decode('utf-8')
02222       else:
02223         self.action_goal.goal.cloud.header.frame_id = str[start:end]
02224       _x = self
02225       start = end
02226       end += 8
02227       (_x.action_goal.goal.cloud.height, _x.action_goal.goal.cloud.width,) = _struct_2I.unpack(str[start:end])
02228       start = end
02229       end += 4
02230       (length,) = _struct_I.unpack(str[start:end])
02231       self.action_goal.goal.cloud.fields = []
02232       for i in range(0, length):
02233         val1 = sensor_msgs.msg.PointField()
02234         start = end
02235         end += 4
02236         (length,) = _struct_I.unpack(str[start:end])
02237         start = end
02238         end += length
02239         if python3:
02240           val1.name = str[start:end].decode('utf-8')
02241         else:
02242           val1.name = str[start:end]
02243         _x = val1
02244         start = end
02245         end += 9
02246         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
02247         self.action_goal.goal.cloud.fields.append(val1)
02248       _x = self
02249       start = end
02250       end += 9
02251       (_x.action_goal.goal.cloud.is_bigendian, _x.action_goal.goal.cloud.point_step, _x.action_goal.goal.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
02252       self.action_goal.goal.cloud.is_bigendian = bool(self.action_goal.goal.cloud.is_bigendian)
02253       start = end
02254       end += 4
02255       (length,) = _struct_I.unpack(str[start:end])
02256       start = end
02257       end += length
02258       if python3:
02259         self.action_goal.goal.cloud.data = str[start:end].decode('utf-8')
02260       else:
02261         self.action_goal.goal.cloud.data = str[start:end]
02262       _x = self
02263       start = end
02264       end += 13
02265       (_x.action_goal.goal.cloud.is_dense, _x.action_goal.goal.pose_stamped.header.seq, _x.action_goal.goal.pose_stamped.header.stamp.secs, _x.action_goal.goal.pose_stamped.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
02266       self.action_goal.goal.cloud.is_dense = bool(self.action_goal.goal.cloud.is_dense)
02267       start = end
02268       end += 4
02269       (length,) = _struct_I.unpack(str[start:end])
02270       start = end
02271       end += length
02272       if python3:
02273         self.action_goal.goal.pose_stamped.header.frame_id = str[start:end].decode('utf-8')
02274       else:
02275         self.action_goal.goal.pose_stamped.header.frame_id = str[start:end]
02276       _x = self
02277       start = end
02278       end += 74
02279       (_x.action_goal.goal.pose_stamped.pose.position.x, _x.action_goal.goal.pose_stamped.pose.position.y, _x.action_goal.goal.pose_stamped.pose.position.z, _x.action_goal.goal.pose_stamped.pose.orientation.x, _x.action_goal.goal.pose_stamped.pose.orientation.y, _x.action_goal.goal.pose_stamped.pose.orientation.z, _x.action_goal.goal.pose_stamped.pose.orientation.w, _x.action_goal.goal.use_orientation, _x.action_goal.goal.seed_index, _x.action_goal.goal.search_mode, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_7dBiB3I.unpack(str[start:end])
02280       self.action_goal.goal.use_orientation = bool(self.action_goal.goal.use_orientation)
02281       start = end
02282       end += 4
02283       (length,) = _struct_I.unpack(str[start:end])
02284       start = end
02285       end += length
02286       if python3:
02287         self.action_result.header.frame_id = str[start:end].decode('utf-8')
02288       else:
02289         self.action_result.header.frame_id = str[start:end]
02290       _x = self
02291       start = end
02292       end += 8
02293       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
02294       start = end
02295       end += 4
02296       (length,) = _struct_I.unpack(str[start:end])
02297       start = end
02298       end += length
02299       if python3:
02300         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
02301       else:
02302         self.action_result.status.goal_id.id = str[start:end]
02303       start = end
02304       end += 1
02305       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
02306       start = end
02307       end += 4
02308       (length,) = _struct_I.unpack(str[start:end])
02309       start = end
02310       end += length
02311       if python3:
02312         self.action_result.status.text = str[start:end].decode('utf-8')
02313       else:
02314         self.action_result.status.text = str[start:end]
02315       start = end
02316       end += 4
02317       (length,) = _struct_I.unpack(str[start:end])
02318       self.action_result.result.grasps = []
02319       for i in range(0, length):
02320         val1 = object_manipulation_msgs.msg.Grasp()
02321         _v118 = val1.pre_grasp_posture
02322         _v119 = _v118.header
02323         start = end
02324         end += 4
02325         (_v119.seq,) = _struct_I.unpack(str[start:end])
02326         _v120 = _v119.stamp
02327         _x = _v120
02328         start = end
02329         end += 8
02330         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02331         start = end
02332         end += 4
02333         (length,) = _struct_I.unpack(str[start:end])
02334         start = end
02335         end += length
02336         if python3:
02337           _v119.frame_id = str[start:end].decode('utf-8')
02338         else:
02339           _v119.frame_id = str[start:end]
02340         start = end
02341         end += 4
02342         (length,) = _struct_I.unpack(str[start:end])
02343         _v118.name = []
02344         for i in range(0, length):
02345           start = end
02346           end += 4
02347           (length,) = _struct_I.unpack(str[start:end])
02348           start = end
02349           end += length
02350           if python3:
02351             val3 = str[start:end].decode('utf-8')
02352           else:
02353             val3 = str[start:end]
02354           _v118.name.append(val3)
02355         start = end
02356         end += 4
02357         (length,) = _struct_I.unpack(str[start:end])
02358         pattern = '<%sd'%length
02359         start = end
02360         end += struct.calcsize(pattern)
02361         _v118.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02362         start = end
02363         end += 4
02364         (length,) = _struct_I.unpack(str[start:end])
02365         pattern = '<%sd'%length
02366         start = end
02367         end += struct.calcsize(pattern)
02368         _v118.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02369         start = end
02370         end += 4
02371         (length,) = _struct_I.unpack(str[start:end])
02372         pattern = '<%sd'%length
02373         start = end
02374         end += struct.calcsize(pattern)
02375         _v118.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02376         _v121 = val1.grasp_posture
02377         _v122 = _v121.header
02378         start = end
02379         end += 4
02380         (_v122.seq,) = _struct_I.unpack(str[start:end])
02381         _v123 = _v122.stamp
02382         _x = _v123
02383         start = end
02384         end += 8
02385         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02386         start = end
02387         end += 4
02388         (length,) = _struct_I.unpack(str[start:end])
02389         start = end
02390         end += length
02391         if python3:
02392           _v122.frame_id = str[start:end].decode('utf-8')
02393         else:
02394           _v122.frame_id = str[start:end]
02395         start = end
02396         end += 4
02397         (length,) = _struct_I.unpack(str[start:end])
02398         _v121.name = []
02399         for i in range(0, length):
02400           start = end
02401           end += 4
02402           (length,) = _struct_I.unpack(str[start:end])
02403           start = end
02404           end += length
02405           if python3:
02406             val3 = str[start:end].decode('utf-8')
02407           else:
02408             val3 = str[start:end]
02409           _v121.name.append(val3)
02410         start = end
02411         end += 4
02412         (length,) = _struct_I.unpack(str[start:end])
02413         pattern = '<%sd'%length
02414         start = end
02415         end += struct.calcsize(pattern)
02416         _v121.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02417         start = end
02418         end += 4
02419         (length,) = _struct_I.unpack(str[start:end])
02420         pattern = '<%sd'%length
02421         start = end
02422         end += struct.calcsize(pattern)
02423         _v121.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02424         start = end
02425         end += 4
02426         (length,) = _struct_I.unpack(str[start:end])
02427         pattern = '<%sd'%length
02428         start = end
02429         end += struct.calcsize(pattern)
02430         _v121.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02431         _v124 = val1.grasp_pose
02432         _v125 = _v124.position
02433         _x = _v125
02434         start = end
02435         end += 24
02436         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02437         _v126 = _v124.orientation
02438         _x = _v126
02439         start = end
02440         end += 32
02441         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02442         _x = val1
02443         start = end
02444         end += 17
02445         (_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance,) = _struct_dB2f.unpack(str[start:end])
02446         val1.cluster_rep = bool(val1.cluster_rep)
02447         start = end
02448         end += 4
02449         (length,) = _struct_I.unpack(str[start:end])
02450         val1.moved_obstacles = []
02451         for i in range(0, length):
02452           val2 = object_manipulation_msgs.msg.GraspableObject()
02453           start = end
02454           end += 4
02455           (length,) = _struct_I.unpack(str[start:end])
02456           start = end
02457           end += length
02458           if python3:
02459             val2.reference_frame_id = str[start:end].decode('utf-8')
02460           else:
02461             val2.reference_frame_id = str[start:end]
02462           start = end
02463           end += 4
02464           (length,) = _struct_I.unpack(str[start:end])
02465           val2.potential_models = []
02466           for i in range(0, length):
02467             val3 = household_objects_database_msgs.msg.DatabaseModelPose()
02468             start = end
02469             end += 4
02470             (val3.model_id,) = _struct_i.unpack(str[start:end])
02471             _v127 = val3.pose
02472             _v128 = _v127.header
02473             start = end
02474             end += 4
02475             (_v128.seq,) = _struct_I.unpack(str[start:end])
02476             _v129 = _v128.stamp
02477             _x = _v129
02478             start = end
02479             end += 8
02480             (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02481             start = end
02482             end += 4
02483             (length,) = _struct_I.unpack(str[start:end])
02484             start = end
02485             end += length
02486             if python3:
02487               _v128.frame_id = str[start:end].decode('utf-8')
02488             else:
02489               _v128.frame_id = str[start:end]
02490             _v130 = _v127.pose
02491             _v131 = _v130.position
02492             _x = _v131
02493             start = end
02494             end += 24
02495             (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02496             _v132 = _v130.orientation
02497             _x = _v132
02498             start = end
02499             end += 32
02500             (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02501             start = end
02502             end += 4
02503             (val3.confidence,) = _struct_f.unpack(str[start:end])
02504             start = end
02505             end += 4
02506             (length,) = _struct_I.unpack(str[start:end])
02507             start = end
02508             end += length
02509             if python3:
02510               val3.detector_name = str[start:end].decode('utf-8')
02511             else:
02512               val3.detector_name = str[start:end]
02513             val2.potential_models.append(val3)
02514           _v133 = val2.cluster
02515           _v134 = _v133.header
02516           start = end
02517           end += 4
02518           (_v134.seq,) = _struct_I.unpack(str[start:end])
02519           _v135 = _v134.stamp
02520           _x = _v135
02521           start = end
02522           end += 8
02523           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02524           start = end
02525           end += 4
02526           (length,) = _struct_I.unpack(str[start:end])
02527           start = end
02528           end += length
02529           if python3:
02530             _v134.frame_id = str[start:end].decode('utf-8')
02531           else:
02532             _v134.frame_id = str[start:end]
02533           start = end
02534           end += 4
02535           (length,) = _struct_I.unpack(str[start:end])
02536           _v133.points = []
02537           for i in range(0, length):
02538             val4 = geometry_msgs.msg.Point32()
02539             _x = val4
02540             start = end
02541             end += 12
02542             (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
02543             _v133.points.append(val4)
02544           start = end
02545           end += 4
02546           (length,) = _struct_I.unpack(str[start:end])
02547           _v133.channels = []
02548           for i in range(0, length):
02549             val4 = sensor_msgs.msg.ChannelFloat32()
02550             start = end
02551             end += 4
02552             (length,) = _struct_I.unpack(str[start:end])
02553             start = end
02554             end += length
02555             if python3:
02556               val4.name = str[start:end].decode('utf-8')
02557             else:
02558               val4.name = str[start:end]
02559             start = end
02560             end += 4
02561             (length,) = _struct_I.unpack(str[start:end])
02562             pattern = '<%sf'%length
02563             start = end
02564             end += struct.calcsize(pattern)
02565             val4.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
02566             _v133.channels.append(val4)
02567           _v136 = val2.region
02568           _v137 = _v136.cloud
02569           _v138 = _v137.header
02570           start = end
02571           end += 4
02572           (_v138.seq,) = _struct_I.unpack(str[start:end])
02573           _v139 = _v138.stamp
02574           _x = _v139
02575           start = end
02576           end += 8
02577           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02578           start = end
02579           end += 4
02580           (length,) = _struct_I.unpack(str[start:end])
02581           start = end
02582           end += length
02583           if python3:
02584             _v138.frame_id = str[start:end].decode('utf-8')
02585           else:
02586             _v138.frame_id = str[start:end]
02587           _x = _v137
02588           start = end
02589           end += 8
02590           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02591           start = end
02592           end += 4
02593           (length,) = _struct_I.unpack(str[start:end])
02594           _v137.fields = []
02595           for i in range(0, length):
02596             val5 = sensor_msgs.msg.PointField()
02597             start = end
02598             end += 4
02599             (length,) = _struct_I.unpack(str[start:end])
02600             start = end
02601             end += length
02602             if python3:
02603               val5.name = str[start:end].decode('utf-8')
02604             else:
02605               val5.name = str[start:end]
02606             _x = val5
02607             start = end
02608             end += 9
02609             (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
02610             _v137.fields.append(val5)
02611           _x = _v137
02612           start = end
02613           end += 9
02614           (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
02615           _v137.is_bigendian = bool(_v137.is_bigendian)
02616           start = end
02617           end += 4
02618           (length,) = _struct_I.unpack(str[start:end])
02619           start = end
02620           end += length
02621           if python3:
02622             _v137.data = str[start:end].decode('utf-8')
02623           else:
02624             _v137.data = str[start:end]
02625           start = end
02626           end += 1
02627           (_v137.is_dense,) = _struct_B.unpack(str[start:end])
02628           _v137.is_dense = bool(_v137.is_dense)
02629           start = end
02630           end += 4
02631           (length,) = _struct_I.unpack(str[start:end])
02632           pattern = '<%si'%length
02633           start = end
02634           end += struct.calcsize(pattern)
02635           _v136.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
02636           _v140 = _v136.image
02637           _v141 = _v140.header
02638           start = end
02639           end += 4
02640           (_v141.seq,) = _struct_I.unpack(str[start:end])
02641           _v142 = _v141.stamp
02642           _x = _v142
02643           start = end
02644           end += 8
02645           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02646           start = end
02647           end += 4
02648           (length,) = _struct_I.unpack(str[start:end])
02649           start = end
02650           end += length
02651           if python3:
02652             _v141.frame_id = str[start:end].decode('utf-8')
02653           else:
02654             _v141.frame_id = str[start:end]
02655           _x = _v140
02656           start = end
02657           end += 8
02658           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02659           start = end
02660           end += 4
02661           (length,) = _struct_I.unpack(str[start:end])
02662           start = end
02663           end += length
02664           if python3:
02665             _v140.encoding = str[start:end].decode('utf-8')
02666           else:
02667             _v140.encoding = str[start:end]
02668           _x = _v140
02669           start = end
02670           end += 5
02671           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
02672           start = end
02673           end += 4
02674           (length,) = _struct_I.unpack(str[start:end])
02675           start = end
02676           end += length
02677           if python3:
02678             _v140.data = str[start:end].decode('utf-8')
02679           else:
02680             _v140.data = str[start:end]
02681           _v143 = _v136.disparity_image
02682           _v144 = _v143.header
02683           start = end
02684           end += 4
02685           (_v144.seq,) = _struct_I.unpack(str[start:end])
02686           _v145 = _v144.stamp
02687           _x = _v145
02688           start = end
02689           end += 8
02690           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02691           start = end
02692           end += 4
02693           (length,) = _struct_I.unpack(str[start:end])
02694           start = end
02695           end += length
02696           if python3:
02697             _v144.frame_id = str[start:end].decode('utf-8')
02698           else:
02699             _v144.frame_id = str[start:end]
02700           _x = _v143
02701           start = end
02702           end += 8
02703           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02704           start = end
02705           end += 4
02706           (length,) = _struct_I.unpack(str[start:end])
02707           start = end
02708           end += length
02709           if python3:
02710             _v143.encoding = str[start:end].decode('utf-8')
02711           else:
02712             _v143.encoding = str[start:end]
02713           _x = _v143
02714           start = end
02715           end += 5
02716           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
02717           start = end
02718           end += 4
02719           (length,) = _struct_I.unpack(str[start:end])
02720           start = end
02721           end += length
02722           if python3:
02723             _v143.data = str[start:end].decode('utf-8')
02724           else:
02725             _v143.data = str[start:end]
02726           _v146 = _v136.cam_info
02727           _v147 = _v146.header
02728           start = end
02729           end += 4
02730           (_v147.seq,) = _struct_I.unpack(str[start:end])
02731           _v148 = _v147.stamp
02732           _x = _v148
02733           start = end
02734           end += 8
02735           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02736           start = end
02737           end += 4
02738           (length,) = _struct_I.unpack(str[start:end])
02739           start = end
02740           end += length
02741           if python3:
02742             _v147.frame_id = str[start:end].decode('utf-8')
02743           else:
02744             _v147.frame_id = str[start:end]
02745           _x = _v146
02746           start = end
02747           end += 8
02748           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02749           start = end
02750           end += 4
02751           (length,) = _struct_I.unpack(str[start:end])
02752           start = end
02753           end += length
02754           if python3:
02755             _v146.distortion_model = str[start:end].decode('utf-8')
02756           else:
02757             _v146.distortion_model = str[start:end]
02758           start = end
02759           end += 4
02760           (length,) = _struct_I.unpack(str[start:end])
02761           pattern = '<%sd'%length
02762           start = end
02763           end += struct.calcsize(pattern)
02764           _v146.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02765           start = end
02766           end += 72
02767           _v146.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
02768           start = end
02769           end += 72
02770           _v146.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
02771           start = end
02772           end += 96
02773           _v146.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
02774           _x = _v146
02775           start = end
02776           end += 8
02777           (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
02778           _v149 = _v146.roi
02779           _x = _v149
02780           start = end
02781           end += 17
02782           (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
02783           _v149.do_rectify = bool(_v149.do_rectify)
02784           _v150 = _v136.roi_box_pose
02785           _v151 = _v150.header
02786           start = end
02787           end += 4
02788           (_v151.seq,) = _struct_I.unpack(str[start:end])
02789           _v152 = _v151.stamp
02790           _x = _v152
02791           start = end
02792           end += 8
02793           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02794           start = end
02795           end += 4
02796           (length,) = _struct_I.unpack(str[start:end])
02797           start = end
02798           end += length
02799           if python3:
02800             _v151.frame_id = str[start:end].decode('utf-8')
02801           else:
02802             _v151.frame_id = str[start:end]
02803           _v153 = _v150.pose
02804           _v154 = _v153.position
02805           _x = _v154
02806           start = end
02807           end += 24
02808           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02809           _v155 = _v153.orientation
02810           _x = _v155
02811           start = end
02812           end += 32
02813           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02814           _v156 = _v136.roi_box_dims
02815           _x = _v156
02816           start = end
02817           end += 24
02818           (_x.x, _x.y, _x.z,) = _struct_3d.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             val2.collision_name = str[start:end].decode('utf-8')
02826           else:
02827             val2.collision_name = str[start:end]
02828           val1.moved_obstacles.append(val2)
02829         self.action_result.result.grasps.append(val1)
02830       _x = self
02831       start = end
02832       end += 16
02833       (_x.action_result.result.result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
02834       start = end
02835       end += 4
02836       (length,) = _struct_I.unpack(str[start:end])
02837       start = end
02838       end += length
02839       if python3:
02840         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
02841       else:
02842         self.action_feedback.header.frame_id = str[start:end]
02843       _x = self
02844       start = end
02845       end += 8
02846       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
02847       start = end
02848       end += 4
02849       (length,) = _struct_I.unpack(str[start:end])
02850       start = end
02851       end += length
02852       if python3:
02853         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
02854       else:
02855         self.action_feedback.status.goal_id.id = str[start:end]
02856       start = end
02857       end += 1
02858       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
02859       start = end
02860       end += 4
02861       (length,) = _struct_I.unpack(str[start:end])
02862       start = end
02863       end += length
02864       if python3:
02865         self.action_feedback.status.text = str[start:end].decode('utf-8')
02866       else:
02867         self.action_feedback.status.text = str[start:end]
02868       return self
02869     except struct.error as e:
02870       raise genpy.DeserializationError(e) #most likely buffer underfill
02871 
02872 _struct_I = genpy.struct_I
02873 _struct_IBI = struct.Struct("<IBI")
02874 _struct_B = struct.Struct("<B")
02875 _struct_12d = struct.Struct("<12d")
02876 _struct_f = struct.Struct("<f")
02877 _struct_dB2f = struct.Struct("<dB2f")
02878 _struct_BI = struct.Struct("<BI")
02879 _struct_3f = struct.Struct("<3f")
02880 _struct_i = struct.Struct("<i")
02881 _struct_3I = struct.Struct("<3I")
02882 _struct_9d = struct.Struct("<9d")
02883 _struct_B3I = struct.Struct("<B3I")
02884 _struct_B2I = struct.Struct("<B2I")
02885 _struct_i3I = struct.Struct("<i3I")
02886 _struct_4d = struct.Struct("<4d")
02887 _struct_7dBiB3I = struct.Struct("<7dBiB3I")
02888 _struct_2I = struct.Struct("<2I")
02889 _struct_4IB = struct.Struct("<4IB")
02890 _struct_3d = struct.Struct("<3d")


pr2_grasp_adjust
Author(s): Adam Leeper
autogenerated on Fri Jan 3 2014 12:00:28