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


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