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


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