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


pr2_object_manipulation_msgs
Author(s): Matei Ciocarlie
autogenerated on Mon Oct 6 2014 11:55:20