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