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


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