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


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