_GraspPlanningGoal.py
Go to the documentation of this file.
00001 """autogenerated by genpy from object_manipulation_msgs/GraspPlanningGoal.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 geometry_msgs.msg
00008 import sensor_msgs.msg
00009 import std_msgs.msg
00010 import object_manipulation_msgs.msg
00011 import household_objects_database_msgs.msg
00012 
00013 class GraspPlanningGoal(genpy.Message):
00014   _md5sum = "5003fdf2225280c9d81c2bce4e645c20"
00015   _type = "object_manipulation_msgs/GraspPlanningGoal"
00016   _has_header = False #flag to mark the presence of a Header object
00017   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00018 # Requests that grasp planning be performed on the object to be grasped
00019 # returns a list of grasps to be tested and executed
00020 
00021 # the arm being used
00022 string arm_name
00023 
00024 # the object to be grasped
00025 GraspableObject target
00026 
00027 # the name that the target object has in the collision environment
00028 # can be left empty if no name is available
00029 string collision_object_name
00030 
00031 # the name that the support surface (e.g. table) has in the collision map
00032 # can be left empty if no name is available
00033 string collision_support_surface_name
00034 
00035 # an optional list of grasps to be evaluated by the planner
00036 Grasp[] grasps_to_evaluate
00037 
00038 # an optional list of obstacles that we have semantic information about
00039 # and that can be moved in the course of grasping
00040 GraspableObject[] movable_obstacles
00041 
00042 
00043 ================================================================================
00044 MSG: object_manipulation_msgs/GraspableObject
00045 # an object that the object_manipulator can work on
00046 
00047 # a graspable object can be represented in multiple ways. This message
00048 # can contain all of them. Which one is actually used is up to the receiver
00049 # of this message. When adding new representations, one must be careful that
00050 # they have reasonable lightweight defaults indicating that that particular
00051 # representation is not available.
00052 
00053 # the tf frame to be used as a reference frame when combining information from
00054 # the different representations below
00055 string reference_frame_id
00056 
00057 # potential recognition results from a database of models
00058 # all poses are relative to the object reference pose
00059 household_objects_database_msgs/DatabaseModelPose[] potential_models
00060 
00061 # the point cloud itself
00062 sensor_msgs/PointCloud cluster
00063 
00064 # a region of a PointCloud2 of interest
00065 object_manipulation_msgs/SceneRegion region
00066 
00067 # the name that this object has in the collision environment
00068 string collision_name
00069 ================================================================================
00070 MSG: household_objects_database_msgs/DatabaseModelPose
00071 # Informs that a specific model from the Model Database has been 
00072 # identified at a certain location
00073 
00074 # the database id of the model
00075 int32 model_id
00076 
00077 # the pose that it can be found in
00078 geometry_msgs/PoseStamped pose
00079 
00080 # a measure of the confidence level in this detection result
00081 float32 confidence
00082 
00083 # the name of the object detector that generated this detection result
00084 string detector_name
00085 
00086 ================================================================================
00087 MSG: geometry_msgs/PoseStamped
00088 # A Pose with reference coordinate frame and timestamp
00089 Header header
00090 Pose pose
00091 
00092 ================================================================================
00093 MSG: std_msgs/Header
00094 # Standard metadata for higher-level stamped data types.
00095 # This is generally used to communicate timestamped data 
00096 # in a particular coordinate frame.
00097 # 
00098 # sequence ID: consecutively increasing ID 
00099 uint32 seq
00100 #Two-integer timestamp that is expressed as:
00101 # * stamp.secs: seconds (stamp_secs) since epoch
00102 # * stamp.nsecs: nanoseconds since stamp_secs
00103 # time-handling sugar is provided by the client library
00104 time stamp
00105 #Frame this data is associated with
00106 # 0: no frame
00107 # 1: global frame
00108 string frame_id
00109 
00110 ================================================================================
00111 MSG: geometry_msgs/Pose
00112 # A representation of pose in free space, composed of postion and orientation. 
00113 Point position
00114 Quaternion orientation
00115 
00116 ================================================================================
00117 MSG: geometry_msgs/Point
00118 # This contains the position of a point in free space
00119 float64 x
00120 float64 y
00121 float64 z
00122 
00123 ================================================================================
00124 MSG: geometry_msgs/Quaternion
00125 # This represents an orientation in free space in quaternion form.
00126 
00127 float64 x
00128 float64 y
00129 float64 z
00130 float64 w
00131 
00132 ================================================================================
00133 MSG: sensor_msgs/PointCloud
00134 # This message holds a collection of 3d points, plus optional additional
00135 # information about each point.
00136 
00137 # Time of sensor data acquisition, coordinate frame ID.
00138 Header header
00139 
00140 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00141 # in the frame given in the header.
00142 geometry_msgs/Point32[] points
00143 
00144 # Each channel should have the same number of elements as points array,
00145 # and the data in each channel should correspond 1:1 with each point.
00146 # Channel names in common practice are listed in ChannelFloat32.msg.
00147 ChannelFloat32[] channels
00148 
00149 ================================================================================
00150 MSG: geometry_msgs/Point32
00151 # This contains the position of a point in free space(with 32 bits of precision).
00152 # It is recommeded to use Point wherever possible instead of Point32.  
00153 # 
00154 # This recommendation is to promote interoperability.  
00155 #
00156 # This message is designed to take up less space when sending
00157 # lots of points at once, as in the case of a PointCloud.  
00158 
00159 float32 x
00160 float32 y
00161 float32 z
00162 ================================================================================
00163 MSG: sensor_msgs/ChannelFloat32
00164 # This message is used by the PointCloud message to hold optional data
00165 # associated with each point in the cloud. The length of the values
00166 # array should be the same as the length of the points array in the
00167 # PointCloud, and each value should be associated with the corresponding
00168 # point.
00169 
00170 # Channel names in existing practice include:
00171 #   "u", "v" - row and column (respectively) in the left stereo image.
00172 #              This is opposite to usual conventions but remains for
00173 #              historical reasons. The newer PointCloud2 message has no
00174 #              such problem.
00175 #   "rgb" - For point clouds produced by color stereo cameras. uint8
00176 #           (R,G,B) values packed into the least significant 24 bits,
00177 #           in order.
00178 #   "intensity" - laser or pixel intensity.
00179 #   "distance"
00180 
00181 # The channel name should give semantics of the channel (e.g.
00182 # "intensity" instead of "value").
00183 string name
00184 
00185 # The values array should be 1-1 with the elements of the associated
00186 # PointCloud.
00187 float32[] values
00188 
00189 ================================================================================
00190 MSG: object_manipulation_msgs/SceneRegion
00191 # Point cloud
00192 sensor_msgs/PointCloud2 cloud
00193 
00194 # Indices for the region of interest
00195 int32[] mask
00196 
00197 # One of the corresponding 2D images, if applicable
00198 sensor_msgs/Image image
00199 
00200 # The disparity image, if applicable
00201 sensor_msgs/Image disparity_image
00202 
00203 # Camera info for the camera that took the image
00204 sensor_msgs/CameraInfo cam_info
00205 
00206 # a 3D region of interest for grasp planning
00207 geometry_msgs/PoseStamped  roi_box_pose
00208 geometry_msgs/Vector3      roi_box_dims
00209 
00210 ================================================================================
00211 MSG: sensor_msgs/PointCloud2
00212 # This message holds a collection of N-dimensional points, which may
00213 # contain additional information such as normals, intensity, etc. The
00214 # point data is stored as a binary blob, its layout described by the
00215 # contents of the "fields" array.
00216 
00217 # The point cloud data may be organized 2d (image-like) or 1d
00218 # (unordered). Point clouds organized as 2d images may be produced by
00219 # camera depth sensors such as stereo or time-of-flight.
00220 
00221 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00222 # points).
00223 Header header
00224 
00225 # 2D structure of the point cloud. If the cloud is unordered, height is
00226 # 1 and width is the length of the point cloud.
00227 uint32 height
00228 uint32 width
00229 
00230 # Describes the channels and their layout in the binary data blob.
00231 PointField[] fields
00232 
00233 bool    is_bigendian # Is this data bigendian?
00234 uint32  point_step   # Length of a point in bytes
00235 uint32  row_step     # Length of a row in bytes
00236 uint8[] data         # Actual point data, size is (row_step*height)
00237 
00238 bool is_dense        # True if there are no invalid points
00239 
00240 ================================================================================
00241 MSG: sensor_msgs/PointField
00242 # This message holds the description of one point entry in the
00243 # PointCloud2 message format.
00244 uint8 INT8    = 1
00245 uint8 UINT8   = 2
00246 uint8 INT16   = 3
00247 uint8 UINT16  = 4
00248 uint8 INT32   = 5
00249 uint8 UINT32  = 6
00250 uint8 FLOAT32 = 7
00251 uint8 FLOAT64 = 8
00252 
00253 string name      # Name of field
00254 uint32 offset    # Offset from start of point struct
00255 uint8  datatype  # Datatype enumeration, see above
00256 uint32 count     # How many elements in the field
00257 
00258 ================================================================================
00259 MSG: sensor_msgs/Image
00260 # This message contains an uncompressed image
00261 # (0, 0) is at top-left corner of image
00262 #
00263 
00264 Header header        # Header timestamp should be acquisition time of image
00265                      # Header frame_id should be optical frame of camera
00266                      # origin of frame should be optical center of cameara
00267                      # +x should point to the right in the image
00268                      # +y should point down in the image
00269                      # +z should point into to plane of the image
00270                      # If the frame_id here and the frame_id of the CameraInfo
00271                      # message associated with the image conflict
00272                      # the behavior is undefined
00273 
00274 uint32 height         # image height, that is, number of rows
00275 uint32 width          # image width, that is, number of columns
00276 
00277 # The legal values for encoding are in file src/image_encodings.cpp
00278 # If you want to standardize a new string format, join
00279 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00280 
00281 string encoding       # Encoding of pixels -- channel meaning, ordering, size
00282                       # taken from the list of strings in src/image_encodings.cpp
00283 
00284 uint8 is_bigendian    # is this data bigendian?
00285 uint32 step           # Full row length in bytes
00286 uint8[] data          # actual matrix data, size is (step * rows)
00287 
00288 ================================================================================
00289 MSG: sensor_msgs/CameraInfo
00290 # This message defines meta information for a camera. It should be in a
00291 # camera namespace on topic "camera_info" and accompanied by up to five
00292 # image topics named:
00293 #
00294 #   image_raw - raw data from the camera driver, possibly Bayer encoded
00295 #   image            - monochrome, distorted
00296 #   image_color      - color, distorted
00297 #   image_rect       - monochrome, rectified
00298 #   image_rect_color - color, rectified
00299 #
00300 # The image_pipeline contains packages (image_proc, stereo_image_proc)
00301 # for producing the four processed image topics from image_raw and
00302 # camera_info. The meaning of the camera parameters are described in
00303 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
00304 #
00305 # The image_geometry package provides a user-friendly interface to
00306 # common operations using this meta information. If you want to, e.g.,
00307 # project a 3d point into image coordinates, we strongly recommend
00308 # using image_geometry.
00309 #
00310 # If the camera is uncalibrated, the matrices D, K, R, P should be left
00311 # zeroed out. In particular, clients may assume that K[0] == 0.0
00312 # indicates an uncalibrated camera.
00313 
00314 #######################################################################
00315 #                     Image acquisition info                          #
00316 #######################################################################
00317 
00318 # Time of image acquisition, camera coordinate frame ID
00319 Header header    # Header timestamp should be acquisition time of image
00320                  # Header frame_id should be optical frame of camera
00321                  # origin of frame should be optical center of camera
00322                  # +x should point to the right in the image
00323                  # +y should point down in the image
00324                  # +z should point into the plane of the image
00325 
00326 
00327 #######################################################################
00328 #                      Calibration Parameters                         #
00329 #######################################################################
00330 # These are fixed during camera calibration. Their values will be the #
00331 # same in all messages until the camera is recalibrated. Note that    #
00332 # self-calibrating systems may "recalibrate" frequently.              #
00333 #                                                                     #
00334 # The internal parameters can be used to warp a raw (distorted) image #
00335 # to:                                                                 #
00336 #   1. An undistorted image (requires D and K)                        #
00337 #   2. A rectified image (requires D, K, R)                           #
00338 # The projection matrix P projects 3D points into the rectified image.#
00339 #######################################################################
00340 
00341 # The image dimensions with which the camera was calibrated. Normally
00342 # this will be the full camera resolution in pixels.
00343 uint32 height
00344 uint32 width
00345 
00346 # The distortion model used. Supported models are listed in
00347 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
00348 # simple model of radial and tangential distortion - is sufficent.
00349 string distortion_model
00350 
00351 # The distortion parameters, size depending on the distortion model.
00352 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
00353 float64[] D
00354 
00355 # Intrinsic camera matrix for the raw (distorted) images.
00356 #     [fx  0 cx]
00357 # K = [ 0 fy cy]
00358 #     [ 0  0  1]
00359 # Projects 3D points in the camera coordinate frame to 2D pixel
00360 # coordinates using the focal lengths (fx, fy) and principal point
00361 # (cx, cy).
00362 float64[9]  K # 3x3 row-major matrix
00363 
00364 # Rectification matrix (stereo cameras only)
00365 # A rotation matrix aligning the camera coordinate system to the ideal
00366 # stereo image plane so that epipolar lines in both stereo images are
00367 # parallel.
00368 float64[9]  R # 3x3 row-major matrix
00369 
00370 # Projection/camera matrix
00371 #     [fx'  0  cx' Tx]
00372 # P = [ 0  fy' cy' Ty]
00373 #     [ 0   0   1   0]
00374 # By convention, this matrix specifies the intrinsic (camera) matrix
00375 #  of the processed (rectified) image. That is, the left 3x3 portion
00376 #  is the normal camera intrinsic matrix for the rectified image.
00377 # It projects 3D points in the camera coordinate frame to 2D pixel
00378 #  coordinates using the focal lengths (fx', fy') and principal point
00379 #  (cx', cy') - these may differ from the values in K.
00380 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
00381 #  also have R = the identity and P[1:3,1:3] = K.
00382 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
00383 #  position of the optical center of the second camera in the first
00384 #  camera's frame. We assume Tz = 0 so both cameras are in the same
00385 #  stereo image plane. The first camera always has Tx = Ty = 0. For
00386 #  the right (second) camera of a horizontal stereo pair, Ty = 0 and
00387 #  Tx = -fx' * B, where B is the baseline between the cameras.
00388 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
00389 #  the rectified image is given by:
00390 #  [u v w]' = P * [X Y Z 1]'
00391 #         x = u / w
00392 #         y = v / w
00393 #  This holds for both images of a stereo pair.
00394 float64[12] P # 3x4 row-major matrix
00395 
00396 
00397 #######################################################################
00398 #                      Operational Parameters                         #
00399 #######################################################################
00400 # These define the image region actually captured by the camera       #
00401 # driver. Although they affect the geometry of the output image, they #
00402 # may be changed freely without recalibrating the camera.             #
00403 #######################################################################
00404 
00405 # Binning refers here to any camera setting which combines rectangular
00406 #  neighborhoods of pixels into larger "super-pixels." It reduces the
00407 #  resolution of the output image to
00408 #  (width / binning_x) x (height / binning_y).
00409 # The default values binning_x = binning_y = 0 is considered the same
00410 #  as binning_x = binning_y = 1 (no subsampling).
00411 uint32 binning_x
00412 uint32 binning_y
00413 
00414 # Region of interest (subwindow of full camera resolution), given in
00415 #  full resolution (unbinned) image coordinates. A particular ROI
00416 #  always denotes the same window of pixels on the camera sensor,
00417 #  regardless of binning settings.
00418 # The default setting of roi (all values 0) is considered the same as
00419 #  full resolution (roi.width = width, roi.height = height).
00420 RegionOfInterest roi
00421 
00422 ================================================================================
00423 MSG: sensor_msgs/RegionOfInterest
00424 # This message is used to specify a region of interest within an image.
00425 #
00426 # When used to specify the ROI setting of the camera when the image was
00427 # taken, the height and width fields should either match the height and
00428 # width fields for the associated image; or height = width = 0
00429 # indicates that the full resolution image was captured.
00430 
00431 uint32 x_offset  # Leftmost pixel of the ROI
00432                  # (0 if the ROI includes the left edge of the image)
00433 uint32 y_offset  # Topmost pixel of the ROI
00434                  # (0 if the ROI includes the top edge of the image)
00435 uint32 height    # Height of ROI
00436 uint32 width     # Width of ROI
00437 
00438 # True if a distinct rectified ROI should be calculated from the "raw"
00439 # ROI in this message. Typically this should be False if the full image
00440 # is captured (ROI not used), and True if a subwindow is captured (ROI
00441 # used).
00442 bool do_rectify
00443 
00444 ================================================================================
00445 MSG: geometry_msgs/Vector3
00446 # This represents a vector in free space. 
00447 
00448 float64 x
00449 float64 y
00450 float64 z
00451 ================================================================================
00452 MSG: object_manipulation_msgs/Grasp
00453 
00454 # The internal posture of the hand for the pre-grasp
00455 # only positions are used
00456 sensor_msgs/JointState pre_grasp_posture
00457 
00458 # The internal posture of the hand for the grasp
00459 # positions and efforts are used
00460 sensor_msgs/JointState grasp_posture
00461 
00462 # The position of the end-effector for the grasp relative to a reference frame 
00463 # (that is always specified elsewhere, not in this message)
00464 geometry_msgs/Pose grasp_pose
00465 
00466 # The estimated probability of success for this grasp
00467 float64 success_probability
00468 
00469 # Debug flag to indicate that this grasp would be the best in its cluster
00470 bool cluster_rep
00471 
00472 # how far the pre-grasp should ideally be away from the grasp
00473 float32 desired_approach_distance
00474 
00475 # how much distance between pre-grasp and grasp must actually be feasible 
00476 # for the grasp not to be rejected
00477 float32 min_approach_distance
00478 
00479 # an optional list of obstacles that we have semantic information about
00480 # and that we expect might move in the course of executing this grasp
00481 # the grasp planner is expected to make sure they move in an OK way; during
00482 # execution, grasp executors will not check for collisions against these objects
00483 GraspableObject[] moved_obstacles
00484 
00485 ================================================================================
00486 MSG: sensor_msgs/JointState
00487 # This is a message that holds data to describe the state of a set of torque controlled joints. 
00488 #
00489 # The state of each joint (revolute or prismatic) is defined by:
00490 #  * the position of the joint (rad or m),
00491 #  * the velocity of the joint (rad/s or m/s) and 
00492 #  * the effort that is applied in the joint (Nm or N).
00493 #
00494 # Each joint is uniquely identified by its name
00495 # The header specifies the time at which the joint states were recorded. All the joint states
00496 # in one message have to be recorded at the same time.
00497 #
00498 # This message consists of a multiple arrays, one for each part of the joint state. 
00499 # The goal is to make each of the fields optional. When e.g. your joints have no
00500 # effort associated with them, you can leave the effort array empty. 
00501 #
00502 # All arrays in this message should have the same size, or be empty.
00503 # This is the only way to uniquely associate the joint name with the correct
00504 # states.
00505 
00506 
00507 Header header
00508 
00509 string[] name
00510 float64[] position
00511 float64[] velocity
00512 float64[] effort
00513 
00514 """
00515   __slots__ = ['arm_name','target','collision_object_name','collision_support_surface_name','grasps_to_evaluate','movable_obstacles']
00516   _slot_types = ['string','object_manipulation_msgs/GraspableObject','string','string','object_manipulation_msgs/Grasp[]','object_manipulation_msgs/GraspableObject[]']
00517 
00518   def __init__(self, *args, **kwds):
00519     """
00520     Constructor. Any message fields that are implicitly/explicitly
00521     set to None will be assigned a default value. The recommend
00522     use is keyword arguments as this is more robust to future message
00523     changes.  You cannot mix in-order arguments and keyword arguments.
00524 
00525     The available fields are:
00526        arm_name,target,collision_object_name,collision_support_surface_name,grasps_to_evaluate,movable_obstacles
00527 
00528     :param args: complete set of field values, in .msg order
00529     :param kwds: use keyword arguments corresponding to message field names
00530     to set specific fields.
00531     """
00532     if args or kwds:
00533       super(GraspPlanningGoal, self).__init__(*args, **kwds)
00534       #message fields cannot be None, assign default values for those that are
00535       if self.arm_name is None:
00536         self.arm_name = ''
00537       if self.target is None:
00538         self.target = object_manipulation_msgs.msg.GraspableObject()
00539       if self.collision_object_name is None:
00540         self.collision_object_name = ''
00541       if self.collision_support_surface_name is None:
00542         self.collision_support_surface_name = ''
00543       if self.grasps_to_evaluate is None:
00544         self.grasps_to_evaluate = []
00545       if self.movable_obstacles is None:
00546         self.movable_obstacles = []
00547     else:
00548       self.arm_name = ''
00549       self.target = object_manipulation_msgs.msg.GraspableObject()
00550       self.collision_object_name = ''
00551       self.collision_support_surface_name = ''
00552       self.grasps_to_evaluate = []
00553       self.movable_obstacles = []
00554 
00555   def _get_types(self):
00556     """
00557     internal API method
00558     """
00559     return self._slot_types
00560 
00561   def serialize(self, buff):
00562     """
00563     serialize message into buffer
00564     :param buff: buffer, ``StringIO``
00565     """
00566     try:
00567       _x = self.arm_name
00568       length = len(_x)
00569       if python3 or type(_x) == unicode:
00570         _x = _x.encode('utf-8')
00571         length = len(_x)
00572       buff.write(struct.pack('<I%ss'%length, length, _x))
00573       _x = self.target.reference_frame_id
00574       length = len(_x)
00575       if python3 or type(_x) == unicode:
00576         _x = _x.encode('utf-8')
00577         length = len(_x)
00578       buff.write(struct.pack('<I%ss'%length, length, _x))
00579       length = len(self.target.potential_models)
00580       buff.write(_struct_I.pack(length))
00581       for val1 in self.target.potential_models:
00582         buff.write(_struct_i.pack(val1.model_id))
00583         _v1 = val1.pose
00584         _v2 = _v1.header
00585         buff.write(_struct_I.pack(_v2.seq))
00586         _v3 = _v2.stamp
00587         _x = _v3
00588         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00589         _x = _v2.frame_id
00590         length = len(_x)
00591         if python3 or type(_x) == unicode:
00592           _x = _x.encode('utf-8')
00593           length = len(_x)
00594         buff.write(struct.pack('<I%ss'%length, length, _x))
00595         _v4 = _v1.pose
00596         _v5 = _v4.position
00597         _x = _v5
00598         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00599         _v6 = _v4.orientation
00600         _x = _v6
00601         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00602         buff.write(_struct_f.pack(val1.confidence))
00603         _x = val1.detector_name
00604         length = len(_x)
00605         if python3 or type(_x) == unicode:
00606           _x = _x.encode('utf-8')
00607           length = len(_x)
00608         buff.write(struct.pack('<I%ss'%length, length, _x))
00609       _x = self
00610       buff.write(_struct_3I.pack(_x.target.cluster.header.seq, _x.target.cluster.header.stamp.secs, _x.target.cluster.header.stamp.nsecs))
00611       _x = self.target.cluster.header.frame_id
00612       length = len(_x)
00613       if python3 or type(_x) == unicode:
00614         _x = _x.encode('utf-8')
00615         length = len(_x)
00616       buff.write(struct.pack('<I%ss'%length, length, _x))
00617       length = len(self.target.cluster.points)
00618       buff.write(_struct_I.pack(length))
00619       for val1 in self.target.cluster.points:
00620         _x = val1
00621         buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00622       length = len(self.target.cluster.channels)
00623       buff.write(_struct_I.pack(length))
00624       for val1 in self.target.cluster.channels:
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         length = len(val1.values)
00632         buff.write(_struct_I.pack(length))
00633         pattern = '<%sf'%length
00634         buff.write(struct.pack(pattern, *val1.values))
00635       _x = self
00636       buff.write(_struct_3I.pack(_x.target.region.cloud.header.seq, _x.target.region.cloud.header.stamp.secs, _x.target.region.cloud.header.stamp.nsecs))
00637       _x = self.target.region.cloud.header.frame_id
00638       length = len(_x)
00639       if python3 or type(_x) == unicode:
00640         _x = _x.encode('utf-8')
00641         length = len(_x)
00642       buff.write(struct.pack('<I%ss'%length, length, _x))
00643       _x = self
00644       buff.write(_struct_2I.pack(_x.target.region.cloud.height, _x.target.region.cloud.width))
00645       length = len(self.target.region.cloud.fields)
00646       buff.write(_struct_I.pack(length))
00647       for val1 in self.target.region.cloud.fields:
00648         _x = val1.name
00649         length = len(_x)
00650         if python3 or type(_x) == unicode:
00651           _x = _x.encode('utf-8')
00652           length = len(_x)
00653         buff.write(struct.pack('<I%ss'%length, length, _x))
00654         _x = val1
00655         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00656       _x = self
00657       buff.write(_struct_B2I.pack(_x.target.region.cloud.is_bigendian, _x.target.region.cloud.point_step, _x.target.region.cloud.row_step))
00658       _x = self.target.region.cloud.data
00659       length = len(_x)
00660       # - if encoded as a list instead, serialize as bytes instead of string
00661       if type(_x) in [list, tuple]:
00662         buff.write(struct.pack('<I%sB'%length, length, *_x))
00663       else:
00664         buff.write(struct.pack('<I%ss'%length, length, _x))
00665       buff.write(_struct_B.pack(self.target.region.cloud.is_dense))
00666       length = len(self.target.region.mask)
00667       buff.write(_struct_I.pack(length))
00668       pattern = '<%si'%length
00669       buff.write(struct.pack(pattern, *self.target.region.mask))
00670       _x = self
00671       buff.write(_struct_3I.pack(_x.target.region.image.header.seq, _x.target.region.image.header.stamp.secs, _x.target.region.image.header.stamp.nsecs))
00672       _x = self.target.region.image.header.frame_id
00673       length = len(_x)
00674       if python3 or type(_x) == unicode:
00675         _x = _x.encode('utf-8')
00676         length = len(_x)
00677       buff.write(struct.pack('<I%ss'%length, length, _x))
00678       _x = self
00679       buff.write(_struct_2I.pack(_x.target.region.image.height, _x.target.region.image.width))
00680       _x = self.target.region.image.encoding
00681       length = len(_x)
00682       if python3 or type(_x) == unicode:
00683         _x = _x.encode('utf-8')
00684         length = len(_x)
00685       buff.write(struct.pack('<I%ss'%length, length, _x))
00686       _x = self
00687       buff.write(_struct_BI.pack(_x.target.region.image.is_bigendian, _x.target.region.image.step))
00688       _x = self.target.region.image.data
00689       length = len(_x)
00690       # - if encoded as a list instead, serialize as bytes instead of string
00691       if type(_x) in [list, tuple]:
00692         buff.write(struct.pack('<I%sB'%length, length, *_x))
00693       else:
00694         buff.write(struct.pack('<I%ss'%length, length, _x))
00695       _x = self
00696       buff.write(_struct_3I.pack(_x.target.region.disparity_image.header.seq, _x.target.region.disparity_image.header.stamp.secs, _x.target.region.disparity_image.header.stamp.nsecs))
00697       _x = self.target.region.disparity_image.header.frame_id
00698       length = len(_x)
00699       if python3 or type(_x) == unicode:
00700         _x = _x.encode('utf-8')
00701         length = len(_x)
00702       buff.write(struct.pack('<I%ss'%length, length, _x))
00703       _x = self
00704       buff.write(_struct_2I.pack(_x.target.region.disparity_image.height, _x.target.region.disparity_image.width))
00705       _x = self.target.region.disparity_image.encoding
00706       length = len(_x)
00707       if python3 or type(_x) == unicode:
00708         _x = _x.encode('utf-8')
00709         length = len(_x)
00710       buff.write(struct.pack('<I%ss'%length, length, _x))
00711       _x = self
00712       buff.write(_struct_BI.pack(_x.target.region.disparity_image.is_bigendian, _x.target.region.disparity_image.step))
00713       _x = self.target.region.disparity_image.data
00714       length = len(_x)
00715       # - if encoded as a list instead, serialize as bytes instead of string
00716       if type(_x) in [list, tuple]:
00717         buff.write(struct.pack('<I%sB'%length, length, *_x))
00718       else:
00719         buff.write(struct.pack('<I%ss'%length, length, _x))
00720       _x = self
00721       buff.write(_struct_3I.pack(_x.target.region.cam_info.header.seq, _x.target.region.cam_info.header.stamp.secs, _x.target.region.cam_info.header.stamp.nsecs))
00722       _x = self.target.region.cam_info.header.frame_id
00723       length = len(_x)
00724       if python3 or type(_x) == unicode:
00725         _x = _x.encode('utf-8')
00726         length = len(_x)
00727       buff.write(struct.pack('<I%ss'%length, length, _x))
00728       _x = self
00729       buff.write(_struct_2I.pack(_x.target.region.cam_info.height, _x.target.region.cam_info.width))
00730       _x = self.target.region.cam_info.distortion_model
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.target.region.cam_info.D)
00737       buff.write(_struct_I.pack(length))
00738       pattern = '<%sd'%length
00739       buff.write(struct.pack(pattern, *self.target.region.cam_info.D))
00740       buff.write(_struct_9d.pack(*self.target.region.cam_info.K))
00741       buff.write(_struct_9d.pack(*self.target.region.cam_info.R))
00742       buff.write(_struct_12d.pack(*self.target.region.cam_info.P))
00743       _x = self
00744       buff.write(_struct_6IB3I.pack(_x.target.region.cam_info.binning_x, _x.target.region.cam_info.binning_y, _x.target.region.cam_info.roi.x_offset, _x.target.region.cam_info.roi.y_offset, _x.target.region.cam_info.roi.height, _x.target.region.cam_info.roi.width, _x.target.region.cam_info.roi.do_rectify, _x.target.region.roi_box_pose.header.seq, _x.target.region.roi_box_pose.header.stamp.secs, _x.target.region.roi_box_pose.header.stamp.nsecs))
00745       _x = self.target.region.roi_box_pose.header.frame_id
00746       length = len(_x)
00747       if python3 or type(_x) == unicode:
00748         _x = _x.encode('utf-8')
00749         length = len(_x)
00750       buff.write(struct.pack('<I%ss'%length, length, _x))
00751       _x = self
00752       buff.write(_struct_10d.pack(_x.target.region.roi_box_pose.pose.position.x, _x.target.region.roi_box_pose.pose.position.y, _x.target.region.roi_box_pose.pose.position.z, _x.target.region.roi_box_pose.pose.orientation.x, _x.target.region.roi_box_pose.pose.orientation.y, _x.target.region.roi_box_pose.pose.orientation.z, _x.target.region.roi_box_pose.pose.orientation.w, _x.target.region.roi_box_dims.x, _x.target.region.roi_box_dims.y, _x.target.region.roi_box_dims.z))
00753       _x = self.target.collision_name
00754       length = len(_x)
00755       if python3 or type(_x) == unicode:
00756         _x = _x.encode('utf-8')
00757         length = len(_x)
00758       buff.write(struct.pack('<I%ss'%length, length, _x))
00759       _x = self.collision_object_name
00760       length = len(_x)
00761       if python3 or type(_x) == unicode:
00762         _x = _x.encode('utf-8')
00763         length = len(_x)
00764       buff.write(struct.pack('<I%ss'%length, length, _x))
00765       _x = self.collision_support_surface_name
00766       length = len(_x)
00767       if python3 or type(_x) == unicode:
00768         _x = _x.encode('utf-8')
00769         length = len(_x)
00770       buff.write(struct.pack('<I%ss'%length, length, _x))
00771       length = len(self.grasps_to_evaluate)
00772       buff.write(_struct_I.pack(length))
00773       for val1 in self.grasps_to_evaluate:
00774         _v7 = val1.pre_grasp_posture
00775         _v8 = _v7.header
00776         buff.write(_struct_I.pack(_v8.seq))
00777         _v9 = _v8.stamp
00778         _x = _v9
00779         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00780         _x = _v8.frame_id
00781         length = len(_x)
00782         if python3 or type(_x) == unicode:
00783           _x = _x.encode('utf-8')
00784           length = len(_x)
00785         buff.write(struct.pack('<I%ss'%length, length, _x))
00786         length = len(_v7.name)
00787         buff.write(_struct_I.pack(length))
00788         for val3 in _v7.name:
00789           length = len(val3)
00790           if python3 or type(val3) == unicode:
00791             val3 = val3.encode('utf-8')
00792             length = len(val3)
00793           buff.write(struct.pack('<I%ss'%length, length, val3))
00794         length = len(_v7.position)
00795         buff.write(_struct_I.pack(length))
00796         pattern = '<%sd'%length
00797         buff.write(struct.pack(pattern, *_v7.position))
00798         length = len(_v7.velocity)
00799         buff.write(_struct_I.pack(length))
00800         pattern = '<%sd'%length
00801         buff.write(struct.pack(pattern, *_v7.velocity))
00802         length = len(_v7.effort)
00803         buff.write(_struct_I.pack(length))
00804         pattern = '<%sd'%length
00805         buff.write(struct.pack(pattern, *_v7.effort))
00806         _v10 = val1.grasp_posture
00807         _v11 = _v10.header
00808         buff.write(_struct_I.pack(_v11.seq))
00809         _v12 = _v11.stamp
00810         _x = _v12
00811         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00812         _x = _v11.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         length = len(_v10.name)
00819         buff.write(_struct_I.pack(length))
00820         for val3 in _v10.name:
00821           length = len(val3)
00822           if python3 or type(val3) == unicode:
00823             val3 = val3.encode('utf-8')
00824             length = len(val3)
00825           buff.write(struct.pack('<I%ss'%length, length, val3))
00826         length = len(_v10.position)
00827         buff.write(_struct_I.pack(length))
00828         pattern = '<%sd'%length
00829         buff.write(struct.pack(pattern, *_v10.position))
00830         length = len(_v10.velocity)
00831         buff.write(_struct_I.pack(length))
00832         pattern = '<%sd'%length
00833         buff.write(struct.pack(pattern, *_v10.velocity))
00834         length = len(_v10.effort)
00835         buff.write(_struct_I.pack(length))
00836         pattern = '<%sd'%length
00837         buff.write(struct.pack(pattern, *_v10.effort))
00838         _v13 = val1.grasp_pose
00839         _v14 = _v13.position
00840         _x = _v14
00841         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00842         _v15 = _v13.orientation
00843         _x = _v15
00844         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00845         _x = val1
00846         buff.write(_struct_dB2f.pack(_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance))
00847         length = len(val1.moved_obstacles)
00848         buff.write(_struct_I.pack(length))
00849         for val2 in val1.moved_obstacles:
00850           _x = val2.reference_frame_id
00851           length = len(_x)
00852           if python3 or type(_x) == unicode:
00853             _x = _x.encode('utf-8')
00854             length = len(_x)
00855           buff.write(struct.pack('<I%ss'%length, length, _x))
00856           length = len(val2.potential_models)
00857           buff.write(_struct_I.pack(length))
00858           for val3 in val2.potential_models:
00859             buff.write(_struct_i.pack(val3.model_id))
00860             _v16 = val3.pose
00861             _v17 = _v16.header
00862             buff.write(_struct_I.pack(_v17.seq))
00863             _v18 = _v17.stamp
00864             _x = _v18
00865             buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00866             _x = _v17.frame_id
00867             length = len(_x)
00868             if python3 or type(_x) == unicode:
00869               _x = _x.encode('utf-8')
00870               length = len(_x)
00871             buff.write(struct.pack('<I%ss'%length, length, _x))
00872             _v19 = _v16.pose
00873             _v20 = _v19.position
00874             _x = _v20
00875             buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00876             _v21 = _v19.orientation
00877             _x = _v21
00878             buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00879             buff.write(_struct_f.pack(val3.confidence))
00880             _x = val3.detector_name
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           _v22 = val2.cluster
00887           _v23 = _v22.header
00888           buff.write(_struct_I.pack(_v23.seq))
00889           _v24 = _v23.stamp
00890           _x = _v24
00891           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00892           _x = _v23.frame_id
00893           length = len(_x)
00894           if python3 or type(_x) == unicode:
00895             _x = _x.encode('utf-8')
00896             length = len(_x)
00897           buff.write(struct.pack('<I%ss'%length, length, _x))
00898           length = len(_v22.points)
00899           buff.write(_struct_I.pack(length))
00900           for val4 in _v22.points:
00901             _x = val4
00902             buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00903           length = len(_v22.channels)
00904           buff.write(_struct_I.pack(length))
00905           for val4 in _v22.channels:
00906             _x = val4.name
00907             length = len(_x)
00908             if python3 or type(_x) == unicode:
00909               _x = _x.encode('utf-8')
00910               length = len(_x)
00911             buff.write(struct.pack('<I%ss'%length, length, _x))
00912             length = len(val4.values)
00913             buff.write(_struct_I.pack(length))
00914             pattern = '<%sf'%length
00915             buff.write(struct.pack(pattern, *val4.values))
00916           _v25 = val2.region
00917           _v26 = _v25.cloud
00918           _v27 = _v26.header
00919           buff.write(_struct_I.pack(_v27.seq))
00920           _v28 = _v27.stamp
00921           _x = _v28
00922           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00923           _x = _v27.frame_id
00924           length = len(_x)
00925           if python3 or type(_x) == unicode:
00926             _x = _x.encode('utf-8')
00927             length = len(_x)
00928           buff.write(struct.pack('<I%ss'%length, length, _x))
00929           _x = _v26
00930           buff.write(_struct_2I.pack(_x.height, _x.width))
00931           length = len(_v26.fields)
00932           buff.write(_struct_I.pack(length))
00933           for val5 in _v26.fields:
00934             _x = val5.name
00935             length = len(_x)
00936             if python3 or type(_x) == unicode:
00937               _x = _x.encode('utf-8')
00938               length = len(_x)
00939             buff.write(struct.pack('<I%ss'%length, length, _x))
00940             _x = val5
00941             buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00942           _x = _v26
00943           buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
00944           _x = _v26.data
00945           length = len(_x)
00946           # - if encoded as a list instead, serialize as bytes instead of string
00947           if type(_x) in [list, tuple]:
00948             buff.write(struct.pack('<I%sB'%length, length, *_x))
00949           else:
00950             buff.write(struct.pack('<I%ss'%length, length, _x))
00951           buff.write(_struct_B.pack(_v26.is_dense))
00952           length = len(_v25.mask)
00953           buff.write(_struct_I.pack(length))
00954           pattern = '<%si'%length
00955           buff.write(struct.pack(pattern, *_v25.mask))
00956           _v29 = _v25.image
00957           _v30 = _v29.header
00958           buff.write(_struct_I.pack(_v30.seq))
00959           _v31 = _v30.stamp
00960           _x = _v31
00961           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00962           _x = _v30.frame_id
00963           length = len(_x)
00964           if python3 or type(_x) == unicode:
00965             _x = _x.encode('utf-8')
00966             length = len(_x)
00967           buff.write(struct.pack('<I%ss'%length, length, _x))
00968           _x = _v29
00969           buff.write(_struct_2I.pack(_x.height, _x.width))
00970           _x = _v29.encoding
00971           length = len(_x)
00972           if python3 or type(_x) == unicode:
00973             _x = _x.encode('utf-8')
00974             length = len(_x)
00975           buff.write(struct.pack('<I%ss'%length, length, _x))
00976           _x = _v29
00977           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
00978           _x = _v29.data
00979           length = len(_x)
00980           # - if encoded as a list instead, serialize as bytes instead of string
00981           if type(_x) in [list, tuple]:
00982             buff.write(struct.pack('<I%sB'%length, length, *_x))
00983           else:
00984             buff.write(struct.pack('<I%ss'%length, length, _x))
00985           _v32 = _v25.disparity_image
00986           _v33 = _v32.header
00987           buff.write(_struct_I.pack(_v33.seq))
00988           _v34 = _v33.stamp
00989           _x = _v34
00990           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00991           _x = _v33.frame_id
00992           length = len(_x)
00993           if python3 or type(_x) == unicode:
00994             _x = _x.encode('utf-8')
00995             length = len(_x)
00996           buff.write(struct.pack('<I%ss'%length, length, _x))
00997           _x = _v32
00998           buff.write(_struct_2I.pack(_x.height, _x.width))
00999           _x = _v32.encoding
01000           length = len(_x)
01001           if python3 or type(_x) == unicode:
01002             _x = _x.encode('utf-8')
01003             length = len(_x)
01004           buff.write(struct.pack('<I%ss'%length, length, _x))
01005           _x = _v32
01006           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
01007           _x = _v32.data
01008           length = len(_x)
01009           # - if encoded as a list instead, serialize as bytes instead of string
01010           if type(_x) in [list, tuple]:
01011             buff.write(struct.pack('<I%sB'%length, length, *_x))
01012           else:
01013             buff.write(struct.pack('<I%ss'%length, length, _x))
01014           _v35 = _v25.cam_info
01015           _v36 = _v35.header
01016           buff.write(_struct_I.pack(_v36.seq))
01017           _v37 = _v36.stamp
01018           _x = _v37
01019           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01020           _x = _v36.frame_id
01021           length = len(_x)
01022           if python3 or type(_x) == unicode:
01023             _x = _x.encode('utf-8')
01024             length = len(_x)
01025           buff.write(struct.pack('<I%ss'%length, length, _x))
01026           _x = _v35
01027           buff.write(_struct_2I.pack(_x.height, _x.width))
01028           _x = _v35.distortion_model
01029           length = len(_x)
01030           if python3 or type(_x) == unicode:
01031             _x = _x.encode('utf-8')
01032             length = len(_x)
01033           buff.write(struct.pack('<I%ss'%length, length, _x))
01034           length = len(_v35.D)
01035           buff.write(_struct_I.pack(length))
01036           pattern = '<%sd'%length
01037           buff.write(struct.pack(pattern, *_v35.D))
01038           buff.write(_struct_9d.pack(*_v35.K))
01039           buff.write(_struct_9d.pack(*_v35.R))
01040           buff.write(_struct_12d.pack(*_v35.P))
01041           _x = _v35
01042           buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
01043           _v38 = _v35.roi
01044           _x = _v38
01045           buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
01046           _v39 = _v25.roi_box_pose
01047           _v40 = _v39.header
01048           buff.write(_struct_I.pack(_v40.seq))
01049           _v41 = _v40.stamp
01050           _x = _v41
01051           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01052           _x = _v40.frame_id
01053           length = len(_x)
01054           if python3 or type(_x) == unicode:
01055             _x = _x.encode('utf-8')
01056             length = len(_x)
01057           buff.write(struct.pack('<I%ss'%length, length, _x))
01058           _v42 = _v39.pose
01059           _v43 = _v42.position
01060           _x = _v43
01061           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01062           _v44 = _v42.orientation
01063           _x = _v44
01064           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01065           _v45 = _v25.roi_box_dims
01066           _x = _v45
01067           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01068           _x = val2.collision_name
01069           length = len(_x)
01070           if python3 or type(_x) == unicode:
01071             _x = _x.encode('utf-8')
01072             length = len(_x)
01073           buff.write(struct.pack('<I%ss'%length, length, _x))
01074       length = len(self.movable_obstacles)
01075       buff.write(_struct_I.pack(length))
01076       for val1 in self.movable_obstacles:
01077         _x = val1.reference_frame_id
01078         length = len(_x)
01079         if python3 or type(_x) == unicode:
01080           _x = _x.encode('utf-8')
01081           length = len(_x)
01082         buff.write(struct.pack('<I%ss'%length, length, _x))
01083         length = len(val1.potential_models)
01084         buff.write(_struct_I.pack(length))
01085         for val2 in val1.potential_models:
01086           buff.write(_struct_i.pack(val2.model_id))
01087           _v46 = val2.pose
01088           _v47 = _v46.header
01089           buff.write(_struct_I.pack(_v47.seq))
01090           _v48 = _v47.stamp
01091           _x = _v48
01092           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01093           _x = _v47.frame_id
01094           length = len(_x)
01095           if python3 or type(_x) == unicode:
01096             _x = _x.encode('utf-8')
01097             length = len(_x)
01098           buff.write(struct.pack('<I%ss'%length, length, _x))
01099           _v49 = _v46.pose
01100           _v50 = _v49.position
01101           _x = _v50
01102           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01103           _v51 = _v49.orientation
01104           _x = _v51
01105           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01106           buff.write(_struct_f.pack(val2.confidence))
01107           _x = val2.detector_name
01108           length = len(_x)
01109           if python3 or type(_x) == unicode:
01110             _x = _x.encode('utf-8')
01111             length = len(_x)
01112           buff.write(struct.pack('<I%ss'%length, length, _x))
01113         _v52 = val1.cluster
01114         _v53 = _v52.header
01115         buff.write(_struct_I.pack(_v53.seq))
01116         _v54 = _v53.stamp
01117         _x = _v54
01118         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01119         _x = _v53.frame_id
01120         length = len(_x)
01121         if python3 or type(_x) == unicode:
01122           _x = _x.encode('utf-8')
01123           length = len(_x)
01124         buff.write(struct.pack('<I%ss'%length, length, _x))
01125         length = len(_v52.points)
01126         buff.write(_struct_I.pack(length))
01127         for val3 in _v52.points:
01128           _x = val3
01129           buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
01130         length = len(_v52.channels)
01131         buff.write(_struct_I.pack(length))
01132         for val3 in _v52.channels:
01133           _x = val3.name
01134           length = len(_x)
01135           if python3 or type(_x) == unicode:
01136             _x = _x.encode('utf-8')
01137             length = len(_x)
01138           buff.write(struct.pack('<I%ss'%length, length, _x))
01139           length = len(val3.values)
01140           buff.write(_struct_I.pack(length))
01141           pattern = '<%sf'%length
01142           buff.write(struct.pack(pattern, *val3.values))
01143         _v55 = val1.region
01144         _v56 = _v55.cloud
01145         _v57 = _v56.header
01146         buff.write(_struct_I.pack(_v57.seq))
01147         _v58 = _v57.stamp
01148         _x = _v58
01149         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01150         _x = _v57.frame_id
01151         length = len(_x)
01152         if python3 or type(_x) == unicode:
01153           _x = _x.encode('utf-8')
01154           length = len(_x)
01155         buff.write(struct.pack('<I%ss'%length, length, _x))
01156         _x = _v56
01157         buff.write(_struct_2I.pack(_x.height, _x.width))
01158         length = len(_v56.fields)
01159         buff.write(_struct_I.pack(length))
01160         for val4 in _v56.fields:
01161           _x = val4.name
01162           length = len(_x)
01163           if python3 or type(_x) == unicode:
01164             _x = _x.encode('utf-8')
01165             length = len(_x)
01166           buff.write(struct.pack('<I%ss'%length, length, _x))
01167           _x = val4
01168           buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
01169         _x = _v56
01170         buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
01171         _x = _v56.data
01172         length = len(_x)
01173         # - if encoded as a list instead, serialize as bytes instead of string
01174         if type(_x) in [list, tuple]:
01175           buff.write(struct.pack('<I%sB'%length, length, *_x))
01176         else:
01177           buff.write(struct.pack('<I%ss'%length, length, _x))
01178         buff.write(_struct_B.pack(_v56.is_dense))
01179         length = len(_v55.mask)
01180         buff.write(_struct_I.pack(length))
01181         pattern = '<%si'%length
01182         buff.write(struct.pack(pattern, *_v55.mask))
01183         _v59 = _v55.image
01184         _v60 = _v59.header
01185         buff.write(_struct_I.pack(_v60.seq))
01186         _v61 = _v60.stamp
01187         _x = _v61
01188         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01189         _x = _v60.frame_id
01190         length = len(_x)
01191         if python3 or type(_x) == unicode:
01192           _x = _x.encode('utf-8')
01193           length = len(_x)
01194         buff.write(struct.pack('<I%ss'%length, length, _x))
01195         _x = _v59
01196         buff.write(_struct_2I.pack(_x.height, _x.width))
01197         _x = _v59.encoding
01198         length = len(_x)
01199         if python3 or type(_x) == unicode:
01200           _x = _x.encode('utf-8')
01201           length = len(_x)
01202         buff.write(struct.pack('<I%ss'%length, length, _x))
01203         _x = _v59
01204         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
01205         _x = _v59.data
01206         length = len(_x)
01207         # - if encoded as a list instead, serialize as bytes instead of string
01208         if type(_x) in [list, tuple]:
01209           buff.write(struct.pack('<I%sB'%length, length, *_x))
01210         else:
01211           buff.write(struct.pack('<I%ss'%length, length, _x))
01212         _v62 = _v55.disparity_image
01213         _v63 = _v62.header
01214         buff.write(_struct_I.pack(_v63.seq))
01215         _v64 = _v63.stamp
01216         _x = _v64
01217         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01218         _x = _v63.frame_id
01219         length = len(_x)
01220         if python3 or type(_x) == unicode:
01221           _x = _x.encode('utf-8')
01222           length = len(_x)
01223         buff.write(struct.pack('<I%ss'%length, length, _x))
01224         _x = _v62
01225         buff.write(_struct_2I.pack(_x.height, _x.width))
01226         _x = _v62.encoding
01227         length = len(_x)
01228         if python3 or type(_x) == unicode:
01229           _x = _x.encode('utf-8')
01230           length = len(_x)
01231         buff.write(struct.pack('<I%ss'%length, length, _x))
01232         _x = _v62
01233         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
01234         _x = _v62.data
01235         length = len(_x)
01236         # - if encoded as a list instead, serialize as bytes instead of string
01237         if type(_x) in [list, tuple]:
01238           buff.write(struct.pack('<I%sB'%length, length, *_x))
01239         else:
01240           buff.write(struct.pack('<I%ss'%length, length, _x))
01241         _v65 = _v55.cam_info
01242         _v66 = _v65.header
01243         buff.write(_struct_I.pack(_v66.seq))
01244         _v67 = _v66.stamp
01245         _x = _v67
01246         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01247         _x = _v66.frame_id
01248         length = len(_x)
01249         if python3 or type(_x) == unicode:
01250           _x = _x.encode('utf-8')
01251           length = len(_x)
01252         buff.write(struct.pack('<I%ss'%length, length, _x))
01253         _x = _v65
01254         buff.write(_struct_2I.pack(_x.height, _x.width))
01255         _x = _v65.distortion_model
01256         length = len(_x)
01257         if python3 or type(_x) == unicode:
01258           _x = _x.encode('utf-8')
01259           length = len(_x)
01260         buff.write(struct.pack('<I%ss'%length, length, _x))
01261         length = len(_v65.D)
01262         buff.write(_struct_I.pack(length))
01263         pattern = '<%sd'%length
01264         buff.write(struct.pack(pattern, *_v65.D))
01265         buff.write(_struct_9d.pack(*_v65.K))
01266         buff.write(_struct_9d.pack(*_v65.R))
01267         buff.write(_struct_12d.pack(*_v65.P))
01268         _x = _v65
01269         buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
01270         _v68 = _v65.roi
01271         _x = _v68
01272         buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
01273         _v69 = _v55.roi_box_pose
01274         _v70 = _v69.header
01275         buff.write(_struct_I.pack(_v70.seq))
01276         _v71 = _v70.stamp
01277         _x = _v71
01278         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01279         _x = _v70.frame_id
01280         length = len(_x)
01281         if python3 or type(_x) == unicode:
01282           _x = _x.encode('utf-8')
01283           length = len(_x)
01284         buff.write(struct.pack('<I%ss'%length, length, _x))
01285         _v72 = _v69.pose
01286         _v73 = _v72.position
01287         _x = _v73
01288         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01289         _v74 = _v72.orientation
01290         _x = _v74
01291         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01292         _v75 = _v55.roi_box_dims
01293         _x = _v75
01294         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01295         _x = val1.collision_name
01296         length = len(_x)
01297         if python3 or type(_x) == unicode:
01298           _x = _x.encode('utf-8')
01299           length = len(_x)
01300         buff.write(struct.pack('<I%ss'%length, length, _x))
01301     except struct.error as se: self._check_types(se)
01302     except TypeError as te: self._check_types(te)
01303 
01304   def deserialize(self, str):
01305     """
01306     unpack serialized message in str into this message instance
01307     :param str: byte array of serialized message, ``str``
01308     """
01309     try:
01310       if self.target is None:
01311         self.target = object_manipulation_msgs.msg.GraspableObject()
01312       if self.grasps_to_evaluate is None:
01313         self.grasps_to_evaluate = None
01314       if self.movable_obstacles is None:
01315         self.movable_obstacles = None
01316       end = 0
01317       start = end
01318       end += 4
01319       (length,) = _struct_I.unpack(str[start:end])
01320       start = end
01321       end += length
01322       if python3:
01323         self.arm_name = str[start:end].decode('utf-8')
01324       else:
01325         self.arm_name = str[start:end]
01326       start = end
01327       end += 4
01328       (length,) = _struct_I.unpack(str[start:end])
01329       start = end
01330       end += length
01331       if python3:
01332         self.target.reference_frame_id = str[start:end].decode('utf-8')
01333       else:
01334         self.target.reference_frame_id = str[start:end]
01335       start = end
01336       end += 4
01337       (length,) = _struct_I.unpack(str[start:end])
01338       self.target.potential_models = []
01339       for i in range(0, length):
01340         val1 = household_objects_database_msgs.msg.DatabaseModelPose()
01341         start = end
01342         end += 4
01343         (val1.model_id,) = _struct_i.unpack(str[start:end])
01344         _v76 = val1.pose
01345         _v77 = _v76.header
01346         start = end
01347         end += 4
01348         (_v77.seq,) = _struct_I.unpack(str[start:end])
01349         _v78 = _v77.stamp
01350         _x = _v78
01351         start = end
01352         end += 8
01353         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01354         start = end
01355         end += 4
01356         (length,) = _struct_I.unpack(str[start:end])
01357         start = end
01358         end += length
01359         if python3:
01360           _v77.frame_id = str[start:end].decode('utf-8')
01361         else:
01362           _v77.frame_id = str[start:end]
01363         _v79 = _v76.pose
01364         _v80 = _v79.position
01365         _x = _v80
01366         start = end
01367         end += 24
01368         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01369         _v81 = _v79.orientation
01370         _x = _v81
01371         start = end
01372         end += 32
01373         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01374         start = end
01375         end += 4
01376         (val1.confidence,) = _struct_f.unpack(str[start:end])
01377         start = end
01378         end += 4
01379         (length,) = _struct_I.unpack(str[start:end])
01380         start = end
01381         end += length
01382         if python3:
01383           val1.detector_name = str[start:end].decode('utf-8')
01384         else:
01385           val1.detector_name = str[start:end]
01386         self.target.potential_models.append(val1)
01387       _x = self
01388       start = end
01389       end += 12
01390       (_x.target.cluster.header.seq, _x.target.cluster.header.stamp.secs, _x.target.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01391       start = end
01392       end += 4
01393       (length,) = _struct_I.unpack(str[start:end])
01394       start = end
01395       end += length
01396       if python3:
01397         self.target.cluster.header.frame_id = str[start:end].decode('utf-8')
01398       else:
01399         self.target.cluster.header.frame_id = str[start:end]
01400       start = end
01401       end += 4
01402       (length,) = _struct_I.unpack(str[start:end])
01403       self.target.cluster.points = []
01404       for i in range(0, length):
01405         val1 = geometry_msgs.msg.Point32()
01406         _x = val1
01407         start = end
01408         end += 12
01409         (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01410         self.target.cluster.points.append(val1)
01411       start = end
01412       end += 4
01413       (length,) = _struct_I.unpack(str[start:end])
01414       self.target.cluster.channels = []
01415       for i in range(0, length):
01416         val1 = sensor_msgs.msg.ChannelFloat32()
01417         start = end
01418         end += 4
01419         (length,) = _struct_I.unpack(str[start:end])
01420         start = end
01421         end += length
01422         if python3:
01423           val1.name = str[start:end].decode('utf-8')
01424         else:
01425           val1.name = str[start:end]
01426         start = end
01427         end += 4
01428         (length,) = _struct_I.unpack(str[start:end])
01429         pattern = '<%sf'%length
01430         start = end
01431         end += struct.calcsize(pattern)
01432         val1.values = struct.unpack(pattern, str[start:end])
01433         self.target.cluster.channels.append(val1)
01434       _x = self
01435       start = end
01436       end += 12
01437       (_x.target.region.cloud.header.seq, _x.target.region.cloud.header.stamp.secs, _x.target.region.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01438       start = end
01439       end += 4
01440       (length,) = _struct_I.unpack(str[start:end])
01441       start = end
01442       end += length
01443       if python3:
01444         self.target.region.cloud.header.frame_id = str[start:end].decode('utf-8')
01445       else:
01446         self.target.region.cloud.header.frame_id = str[start:end]
01447       _x = self
01448       start = end
01449       end += 8
01450       (_x.target.region.cloud.height, _x.target.region.cloud.width,) = _struct_2I.unpack(str[start:end])
01451       start = end
01452       end += 4
01453       (length,) = _struct_I.unpack(str[start:end])
01454       self.target.region.cloud.fields = []
01455       for i in range(0, length):
01456         val1 = sensor_msgs.msg.PointField()
01457         start = end
01458         end += 4
01459         (length,) = _struct_I.unpack(str[start:end])
01460         start = end
01461         end += length
01462         if python3:
01463           val1.name = str[start:end].decode('utf-8')
01464         else:
01465           val1.name = str[start:end]
01466         _x = val1
01467         start = end
01468         end += 9
01469         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01470         self.target.region.cloud.fields.append(val1)
01471       _x = self
01472       start = end
01473       end += 9
01474       (_x.target.region.cloud.is_bigendian, _x.target.region.cloud.point_step, _x.target.region.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
01475       self.target.region.cloud.is_bigendian = bool(self.target.region.cloud.is_bigendian)
01476       start = end
01477       end += 4
01478       (length,) = _struct_I.unpack(str[start:end])
01479       start = end
01480       end += length
01481       if python3:
01482         self.target.region.cloud.data = str[start:end].decode('utf-8')
01483       else:
01484         self.target.region.cloud.data = str[start:end]
01485       start = end
01486       end += 1
01487       (self.target.region.cloud.is_dense,) = _struct_B.unpack(str[start:end])
01488       self.target.region.cloud.is_dense = bool(self.target.region.cloud.is_dense)
01489       start = end
01490       end += 4
01491       (length,) = _struct_I.unpack(str[start:end])
01492       pattern = '<%si'%length
01493       start = end
01494       end += struct.calcsize(pattern)
01495       self.target.region.mask = struct.unpack(pattern, str[start:end])
01496       _x = self
01497       start = end
01498       end += 12
01499       (_x.target.region.image.header.seq, _x.target.region.image.header.stamp.secs, _x.target.region.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01500       start = end
01501       end += 4
01502       (length,) = _struct_I.unpack(str[start:end])
01503       start = end
01504       end += length
01505       if python3:
01506         self.target.region.image.header.frame_id = str[start:end].decode('utf-8')
01507       else:
01508         self.target.region.image.header.frame_id = str[start:end]
01509       _x = self
01510       start = end
01511       end += 8
01512       (_x.target.region.image.height, _x.target.region.image.width,) = _struct_2I.unpack(str[start:end])
01513       start = end
01514       end += 4
01515       (length,) = _struct_I.unpack(str[start:end])
01516       start = end
01517       end += length
01518       if python3:
01519         self.target.region.image.encoding = str[start:end].decode('utf-8')
01520       else:
01521         self.target.region.image.encoding = str[start:end]
01522       _x = self
01523       start = end
01524       end += 5
01525       (_x.target.region.image.is_bigendian, _x.target.region.image.step,) = _struct_BI.unpack(str[start:end])
01526       start = end
01527       end += 4
01528       (length,) = _struct_I.unpack(str[start:end])
01529       start = end
01530       end += length
01531       if python3:
01532         self.target.region.image.data = str[start:end].decode('utf-8')
01533       else:
01534         self.target.region.image.data = str[start:end]
01535       _x = self
01536       start = end
01537       end += 12
01538       (_x.target.region.disparity_image.header.seq, _x.target.region.disparity_image.header.stamp.secs, _x.target.region.disparity_image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01539       start = end
01540       end += 4
01541       (length,) = _struct_I.unpack(str[start:end])
01542       start = end
01543       end += length
01544       if python3:
01545         self.target.region.disparity_image.header.frame_id = str[start:end].decode('utf-8')
01546       else:
01547         self.target.region.disparity_image.header.frame_id = str[start:end]
01548       _x = self
01549       start = end
01550       end += 8
01551       (_x.target.region.disparity_image.height, _x.target.region.disparity_image.width,) = _struct_2I.unpack(str[start:end])
01552       start = end
01553       end += 4
01554       (length,) = _struct_I.unpack(str[start:end])
01555       start = end
01556       end += length
01557       if python3:
01558         self.target.region.disparity_image.encoding = str[start:end].decode('utf-8')
01559       else:
01560         self.target.region.disparity_image.encoding = str[start:end]
01561       _x = self
01562       start = end
01563       end += 5
01564       (_x.target.region.disparity_image.is_bigendian, _x.target.region.disparity_image.step,) = _struct_BI.unpack(str[start:end])
01565       start = end
01566       end += 4
01567       (length,) = _struct_I.unpack(str[start:end])
01568       start = end
01569       end += length
01570       if python3:
01571         self.target.region.disparity_image.data = str[start:end].decode('utf-8')
01572       else:
01573         self.target.region.disparity_image.data = str[start:end]
01574       _x = self
01575       start = end
01576       end += 12
01577       (_x.target.region.cam_info.header.seq, _x.target.region.cam_info.header.stamp.secs, _x.target.region.cam_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01578       start = end
01579       end += 4
01580       (length,) = _struct_I.unpack(str[start:end])
01581       start = end
01582       end += length
01583       if python3:
01584         self.target.region.cam_info.header.frame_id = str[start:end].decode('utf-8')
01585       else:
01586         self.target.region.cam_info.header.frame_id = str[start:end]
01587       _x = self
01588       start = end
01589       end += 8
01590       (_x.target.region.cam_info.height, _x.target.region.cam_info.width,) = _struct_2I.unpack(str[start:end])
01591       start = end
01592       end += 4
01593       (length,) = _struct_I.unpack(str[start:end])
01594       start = end
01595       end += length
01596       if python3:
01597         self.target.region.cam_info.distortion_model = str[start:end].decode('utf-8')
01598       else:
01599         self.target.region.cam_info.distortion_model = str[start:end]
01600       start = end
01601       end += 4
01602       (length,) = _struct_I.unpack(str[start:end])
01603       pattern = '<%sd'%length
01604       start = end
01605       end += struct.calcsize(pattern)
01606       self.target.region.cam_info.D = struct.unpack(pattern, str[start:end])
01607       start = end
01608       end += 72
01609       self.target.region.cam_info.K = _struct_9d.unpack(str[start:end])
01610       start = end
01611       end += 72
01612       self.target.region.cam_info.R = _struct_9d.unpack(str[start:end])
01613       start = end
01614       end += 96
01615       self.target.region.cam_info.P = _struct_12d.unpack(str[start:end])
01616       _x = self
01617       start = end
01618       end += 37
01619       (_x.target.region.cam_info.binning_x, _x.target.region.cam_info.binning_y, _x.target.region.cam_info.roi.x_offset, _x.target.region.cam_info.roi.y_offset, _x.target.region.cam_info.roi.height, _x.target.region.cam_info.roi.width, _x.target.region.cam_info.roi.do_rectify, _x.target.region.roi_box_pose.header.seq, _x.target.region.roi_box_pose.header.stamp.secs, _x.target.region.roi_box_pose.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
01620       self.target.region.cam_info.roi.do_rectify = bool(self.target.region.cam_info.roi.do_rectify)
01621       start = end
01622       end += 4
01623       (length,) = _struct_I.unpack(str[start:end])
01624       start = end
01625       end += length
01626       if python3:
01627         self.target.region.roi_box_pose.header.frame_id = str[start:end].decode('utf-8')
01628       else:
01629         self.target.region.roi_box_pose.header.frame_id = str[start:end]
01630       _x = self
01631       start = end
01632       end += 80
01633       (_x.target.region.roi_box_pose.pose.position.x, _x.target.region.roi_box_pose.pose.position.y, _x.target.region.roi_box_pose.pose.position.z, _x.target.region.roi_box_pose.pose.orientation.x, _x.target.region.roi_box_pose.pose.orientation.y, _x.target.region.roi_box_pose.pose.orientation.z, _x.target.region.roi_box_pose.pose.orientation.w, _x.target.region.roi_box_dims.x, _x.target.region.roi_box_dims.y, _x.target.region.roi_box_dims.z,) = _struct_10d.unpack(str[start:end])
01634       start = end
01635       end += 4
01636       (length,) = _struct_I.unpack(str[start:end])
01637       start = end
01638       end += length
01639       if python3:
01640         self.target.collision_name = str[start:end].decode('utf-8')
01641       else:
01642         self.target.collision_name = str[start:end]
01643       start = end
01644       end += 4
01645       (length,) = _struct_I.unpack(str[start:end])
01646       start = end
01647       end += length
01648       if python3:
01649         self.collision_object_name = str[start:end].decode('utf-8')
01650       else:
01651         self.collision_object_name = str[start:end]
01652       start = end
01653       end += 4
01654       (length,) = _struct_I.unpack(str[start:end])
01655       start = end
01656       end += length
01657       if python3:
01658         self.collision_support_surface_name = str[start:end].decode('utf-8')
01659       else:
01660         self.collision_support_surface_name = str[start:end]
01661       start = end
01662       end += 4
01663       (length,) = _struct_I.unpack(str[start:end])
01664       self.grasps_to_evaluate = []
01665       for i in range(0, length):
01666         val1 = object_manipulation_msgs.msg.Grasp()
01667         _v82 = val1.pre_grasp_posture
01668         _v83 = _v82.header
01669         start = end
01670         end += 4
01671         (_v83.seq,) = _struct_I.unpack(str[start:end])
01672         _v84 = _v83.stamp
01673         _x = _v84
01674         start = end
01675         end += 8
01676         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01677         start = end
01678         end += 4
01679         (length,) = _struct_I.unpack(str[start:end])
01680         start = end
01681         end += length
01682         if python3:
01683           _v83.frame_id = str[start:end].decode('utf-8')
01684         else:
01685           _v83.frame_id = str[start:end]
01686         start = end
01687         end += 4
01688         (length,) = _struct_I.unpack(str[start:end])
01689         _v82.name = []
01690         for i in range(0, length):
01691           start = end
01692           end += 4
01693           (length,) = _struct_I.unpack(str[start:end])
01694           start = end
01695           end += length
01696           if python3:
01697             val3 = str[start:end].decode('utf-8')
01698           else:
01699             val3 = str[start:end]
01700           _v82.name.append(val3)
01701         start = end
01702         end += 4
01703         (length,) = _struct_I.unpack(str[start:end])
01704         pattern = '<%sd'%length
01705         start = end
01706         end += struct.calcsize(pattern)
01707         _v82.position = struct.unpack(pattern, str[start:end])
01708         start = end
01709         end += 4
01710         (length,) = _struct_I.unpack(str[start:end])
01711         pattern = '<%sd'%length
01712         start = end
01713         end += struct.calcsize(pattern)
01714         _v82.velocity = struct.unpack(pattern, str[start:end])
01715         start = end
01716         end += 4
01717         (length,) = _struct_I.unpack(str[start:end])
01718         pattern = '<%sd'%length
01719         start = end
01720         end += struct.calcsize(pattern)
01721         _v82.effort = struct.unpack(pattern, str[start:end])
01722         _v85 = val1.grasp_posture
01723         _v86 = _v85.header
01724         start = end
01725         end += 4
01726         (_v86.seq,) = _struct_I.unpack(str[start:end])
01727         _v87 = _v86.stamp
01728         _x = _v87
01729         start = end
01730         end += 8
01731         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01732         start = end
01733         end += 4
01734         (length,) = _struct_I.unpack(str[start:end])
01735         start = end
01736         end += length
01737         if python3:
01738           _v86.frame_id = str[start:end].decode('utf-8')
01739         else:
01740           _v86.frame_id = str[start:end]
01741         start = end
01742         end += 4
01743         (length,) = _struct_I.unpack(str[start:end])
01744         _v85.name = []
01745         for i in range(0, length):
01746           start = end
01747           end += 4
01748           (length,) = _struct_I.unpack(str[start:end])
01749           start = end
01750           end += length
01751           if python3:
01752             val3 = str[start:end].decode('utf-8')
01753           else:
01754             val3 = str[start:end]
01755           _v85.name.append(val3)
01756         start = end
01757         end += 4
01758         (length,) = _struct_I.unpack(str[start:end])
01759         pattern = '<%sd'%length
01760         start = end
01761         end += struct.calcsize(pattern)
01762         _v85.position = struct.unpack(pattern, str[start:end])
01763         start = end
01764         end += 4
01765         (length,) = _struct_I.unpack(str[start:end])
01766         pattern = '<%sd'%length
01767         start = end
01768         end += struct.calcsize(pattern)
01769         _v85.velocity = struct.unpack(pattern, str[start:end])
01770         start = end
01771         end += 4
01772         (length,) = _struct_I.unpack(str[start:end])
01773         pattern = '<%sd'%length
01774         start = end
01775         end += struct.calcsize(pattern)
01776         _v85.effort = struct.unpack(pattern, str[start:end])
01777         _v88 = val1.grasp_pose
01778         _v89 = _v88.position
01779         _x = _v89
01780         start = end
01781         end += 24
01782         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01783         _v90 = _v88.orientation
01784         _x = _v90
01785         start = end
01786         end += 32
01787         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01788         _x = val1
01789         start = end
01790         end += 17
01791         (_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance,) = _struct_dB2f.unpack(str[start:end])
01792         val1.cluster_rep = bool(val1.cluster_rep)
01793         start = end
01794         end += 4
01795         (length,) = _struct_I.unpack(str[start:end])
01796         val1.moved_obstacles = []
01797         for i in range(0, length):
01798           val2 = object_manipulation_msgs.msg.GraspableObject()
01799           start = end
01800           end += 4
01801           (length,) = _struct_I.unpack(str[start:end])
01802           start = end
01803           end += length
01804           if python3:
01805             val2.reference_frame_id = str[start:end].decode('utf-8')
01806           else:
01807             val2.reference_frame_id = str[start:end]
01808           start = end
01809           end += 4
01810           (length,) = _struct_I.unpack(str[start:end])
01811           val2.potential_models = []
01812           for i in range(0, length):
01813             val3 = household_objects_database_msgs.msg.DatabaseModelPose()
01814             start = end
01815             end += 4
01816             (val3.model_id,) = _struct_i.unpack(str[start:end])
01817             _v91 = val3.pose
01818             _v92 = _v91.header
01819             start = end
01820             end += 4
01821             (_v92.seq,) = _struct_I.unpack(str[start:end])
01822             _v93 = _v92.stamp
01823             _x = _v93
01824             start = end
01825             end += 8
01826             (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01827             start = end
01828             end += 4
01829             (length,) = _struct_I.unpack(str[start:end])
01830             start = end
01831             end += length
01832             if python3:
01833               _v92.frame_id = str[start:end].decode('utf-8')
01834             else:
01835               _v92.frame_id = str[start:end]
01836             _v94 = _v91.pose
01837             _v95 = _v94.position
01838             _x = _v95
01839             start = end
01840             end += 24
01841             (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01842             _v96 = _v94.orientation
01843             _x = _v96
01844             start = end
01845             end += 32
01846             (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01847             start = end
01848             end += 4
01849             (val3.confidence,) = _struct_f.unpack(str[start:end])
01850             start = end
01851             end += 4
01852             (length,) = _struct_I.unpack(str[start:end])
01853             start = end
01854             end += length
01855             if python3:
01856               val3.detector_name = str[start:end].decode('utf-8')
01857             else:
01858               val3.detector_name = str[start:end]
01859             val2.potential_models.append(val3)
01860           _v97 = val2.cluster
01861           _v98 = _v97.header
01862           start = end
01863           end += 4
01864           (_v98.seq,) = _struct_I.unpack(str[start:end])
01865           _v99 = _v98.stamp
01866           _x = _v99
01867           start = end
01868           end += 8
01869           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01870           start = end
01871           end += 4
01872           (length,) = _struct_I.unpack(str[start:end])
01873           start = end
01874           end += length
01875           if python3:
01876             _v98.frame_id = str[start:end].decode('utf-8')
01877           else:
01878             _v98.frame_id = str[start:end]
01879           start = end
01880           end += 4
01881           (length,) = _struct_I.unpack(str[start:end])
01882           _v97.points = []
01883           for i in range(0, length):
01884             val4 = geometry_msgs.msg.Point32()
01885             _x = val4
01886             start = end
01887             end += 12
01888             (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01889             _v97.points.append(val4)
01890           start = end
01891           end += 4
01892           (length,) = _struct_I.unpack(str[start:end])
01893           _v97.channels = []
01894           for i in range(0, length):
01895             val4 = sensor_msgs.msg.ChannelFloat32()
01896             start = end
01897             end += 4
01898             (length,) = _struct_I.unpack(str[start:end])
01899             start = end
01900             end += length
01901             if python3:
01902               val4.name = str[start:end].decode('utf-8')
01903             else:
01904               val4.name = str[start:end]
01905             start = end
01906             end += 4
01907             (length,) = _struct_I.unpack(str[start:end])
01908             pattern = '<%sf'%length
01909             start = end
01910             end += struct.calcsize(pattern)
01911             val4.values = struct.unpack(pattern, str[start:end])
01912             _v97.channels.append(val4)
01913           _v100 = val2.region
01914           _v101 = _v100.cloud
01915           _v102 = _v101.header
01916           start = end
01917           end += 4
01918           (_v102.seq,) = _struct_I.unpack(str[start:end])
01919           _v103 = _v102.stamp
01920           _x = _v103
01921           start = end
01922           end += 8
01923           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01924           start = end
01925           end += 4
01926           (length,) = _struct_I.unpack(str[start:end])
01927           start = end
01928           end += length
01929           if python3:
01930             _v102.frame_id = str[start:end].decode('utf-8')
01931           else:
01932             _v102.frame_id = str[start:end]
01933           _x = _v101
01934           start = end
01935           end += 8
01936           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01937           start = end
01938           end += 4
01939           (length,) = _struct_I.unpack(str[start:end])
01940           _v101.fields = []
01941           for i in range(0, length):
01942             val5 = sensor_msgs.msg.PointField()
01943             start = end
01944             end += 4
01945             (length,) = _struct_I.unpack(str[start:end])
01946             start = end
01947             end += length
01948             if python3:
01949               val5.name = str[start:end].decode('utf-8')
01950             else:
01951               val5.name = str[start:end]
01952             _x = val5
01953             start = end
01954             end += 9
01955             (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01956             _v101.fields.append(val5)
01957           _x = _v101
01958           start = end
01959           end += 9
01960           (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
01961           _v101.is_bigendian = bool(_v101.is_bigendian)
01962           start = end
01963           end += 4
01964           (length,) = _struct_I.unpack(str[start:end])
01965           start = end
01966           end += length
01967           if python3:
01968             _v101.data = str[start:end].decode('utf-8')
01969           else:
01970             _v101.data = str[start:end]
01971           start = end
01972           end += 1
01973           (_v101.is_dense,) = _struct_B.unpack(str[start:end])
01974           _v101.is_dense = bool(_v101.is_dense)
01975           start = end
01976           end += 4
01977           (length,) = _struct_I.unpack(str[start:end])
01978           pattern = '<%si'%length
01979           start = end
01980           end += struct.calcsize(pattern)
01981           _v100.mask = struct.unpack(pattern, str[start:end])
01982           _v104 = _v100.image
01983           _v105 = _v104.header
01984           start = end
01985           end += 4
01986           (_v105.seq,) = _struct_I.unpack(str[start:end])
01987           _v106 = _v105.stamp
01988           _x = _v106
01989           start = end
01990           end += 8
01991           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01992           start = end
01993           end += 4
01994           (length,) = _struct_I.unpack(str[start:end])
01995           start = end
01996           end += length
01997           if python3:
01998             _v105.frame_id = str[start:end].decode('utf-8')
01999           else:
02000             _v105.frame_id = str[start:end]
02001           _x = _v104
02002           start = end
02003           end += 8
02004           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02005           start = end
02006           end += 4
02007           (length,) = _struct_I.unpack(str[start:end])
02008           start = end
02009           end += length
02010           if python3:
02011             _v104.encoding = str[start:end].decode('utf-8')
02012           else:
02013             _v104.encoding = str[start:end]
02014           _x = _v104
02015           start = end
02016           end += 5
02017           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
02018           start = end
02019           end += 4
02020           (length,) = _struct_I.unpack(str[start:end])
02021           start = end
02022           end += length
02023           if python3:
02024             _v104.data = str[start:end].decode('utf-8')
02025           else:
02026             _v104.data = str[start:end]
02027           _v107 = _v100.disparity_image
02028           _v108 = _v107.header
02029           start = end
02030           end += 4
02031           (_v108.seq,) = _struct_I.unpack(str[start:end])
02032           _v109 = _v108.stamp
02033           _x = _v109
02034           start = end
02035           end += 8
02036           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02037           start = end
02038           end += 4
02039           (length,) = _struct_I.unpack(str[start:end])
02040           start = end
02041           end += length
02042           if python3:
02043             _v108.frame_id = str[start:end].decode('utf-8')
02044           else:
02045             _v108.frame_id = str[start:end]
02046           _x = _v107
02047           start = end
02048           end += 8
02049           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02050           start = end
02051           end += 4
02052           (length,) = _struct_I.unpack(str[start:end])
02053           start = end
02054           end += length
02055           if python3:
02056             _v107.encoding = str[start:end].decode('utf-8')
02057           else:
02058             _v107.encoding = str[start:end]
02059           _x = _v107
02060           start = end
02061           end += 5
02062           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
02063           start = end
02064           end += 4
02065           (length,) = _struct_I.unpack(str[start:end])
02066           start = end
02067           end += length
02068           if python3:
02069             _v107.data = str[start:end].decode('utf-8')
02070           else:
02071             _v107.data = str[start:end]
02072           _v110 = _v100.cam_info
02073           _v111 = _v110.header
02074           start = end
02075           end += 4
02076           (_v111.seq,) = _struct_I.unpack(str[start:end])
02077           _v112 = _v111.stamp
02078           _x = _v112
02079           start = end
02080           end += 8
02081           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02082           start = end
02083           end += 4
02084           (length,) = _struct_I.unpack(str[start:end])
02085           start = end
02086           end += length
02087           if python3:
02088             _v111.frame_id = str[start:end].decode('utf-8')
02089           else:
02090             _v111.frame_id = str[start:end]
02091           _x = _v110
02092           start = end
02093           end += 8
02094           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02095           start = end
02096           end += 4
02097           (length,) = _struct_I.unpack(str[start:end])
02098           start = end
02099           end += length
02100           if python3:
02101             _v110.distortion_model = str[start:end].decode('utf-8')
02102           else:
02103             _v110.distortion_model = str[start:end]
02104           start = end
02105           end += 4
02106           (length,) = _struct_I.unpack(str[start:end])
02107           pattern = '<%sd'%length
02108           start = end
02109           end += struct.calcsize(pattern)
02110           _v110.D = struct.unpack(pattern, str[start:end])
02111           start = end
02112           end += 72
02113           _v110.K = _struct_9d.unpack(str[start:end])
02114           start = end
02115           end += 72
02116           _v110.R = _struct_9d.unpack(str[start:end])
02117           start = end
02118           end += 96
02119           _v110.P = _struct_12d.unpack(str[start:end])
02120           _x = _v110
02121           start = end
02122           end += 8
02123           (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
02124           _v113 = _v110.roi
02125           _x = _v113
02126           start = end
02127           end += 17
02128           (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
02129           _v113.do_rectify = bool(_v113.do_rectify)
02130           _v114 = _v100.roi_box_pose
02131           _v115 = _v114.header
02132           start = end
02133           end += 4
02134           (_v115.seq,) = _struct_I.unpack(str[start:end])
02135           _v116 = _v115.stamp
02136           _x = _v116
02137           start = end
02138           end += 8
02139           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02140           start = end
02141           end += 4
02142           (length,) = _struct_I.unpack(str[start:end])
02143           start = end
02144           end += length
02145           if python3:
02146             _v115.frame_id = str[start:end].decode('utf-8')
02147           else:
02148             _v115.frame_id = str[start:end]
02149           _v117 = _v114.pose
02150           _v118 = _v117.position
02151           _x = _v118
02152           start = end
02153           end += 24
02154           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02155           _v119 = _v117.orientation
02156           _x = _v119
02157           start = end
02158           end += 32
02159           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02160           _v120 = _v100.roi_box_dims
02161           _x = _v120
02162           start = end
02163           end += 24
02164           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02165           start = end
02166           end += 4
02167           (length,) = _struct_I.unpack(str[start:end])
02168           start = end
02169           end += length
02170           if python3:
02171             val2.collision_name = str[start:end].decode('utf-8')
02172           else:
02173             val2.collision_name = str[start:end]
02174           val1.moved_obstacles.append(val2)
02175         self.grasps_to_evaluate.append(val1)
02176       start = end
02177       end += 4
02178       (length,) = _struct_I.unpack(str[start:end])
02179       self.movable_obstacles = []
02180       for i in range(0, length):
02181         val1 = object_manipulation_msgs.msg.GraspableObject()
02182         start = end
02183         end += 4
02184         (length,) = _struct_I.unpack(str[start:end])
02185         start = end
02186         end += length
02187         if python3:
02188           val1.reference_frame_id = str[start:end].decode('utf-8')
02189         else:
02190           val1.reference_frame_id = str[start:end]
02191         start = end
02192         end += 4
02193         (length,) = _struct_I.unpack(str[start:end])
02194         val1.potential_models = []
02195         for i in range(0, length):
02196           val2 = household_objects_database_msgs.msg.DatabaseModelPose()
02197           start = end
02198           end += 4
02199           (val2.model_id,) = _struct_i.unpack(str[start:end])
02200           _v121 = val2.pose
02201           _v122 = _v121.header
02202           start = end
02203           end += 4
02204           (_v122.seq,) = _struct_I.unpack(str[start:end])
02205           _v123 = _v122.stamp
02206           _x = _v123
02207           start = end
02208           end += 8
02209           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02210           start = end
02211           end += 4
02212           (length,) = _struct_I.unpack(str[start:end])
02213           start = end
02214           end += length
02215           if python3:
02216             _v122.frame_id = str[start:end].decode('utf-8')
02217           else:
02218             _v122.frame_id = str[start:end]
02219           _v124 = _v121.pose
02220           _v125 = _v124.position
02221           _x = _v125
02222           start = end
02223           end += 24
02224           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02225           _v126 = _v124.orientation
02226           _x = _v126
02227           start = end
02228           end += 32
02229           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02230           start = end
02231           end += 4
02232           (val2.confidence,) = _struct_f.unpack(str[start:end])
02233           start = end
02234           end += 4
02235           (length,) = _struct_I.unpack(str[start:end])
02236           start = end
02237           end += length
02238           if python3:
02239             val2.detector_name = str[start:end].decode('utf-8')
02240           else:
02241             val2.detector_name = str[start:end]
02242           val1.potential_models.append(val2)
02243         _v127 = val1.cluster
02244         _v128 = _v127.header
02245         start = end
02246         end += 4
02247         (_v128.seq,) = _struct_I.unpack(str[start:end])
02248         _v129 = _v128.stamp
02249         _x = _v129
02250         start = end
02251         end += 8
02252         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02253         start = end
02254         end += 4
02255         (length,) = _struct_I.unpack(str[start:end])
02256         start = end
02257         end += length
02258         if python3:
02259           _v128.frame_id = str[start:end].decode('utf-8')
02260         else:
02261           _v128.frame_id = str[start:end]
02262         start = end
02263         end += 4
02264         (length,) = _struct_I.unpack(str[start:end])
02265         _v127.points = []
02266         for i in range(0, length):
02267           val3 = geometry_msgs.msg.Point32()
02268           _x = val3
02269           start = end
02270           end += 12
02271           (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
02272           _v127.points.append(val3)
02273         start = end
02274         end += 4
02275         (length,) = _struct_I.unpack(str[start:end])
02276         _v127.channels = []
02277         for i in range(0, length):
02278           val3 = sensor_msgs.msg.ChannelFloat32()
02279           start = end
02280           end += 4
02281           (length,) = _struct_I.unpack(str[start:end])
02282           start = end
02283           end += length
02284           if python3:
02285             val3.name = str[start:end].decode('utf-8')
02286           else:
02287             val3.name = str[start:end]
02288           start = end
02289           end += 4
02290           (length,) = _struct_I.unpack(str[start:end])
02291           pattern = '<%sf'%length
02292           start = end
02293           end += struct.calcsize(pattern)
02294           val3.values = struct.unpack(pattern, str[start:end])
02295           _v127.channels.append(val3)
02296         _v130 = val1.region
02297         _v131 = _v130.cloud
02298         _v132 = _v131.header
02299         start = end
02300         end += 4
02301         (_v132.seq,) = _struct_I.unpack(str[start:end])
02302         _v133 = _v132.stamp
02303         _x = _v133
02304         start = end
02305         end += 8
02306         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02307         start = end
02308         end += 4
02309         (length,) = _struct_I.unpack(str[start:end])
02310         start = end
02311         end += length
02312         if python3:
02313           _v132.frame_id = str[start:end].decode('utf-8')
02314         else:
02315           _v132.frame_id = str[start:end]
02316         _x = _v131
02317         start = end
02318         end += 8
02319         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02320         start = end
02321         end += 4
02322         (length,) = _struct_I.unpack(str[start:end])
02323         _v131.fields = []
02324         for i in range(0, length):
02325           val4 = sensor_msgs.msg.PointField()
02326           start = end
02327           end += 4
02328           (length,) = _struct_I.unpack(str[start:end])
02329           start = end
02330           end += length
02331           if python3:
02332             val4.name = str[start:end].decode('utf-8')
02333           else:
02334             val4.name = str[start:end]
02335           _x = val4
02336           start = end
02337           end += 9
02338           (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
02339           _v131.fields.append(val4)
02340         _x = _v131
02341         start = end
02342         end += 9
02343         (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
02344         _v131.is_bigendian = bool(_v131.is_bigendian)
02345         start = end
02346         end += 4
02347         (length,) = _struct_I.unpack(str[start:end])
02348         start = end
02349         end += length
02350         if python3:
02351           _v131.data = str[start:end].decode('utf-8')
02352         else:
02353           _v131.data = str[start:end]
02354         start = end
02355         end += 1
02356         (_v131.is_dense,) = _struct_B.unpack(str[start:end])
02357         _v131.is_dense = bool(_v131.is_dense)
02358         start = end
02359         end += 4
02360         (length,) = _struct_I.unpack(str[start:end])
02361         pattern = '<%si'%length
02362         start = end
02363         end += struct.calcsize(pattern)
02364         _v130.mask = struct.unpack(pattern, str[start:end])
02365         _v134 = _v130.image
02366         _v135 = _v134.header
02367         start = end
02368         end += 4
02369         (_v135.seq,) = _struct_I.unpack(str[start:end])
02370         _v136 = _v135.stamp
02371         _x = _v136
02372         start = end
02373         end += 8
02374         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02375         start = end
02376         end += 4
02377         (length,) = _struct_I.unpack(str[start:end])
02378         start = end
02379         end += length
02380         if python3:
02381           _v135.frame_id = str[start:end].decode('utf-8')
02382         else:
02383           _v135.frame_id = str[start:end]
02384         _x = _v134
02385         start = end
02386         end += 8
02387         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02388         start = end
02389         end += 4
02390         (length,) = _struct_I.unpack(str[start:end])
02391         start = end
02392         end += length
02393         if python3:
02394           _v134.encoding = str[start:end].decode('utf-8')
02395         else:
02396           _v134.encoding = str[start:end]
02397         _x = _v134
02398         start = end
02399         end += 5
02400         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
02401         start = end
02402         end += 4
02403         (length,) = _struct_I.unpack(str[start:end])
02404         start = end
02405         end += length
02406         if python3:
02407           _v134.data = str[start:end].decode('utf-8')
02408         else:
02409           _v134.data = str[start:end]
02410         _v137 = _v130.disparity_image
02411         _v138 = _v137.header
02412         start = end
02413         end += 4
02414         (_v138.seq,) = _struct_I.unpack(str[start:end])
02415         _v139 = _v138.stamp
02416         _x = _v139
02417         start = end
02418         end += 8
02419         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02420         start = end
02421         end += 4
02422         (length,) = _struct_I.unpack(str[start:end])
02423         start = end
02424         end += length
02425         if python3:
02426           _v138.frame_id = str[start:end].decode('utf-8')
02427         else:
02428           _v138.frame_id = str[start:end]
02429         _x = _v137
02430         start = end
02431         end += 8
02432         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02433         start = end
02434         end += 4
02435         (length,) = _struct_I.unpack(str[start:end])
02436         start = end
02437         end += length
02438         if python3:
02439           _v137.encoding = str[start:end].decode('utf-8')
02440         else:
02441           _v137.encoding = str[start:end]
02442         _x = _v137
02443         start = end
02444         end += 5
02445         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
02446         start = end
02447         end += 4
02448         (length,) = _struct_I.unpack(str[start:end])
02449         start = end
02450         end += length
02451         if python3:
02452           _v137.data = str[start:end].decode('utf-8')
02453         else:
02454           _v137.data = str[start:end]
02455         _v140 = _v130.cam_info
02456         _v141 = _v140.header
02457         start = end
02458         end += 4
02459         (_v141.seq,) = _struct_I.unpack(str[start:end])
02460         _v142 = _v141.stamp
02461         _x = _v142
02462         start = end
02463         end += 8
02464         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02465         start = end
02466         end += 4
02467         (length,) = _struct_I.unpack(str[start:end])
02468         start = end
02469         end += length
02470         if python3:
02471           _v141.frame_id = str[start:end].decode('utf-8')
02472         else:
02473           _v141.frame_id = str[start:end]
02474         _x = _v140
02475         start = end
02476         end += 8
02477         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02478         start = end
02479         end += 4
02480         (length,) = _struct_I.unpack(str[start:end])
02481         start = end
02482         end += length
02483         if python3:
02484           _v140.distortion_model = str[start:end].decode('utf-8')
02485         else:
02486           _v140.distortion_model = str[start:end]
02487         start = end
02488         end += 4
02489         (length,) = _struct_I.unpack(str[start:end])
02490         pattern = '<%sd'%length
02491         start = end
02492         end += struct.calcsize(pattern)
02493         _v140.D = struct.unpack(pattern, str[start:end])
02494         start = end
02495         end += 72
02496         _v140.K = _struct_9d.unpack(str[start:end])
02497         start = end
02498         end += 72
02499         _v140.R = _struct_9d.unpack(str[start:end])
02500         start = end
02501         end += 96
02502         _v140.P = _struct_12d.unpack(str[start:end])
02503         _x = _v140
02504         start = end
02505         end += 8
02506         (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
02507         _v143 = _v140.roi
02508         _x = _v143
02509         start = end
02510         end += 17
02511         (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
02512         _v143.do_rectify = bool(_v143.do_rectify)
02513         _v144 = _v130.roi_box_pose
02514         _v145 = _v144.header
02515         start = end
02516         end += 4
02517         (_v145.seq,) = _struct_I.unpack(str[start:end])
02518         _v146 = _v145.stamp
02519         _x = _v146
02520         start = end
02521         end += 8
02522         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02523         start = end
02524         end += 4
02525         (length,) = _struct_I.unpack(str[start:end])
02526         start = end
02527         end += length
02528         if python3:
02529           _v145.frame_id = str[start:end].decode('utf-8')
02530         else:
02531           _v145.frame_id = str[start:end]
02532         _v147 = _v144.pose
02533         _v148 = _v147.position
02534         _x = _v148
02535         start = end
02536         end += 24
02537         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02538         _v149 = _v147.orientation
02539         _x = _v149
02540         start = end
02541         end += 32
02542         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02543         _v150 = _v130.roi_box_dims
02544         _x = _v150
02545         start = end
02546         end += 24
02547         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02548         start = end
02549         end += 4
02550         (length,) = _struct_I.unpack(str[start:end])
02551         start = end
02552         end += length
02553         if python3:
02554           val1.collision_name = str[start:end].decode('utf-8')
02555         else:
02556           val1.collision_name = str[start:end]
02557         self.movable_obstacles.append(val1)
02558       return self
02559     except struct.error as e:
02560       raise genpy.DeserializationError(e) #most likely buffer underfill
02561 
02562 
02563   def serialize_numpy(self, buff, numpy):
02564     """
02565     serialize message with numpy array types into buffer
02566     :param buff: buffer, ``StringIO``
02567     :param numpy: numpy python module
02568     """
02569     try:
02570       _x = self.arm_name
02571       length = len(_x)
02572       if python3 or type(_x) == unicode:
02573         _x = _x.encode('utf-8')
02574         length = len(_x)
02575       buff.write(struct.pack('<I%ss'%length, length, _x))
02576       _x = self.target.reference_frame_id
02577       length = len(_x)
02578       if python3 or type(_x) == unicode:
02579         _x = _x.encode('utf-8')
02580         length = len(_x)
02581       buff.write(struct.pack('<I%ss'%length, length, _x))
02582       length = len(self.target.potential_models)
02583       buff.write(_struct_I.pack(length))
02584       for val1 in self.target.potential_models:
02585         buff.write(_struct_i.pack(val1.model_id))
02586         _v151 = val1.pose
02587         _v152 = _v151.header
02588         buff.write(_struct_I.pack(_v152.seq))
02589         _v153 = _v152.stamp
02590         _x = _v153
02591         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02592         _x = _v152.frame_id
02593         length = len(_x)
02594         if python3 or type(_x) == unicode:
02595           _x = _x.encode('utf-8')
02596           length = len(_x)
02597         buff.write(struct.pack('<I%ss'%length, length, _x))
02598         _v154 = _v151.pose
02599         _v155 = _v154.position
02600         _x = _v155
02601         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02602         _v156 = _v154.orientation
02603         _x = _v156
02604         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02605         buff.write(_struct_f.pack(val1.confidence))
02606         _x = val1.detector_name
02607         length = len(_x)
02608         if python3 or type(_x) == unicode:
02609           _x = _x.encode('utf-8')
02610           length = len(_x)
02611         buff.write(struct.pack('<I%ss'%length, length, _x))
02612       _x = self
02613       buff.write(_struct_3I.pack(_x.target.cluster.header.seq, _x.target.cluster.header.stamp.secs, _x.target.cluster.header.stamp.nsecs))
02614       _x = self.target.cluster.header.frame_id
02615       length = len(_x)
02616       if python3 or type(_x) == unicode:
02617         _x = _x.encode('utf-8')
02618         length = len(_x)
02619       buff.write(struct.pack('<I%ss'%length, length, _x))
02620       length = len(self.target.cluster.points)
02621       buff.write(_struct_I.pack(length))
02622       for val1 in self.target.cluster.points:
02623         _x = val1
02624         buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
02625       length = len(self.target.cluster.channels)
02626       buff.write(_struct_I.pack(length))
02627       for val1 in self.target.cluster.channels:
02628         _x = val1.name
02629         length = len(_x)
02630         if python3 or type(_x) == unicode:
02631           _x = _x.encode('utf-8')
02632           length = len(_x)
02633         buff.write(struct.pack('<I%ss'%length, length, _x))
02634         length = len(val1.values)
02635         buff.write(_struct_I.pack(length))
02636         pattern = '<%sf'%length
02637         buff.write(val1.values.tostring())
02638       _x = self
02639       buff.write(_struct_3I.pack(_x.target.region.cloud.header.seq, _x.target.region.cloud.header.stamp.secs, _x.target.region.cloud.header.stamp.nsecs))
02640       _x = self.target.region.cloud.header.frame_id
02641       length = len(_x)
02642       if python3 or type(_x) == unicode:
02643         _x = _x.encode('utf-8')
02644         length = len(_x)
02645       buff.write(struct.pack('<I%ss'%length, length, _x))
02646       _x = self
02647       buff.write(_struct_2I.pack(_x.target.region.cloud.height, _x.target.region.cloud.width))
02648       length = len(self.target.region.cloud.fields)
02649       buff.write(_struct_I.pack(length))
02650       for val1 in self.target.region.cloud.fields:
02651         _x = val1.name
02652         length = len(_x)
02653         if python3 or type(_x) == unicode:
02654           _x = _x.encode('utf-8')
02655           length = len(_x)
02656         buff.write(struct.pack('<I%ss'%length, length, _x))
02657         _x = val1
02658         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
02659       _x = self
02660       buff.write(_struct_B2I.pack(_x.target.region.cloud.is_bigendian, _x.target.region.cloud.point_step, _x.target.region.cloud.row_step))
02661       _x = self.target.region.cloud.data
02662       length = len(_x)
02663       # - if encoded as a list instead, serialize as bytes instead of string
02664       if type(_x) in [list, tuple]:
02665         buff.write(struct.pack('<I%sB'%length, length, *_x))
02666       else:
02667         buff.write(struct.pack('<I%ss'%length, length, _x))
02668       buff.write(_struct_B.pack(self.target.region.cloud.is_dense))
02669       length = len(self.target.region.mask)
02670       buff.write(_struct_I.pack(length))
02671       pattern = '<%si'%length
02672       buff.write(self.target.region.mask.tostring())
02673       _x = self
02674       buff.write(_struct_3I.pack(_x.target.region.image.header.seq, _x.target.region.image.header.stamp.secs, _x.target.region.image.header.stamp.nsecs))
02675       _x = self.target.region.image.header.frame_id
02676       length = len(_x)
02677       if python3 or type(_x) == unicode:
02678         _x = _x.encode('utf-8')
02679         length = len(_x)
02680       buff.write(struct.pack('<I%ss'%length, length, _x))
02681       _x = self
02682       buff.write(_struct_2I.pack(_x.target.region.image.height, _x.target.region.image.width))
02683       _x = self.target.region.image.encoding
02684       length = len(_x)
02685       if python3 or type(_x) == unicode:
02686         _x = _x.encode('utf-8')
02687         length = len(_x)
02688       buff.write(struct.pack('<I%ss'%length, length, _x))
02689       _x = self
02690       buff.write(_struct_BI.pack(_x.target.region.image.is_bigendian, _x.target.region.image.step))
02691       _x = self.target.region.image.data
02692       length = len(_x)
02693       # - if encoded as a list instead, serialize as bytes instead of string
02694       if type(_x) in [list, tuple]:
02695         buff.write(struct.pack('<I%sB'%length, length, *_x))
02696       else:
02697         buff.write(struct.pack('<I%ss'%length, length, _x))
02698       _x = self
02699       buff.write(_struct_3I.pack(_x.target.region.disparity_image.header.seq, _x.target.region.disparity_image.header.stamp.secs, _x.target.region.disparity_image.header.stamp.nsecs))
02700       _x = self.target.region.disparity_image.header.frame_id
02701       length = len(_x)
02702       if python3 or type(_x) == unicode:
02703         _x = _x.encode('utf-8')
02704         length = len(_x)
02705       buff.write(struct.pack('<I%ss'%length, length, _x))
02706       _x = self
02707       buff.write(_struct_2I.pack(_x.target.region.disparity_image.height, _x.target.region.disparity_image.width))
02708       _x = self.target.region.disparity_image.encoding
02709       length = len(_x)
02710       if python3 or type(_x) == unicode:
02711         _x = _x.encode('utf-8')
02712         length = len(_x)
02713       buff.write(struct.pack('<I%ss'%length, length, _x))
02714       _x = self
02715       buff.write(_struct_BI.pack(_x.target.region.disparity_image.is_bigendian, _x.target.region.disparity_image.step))
02716       _x = self.target.region.disparity_image.data
02717       length = len(_x)
02718       # - if encoded as a list instead, serialize as bytes instead of string
02719       if type(_x) in [list, tuple]:
02720         buff.write(struct.pack('<I%sB'%length, length, *_x))
02721       else:
02722         buff.write(struct.pack('<I%ss'%length, length, _x))
02723       _x = self
02724       buff.write(_struct_3I.pack(_x.target.region.cam_info.header.seq, _x.target.region.cam_info.header.stamp.secs, _x.target.region.cam_info.header.stamp.nsecs))
02725       _x = self.target.region.cam_info.header.frame_id
02726       length = len(_x)
02727       if python3 or type(_x) == unicode:
02728         _x = _x.encode('utf-8')
02729         length = len(_x)
02730       buff.write(struct.pack('<I%ss'%length, length, _x))
02731       _x = self
02732       buff.write(_struct_2I.pack(_x.target.region.cam_info.height, _x.target.region.cam_info.width))
02733       _x = self.target.region.cam_info.distortion_model
02734       length = len(_x)
02735       if python3 or type(_x) == unicode:
02736         _x = _x.encode('utf-8')
02737         length = len(_x)
02738       buff.write(struct.pack('<I%ss'%length, length, _x))
02739       length = len(self.target.region.cam_info.D)
02740       buff.write(_struct_I.pack(length))
02741       pattern = '<%sd'%length
02742       buff.write(self.target.region.cam_info.D.tostring())
02743       buff.write(self.target.region.cam_info.K.tostring())
02744       buff.write(self.target.region.cam_info.R.tostring())
02745       buff.write(self.target.region.cam_info.P.tostring())
02746       _x = self
02747       buff.write(_struct_6IB3I.pack(_x.target.region.cam_info.binning_x, _x.target.region.cam_info.binning_y, _x.target.region.cam_info.roi.x_offset, _x.target.region.cam_info.roi.y_offset, _x.target.region.cam_info.roi.height, _x.target.region.cam_info.roi.width, _x.target.region.cam_info.roi.do_rectify, _x.target.region.roi_box_pose.header.seq, _x.target.region.roi_box_pose.header.stamp.secs, _x.target.region.roi_box_pose.header.stamp.nsecs))
02748       _x = self.target.region.roi_box_pose.header.frame_id
02749       length = len(_x)
02750       if python3 or type(_x) == unicode:
02751         _x = _x.encode('utf-8')
02752         length = len(_x)
02753       buff.write(struct.pack('<I%ss'%length, length, _x))
02754       _x = self
02755       buff.write(_struct_10d.pack(_x.target.region.roi_box_pose.pose.position.x, _x.target.region.roi_box_pose.pose.position.y, _x.target.region.roi_box_pose.pose.position.z, _x.target.region.roi_box_pose.pose.orientation.x, _x.target.region.roi_box_pose.pose.orientation.y, _x.target.region.roi_box_pose.pose.orientation.z, _x.target.region.roi_box_pose.pose.orientation.w, _x.target.region.roi_box_dims.x, _x.target.region.roi_box_dims.y, _x.target.region.roi_box_dims.z))
02756       _x = self.target.collision_name
02757       length = len(_x)
02758       if python3 or type(_x) == unicode:
02759         _x = _x.encode('utf-8')
02760         length = len(_x)
02761       buff.write(struct.pack('<I%ss'%length, length, _x))
02762       _x = self.collision_object_name
02763       length = len(_x)
02764       if python3 or type(_x) == unicode:
02765         _x = _x.encode('utf-8')
02766         length = len(_x)
02767       buff.write(struct.pack('<I%ss'%length, length, _x))
02768       _x = self.collision_support_surface_name
02769       length = len(_x)
02770       if python3 or type(_x) == unicode:
02771         _x = _x.encode('utf-8')
02772         length = len(_x)
02773       buff.write(struct.pack('<I%ss'%length, length, _x))
02774       length = len(self.grasps_to_evaluate)
02775       buff.write(_struct_I.pack(length))
02776       for val1 in self.grasps_to_evaluate:
02777         _v157 = val1.pre_grasp_posture
02778         _v158 = _v157.header
02779         buff.write(_struct_I.pack(_v158.seq))
02780         _v159 = _v158.stamp
02781         _x = _v159
02782         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02783         _x = _v158.frame_id
02784         length = len(_x)
02785         if python3 or type(_x) == unicode:
02786           _x = _x.encode('utf-8')
02787           length = len(_x)
02788         buff.write(struct.pack('<I%ss'%length, length, _x))
02789         length = len(_v157.name)
02790         buff.write(_struct_I.pack(length))
02791         for val3 in _v157.name:
02792           length = len(val3)
02793           if python3 or type(val3) == unicode:
02794             val3 = val3.encode('utf-8')
02795             length = len(val3)
02796           buff.write(struct.pack('<I%ss'%length, length, val3))
02797         length = len(_v157.position)
02798         buff.write(_struct_I.pack(length))
02799         pattern = '<%sd'%length
02800         buff.write(_v157.position.tostring())
02801         length = len(_v157.velocity)
02802         buff.write(_struct_I.pack(length))
02803         pattern = '<%sd'%length
02804         buff.write(_v157.velocity.tostring())
02805         length = len(_v157.effort)
02806         buff.write(_struct_I.pack(length))
02807         pattern = '<%sd'%length
02808         buff.write(_v157.effort.tostring())
02809         _v160 = val1.grasp_posture
02810         _v161 = _v160.header
02811         buff.write(_struct_I.pack(_v161.seq))
02812         _v162 = _v161.stamp
02813         _x = _v162
02814         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02815         _x = _v161.frame_id
02816         length = len(_x)
02817         if python3 or type(_x) == unicode:
02818           _x = _x.encode('utf-8')
02819           length = len(_x)
02820         buff.write(struct.pack('<I%ss'%length, length, _x))
02821         length = len(_v160.name)
02822         buff.write(_struct_I.pack(length))
02823         for val3 in _v160.name:
02824           length = len(val3)
02825           if python3 or type(val3) == unicode:
02826             val3 = val3.encode('utf-8')
02827             length = len(val3)
02828           buff.write(struct.pack('<I%ss'%length, length, val3))
02829         length = len(_v160.position)
02830         buff.write(_struct_I.pack(length))
02831         pattern = '<%sd'%length
02832         buff.write(_v160.position.tostring())
02833         length = len(_v160.velocity)
02834         buff.write(_struct_I.pack(length))
02835         pattern = '<%sd'%length
02836         buff.write(_v160.velocity.tostring())
02837         length = len(_v160.effort)
02838         buff.write(_struct_I.pack(length))
02839         pattern = '<%sd'%length
02840         buff.write(_v160.effort.tostring())
02841         _v163 = val1.grasp_pose
02842         _v164 = _v163.position
02843         _x = _v164
02844         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02845         _v165 = _v163.orientation
02846         _x = _v165
02847         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02848         _x = val1
02849         buff.write(_struct_dB2f.pack(_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance))
02850         length = len(val1.moved_obstacles)
02851         buff.write(_struct_I.pack(length))
02852         for val2 in val1.moved_obstacles:
02853           _x = val2.reference_frame_id
02854           length = len(_x)
02855           if python3 or type(_x) == unicode:
02856             _x = _x.encode('utf-8')
02857             length = len(_x)
02858           buff.write(struct.pack('<I%ss'%length, length, _x))
02859           length = len(val2.potential_models)
02860           buff.write(_struct_I.pack(length))
02861           for val3 in val2.potential_models:
02862             buff.write(_struct_i.pack(val3.model_id))
02863             _v166 = val3.pose
02864             _v167 = _v166.header
02865             buff.write(_struct_I.pack(_v167.seq))
02866             _v168 = _v167.stamp
02867             _x = _v168
02868             buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02869             _x = _v167.frame_id
02870             length = len(_x)
02871             if python3 or type(_x) == unicode:
02872               _x = _x.encode('utf-8')
02873               length = len(_x)
02874             buff.write(struct.pack('<I%ss'%length, length, _x))
02875             _v169 = _v166.pose
02876             _v170 = _v169.position
02877             _x = _v170
02878             buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02879             _v171 = _v169.orientation
02880             _x = _v171
02881             buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02882             buff.write(_struct_f.pack(val3.confidence))
02883             _x = val3.detector_name
02884             length = len(_x)
02885             if python3 or type(_x) == unicode:
02886               _x = _x.encode('utf-8')
02887               length = len(_x)
02888             buff.write(struct.pack('<I%ss'%length, length, _x))
02889           _v172 = val2.cluster
02890           _v173 = _v172.header
02891           buff.write(_struct_I.pack(_v173.seq))
02892           _v174 = _v173.stamp
02893           _x = _v174
02894           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02895           _x = _v173.frame_id
02896           length = len(_x)
02897           if python3 or type(_x) == unicode:
02898             _x = _x.encode('utf-8')
02899             length = len(_x)
02900           buff.write(struct.pack('<I%ss'%length, length, _x))
02901           length = len(_v172.points)
02902           buff.write(_struct_I.pack(length))
02903           for val4 in _v172.points:
02904             _x = val4
02905             buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
02906           length = len(_v172.channels)
02907           buff.write(_struct_I.pack(length))
02908           for val4 in _v172.channels:
02909             _x = val4.name
02910             length = len(_x)
02911             if python3 or type(_x) == unicode:
02912               _x = _x.encode('utf-8')
02913               length = len(_x)
02914             buff.write(struct.pack('<I%ss'%length, length, _x))
02915             length = len(val4.values)
02916             buff.write(_struct_I.pack(length))
02917             pattern = '<%sf'%length
02918             buff.write(val4.values.tostring())
02919           _v175 = val2.region
02920           _v176 = _v175.cloud
02921           _v177 = _v176.header
02922           buff.write(_struct_I.pack(_v177.seq))
02923           _v178 = _v177.stamp
02924           _x = _v178
02925           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02926           _x = _v177.frame_id
02927           length = len(_x)
02928           if python3 or type(_x) == unicode:
02929             _x = _x.encode('utf-8')
02930             length = len(_x)
02931           buff.write(struct.pack('<I%ss'%length, length, _x))
02932           _x = _v176
02933           buff.write(_struct_2I.pack(_x.height, _x.width))
02934           length = len(_v176.fields)
02935           buff.write(_struct_I.pack(length))
02936           for val5 in _v176.fields:
02937             _x = val5.name
02938             length = len(_x)
02939             if python3 or type(_x) == unicode:
02940               _x = _x.encode('utf-8')
02941               length = len(_x)
02942             buff.write(struct.pack('<I%ss'%length, length, _x))
02943             _x = val5
02944             buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
02945           _x = _v176
02946           buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
02947           _x = _v176.data
02948           length = len(_x)
02949           # - if encoded as a list instead, serialize as bytes instead of string
02950           if type(_x) in [list, tuple]:
02951             buff.write(struct.pack('<I%sB'%length, length, *_x))
02952           else:
02953             buff.write(struct.pack('<I%ss'%length, length, _x))
02954           buff.write(_struct_B.pack(_v176.is_dense))
02955           length = len(_v175.mask)
02956           buff.write(_struct_I.pack(length))
02957           pattern = '<%si'%length
02958           buff.write(_v175.mask.tostring())
02959           _v179 = _v175.image
02960           _v180 = _v179.header
02961           buff.write(_struct_I.pack(_v180.seq))
02962           _v181 = _v180.stamp
02963           _x = _v181
02964           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02965           _x = _v180.frame_id
02966           length = len(_x)
02967           if python3 or type(_x) == unicode:
02968             _x = _x.encode('utf-8')
02969             length = len(_x)
02970           buff.write(struct.pack('<I%ss'%length, length, _x))
02971           _x = _v179
02972           buff.write(_struct_2I.pack(_x.height, _x.width))
02973           _x = _v179.encoding
02974           length = len(_x)
02975           if python3 or type(_x) == unicode:
02976             _x = _x.encode('utf-8')
02977             length = len(_x)
02978           buff.write(struct.pack('<I%ss'%length, length, _x))
02979           _x = _v179
02980           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
02981           _x = _v179.data
02982           length = len(_x)
02983           # - if encoded as a list instead, serialize as bytes instead of string
02984           if type(_x) in [list, tuple]:
02985             buff.write(struct.pack('<I%sB'%length, length, *_x))
02986           else:
02987             buff.write(struct.pack('<I%ss'%length, length, _x))
02988           _v182 = _v175.disparity_image
02989           _v183 = _v182.header
02990           buff.write(_struct_I.pack(_v183.seq))
02991           _v184 = _v183.stamp
02992           _x = _v184
02993           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02994           _x = _v183.frame_id
02995           length = len(_x)
02996           if python3 or type(_x) == unicode:
02997             _x = _x.encode('utf-8')
02998             length = len(_x)
02999           buff.write(struct.pack('<I%ss'%length, length, _x))
03000           _x = _v182
03001           buff.write(_struct_2I.pack(_x.height, _x.width))
03002           _x = _v182.encoding
03003           length = len(_x)
03004           if python3 or type(_x) == unicode:
03005             _x = _x.encode('utf-8')
03006             length = len(_x)
03007           buff.write(struct.pack('<I%ss'%length, length, _x))
03008           _x = _v182
03009           buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
03010           _x = _v182.data
03011           length = len(_x)
03012           # - if encoded as a list instead, serialize as bytes instead of string
03013           if type(_x) in [list, tuple]:
03014             buff.write(struct.pack('<I%sB'%length, length, *_x))
03015           else:
03016             buff.write(struct.pack('<I%ss'%length, length, _x))
03017           _v185 = _v175.cam_info
03018           _v186 = _v185.header
03019           buff.write(_struct_I.pack(_v186.seq))
03020           _v187 = _v186.stamp
03021           _x = _v187
03022           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03023           _x = _v186.frame_id
03024           length = len(_x)
03025           if python3 or type(_x) == unicode:
03026             _x = _x.encode('utf-8')
03027             length = len(_x)
03028           buff.write(struct.pack('<I%ss'%length, length, _x))
03029           _x = _v185
03030           buff.write(_struct_2I.pack(_x.height, _x.width))
03031           _x = _v185.distortion_model
03032           length = len(_x)
03033           if python3 or type(_x) == unicode:
03034             _x = _x.encode('utf-8')
03035             length = len(_x)
03036           buff.write(struct.pack('<I%ss'%length, length, _x))
03037           length = len(_v185.D)
03038           buff.write(_struct_I.pack(length))
03039           pattern = '<%sd'%length
03040           buff.write(_v185.D.tostring())
03041           buff.write(_v185.K.tostring())
03042           buff.write(_v185.R.tostring())
03043           buff.write(_v185.P.tostring())
03044           _x = _v185
03045           buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
03046           _v188 = _v185.roi
03047           _x = _v188
03048           buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
03049           _v189 = _v175.roi_box_pose
03050           _v190 = _v189.header
03051           buff.write(_struct_I.pack(_v190.seq))
03052           _v191 = _v190.stamp
03053           _x = _v191
03054           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03055           _x = _v190.frame_id
03056           length = len(_x)
03057           if python3 or type(_x) == unicode:
03058             _x = _x.encode('utf-8')
03059             length = len(_x)
03060           buff.write(struct.pack('<I%ss'%length, length, _x))
03061           _v192 = _v189.pose
03062           _v193 = _v192.position
03063           _x = _v193
03064           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03065           _v194 = _v192.orientation
03066           _x = _v194
03067           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03068           _v195 = _v175.roi_box_dims
03069           _x = _v195
03070           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03071           _x = val2.collision_name
03072           length = len(_x)
03073           if python3 or type(_x) == unicode:
03074             _x = _x.encode('utf-8')
03075             length = len(_x)
03076           buff.write(struct.pack('<I%ss'%length, length, _x))
03077       length = len(self.movable_obstacles)
03078       buff.write(_struct_I.pack(length))
03079       for val1 in self.movable_obstacles:
03080         _x = val1.reference_frame_id
03081         length = len(_x)
03082         if python3 or type(_x) == unicode:
03083           _x = _x.encode('utf-8')
03084           length = len(_x)
03085         buff.write(struct.pack('<I%ss'%length, length, _x))
03086         length = len(val1.potential_models)
03087         buff.write(_struct_I.pack(length))
03088         for val2 in val1.potential_models:
03089           buff.write(_struct_i.pack(val2.model_id))
03090           _v196 = val2.pose
03091           _v197 = _v196.header
03092           buff.write(_struct_I.pack(_v197.seq))
03093           _v198 = _v197.stamp
03094           _x = _v198
03095           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03096           _x = _v197.frame_id
03097           length = len(_x)
03098           if python3 or type(_x) == unicode:
03099             _x = _x.encode('utf-8')
03100             length = len(_x)
03101           buff.write(struct.pack('<I%ss'%length, length, _x))
03102           _v199 = _v196.pose
03103           _v200 = _v199.position
03104           _x = _v200
03105           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03106           _v201 = _v199.orientation
03107           _x = _v201
03108           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03109           buff.write(_struct_f.pack(val2.confidence))
03110           _x = val2.detector_name
03111           length = len(_x)
03112           if python3 or type(_x) == unicode:
03113             _x = _x.encode('utf-8')
03114             length = len(_x)
03115           buff.write(struct.pack('<I%ss'%length, length, _x))
03116         _v202 = val1.cluster
03117         _v203 = _v202.header
03118         buff.write(_struct_I.pack(_v203.seq))
03119         _v204 = _v203.stamp
03120         _x = _v204
03121         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03122         _x = _v203.frame_id
03123         length = len(_x)
03124         if python3 or type(_x) == unicode:
03125           _x = _x.encode('utf-8')
03126           length = len(_x)
03127         buff.write(struct.pack('<I%ss'%length, length, _x))
03128         length = len(_v202.points)
03129         buff.write(_struct_I.pack(length))
03130         for val3 in _v202.points:
03131           _x = val3
03132           buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
03133         length = len(_v202.channels)
03134         buff.write(_struct_I.pack(length))
03135         for val3 in _v202.channels:
03136           _x = val3.name
03137           length = len(_x)
03138           if python3 or type(_x) == unicode:
03139             _x = _x.encode('utf-8')
03140             length = len(_x)
03141           buff.write(struct.pack('<I%ss'%length, length, _x))
03142           length = len(val3.values)
03143           buff.write(_struct_I.pack(length))
03144           pattern = '<%sf'%length
03145           buff.write(val3.values.tostring())
03146         _v205 = val1.region
03147         _v206 = _v205.cloud
03148         _v207 = _v206.header
03149         buff.write(_struct_I.pack(_v207.seq))
03150         _v208 = _v207.stamp
03151         _x = _v208
03152         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03153         _x = _v207.frame_id
03154         length = len(_x)
03155         if python3 or type(_x) == unicode:
03156           _x = _x.encode('utf-8')
03157           length = len(_x)
03158         buff.write(struct.pack('<I%ss'%length, length, _x))
03159         _x = _v206
03160         buff.write(_struct_2I.pack(_x.height, _x.width))
03161         length = len(_v206.fields)
03162         buff.write(_struct_I.pack(length))
03163         for val4 in _v206.fields:
03164           _x = val4.name
03165           length = len(_x)
03166           if python3 or type(_x) == unicode:
03167             _x = _x.encode('utf-8')
03168             length = len(_x)
03169           buff.write(struct.pack('<I%ss'%length, length, _x))
03170           _x = val4
03171           buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
03172         _x = _v206
03173         buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
03174         _x = _v206.data
03175         length = len(_x)
03176         # - if encoded as a list instead, serialize as bytes instead of string
03177         if type(_x) in [list, tuple]:
03178           buff.write(struct.pack('<I%sB'%length, length, *_x))
03179         else:
03180           buff.write(struct.pack('<I%ss'%length, length, _x))
03181         buff.write(_struct_B.pack(_v206.is_dense))
03182         length = len(_v205.mask)
03183         buff.write(_struct_I.pack(length))
03184         pattern = '<%si'%length
03185         buff.write(_v205.mask.tostring())
03186         _v209 = _v205.image
03187         _v210 = _v209.header
03188         buff.write(_struct_I.pack(_v210.seq))
03189         _v211 = _v210.stamp
03190         _x = _v211
03191         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03192         _x = _v210.frame_id
03193         length = len(_x)
03194         if python3 or type(_x) == unicode:
03195           _x = _x.encode('utf-8')
03196           length = len(_x)
03197         buff.write(struct.pack('<I%ss'%length, length, _x))
03198         _x = _v209
03199         buff.write(_struct_2I.pack(_x.height, _x.width))
03200         _x = _v209.encoding
03201         length = len(_x)
03202         if python3 or type(_x) == unicode:
03203           _x = _x.encode('utf-8')
03204           length = len(_x)
03205         buff.write(struct.pack('<I%ss'%length, length, _x))
03206         _x = _v209
03207         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
03208         _x = _v209.data
03209         length = len(_x)
03210         # - if encoded as a list instead, serialize as bytes instead of string
03211         if type(_x) in [list, tuple]:
03212           buff.write(struct.pack('<I%sB'%length, length, *_x))
03213         else:
03214           buff.write(struct.pack('<I%ss'%length, length, _x))
03215         _v212 = _v205.disparity_image
03216         _v213 = _v212.header
03217         buff.write(_struct_I.pack(_v213.seq))
03218         _v214 = _v213.stamp
03219         _x = _v214
03220         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03221         _x = _v213.frame_id
03222         length = len(_x)
03223         if python3 or type(_x) == unicode:
03224           _x = _x.encode('utf-8')
03225           length = len(_x)
03226         buff.write(struct.pack('<I%ss'%length, length, _x))
03227         _x = _v212
03228         buff.write(_struct_2I.pack(_x.height, _x.width))
03229         _x = _v212.encoding
03230         length = len(_x)
03231         if python3 or type(_x) == unicode:
03232           _x = _x.encode('utf-8')
03233           length = len(_x)
03234         buff.write(struct.pack('<I%ss'%length, length, _x))
03235         _x = _v212
03236         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
03237         _x = _v212.data
03238         length = len(_x)
03239         # - if encoded as a list instead, serialize as bytes instead of string
03240         if type(_x) in [list, tuple]:
03241           buff.write(struct.pack('<I%sB'%length, length, *_x))
03242         else:
03243           buff.write(struct.pack('<I%ss'%length, length, _x))
03244         _v215 = _v205.cam_info
03245         _v216 = _v215.header
03246         buff.write(_struct_I.pack(_v216.seq))
03247         _v217 = _v216.stamp
03248         _x = _v217
03249         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03250         _x = _v216.frame_id
03251         length = len(_x)
03252         if python3 or type(_x) == unicode:
03253           _x = _x.encode('utf-8')
03254           length = len(_x)
03255         buff.write(struct.pack('<I%ss'%length, length, _x))
03256         _x = _v215
03257         buff.write(_struct_2I.pack(_x.height, _x.width))
03258         _x = _v215.distortion_model
03259         length = len(_x)
03260         if python3 or type(_x) == unicode:
03261           _x = _x.encode('utf-8')
03262           length = len(_x)
03263         buff.write(struct.pack('<I%ss'%length, length, _x))
03264         length = len(_v215.D)
03265         buff.write(_struct_I.pack(length))
03266         pattern = '<%sd'%length
03267         buff.write(_v215.D.tostring())
03268         buff.write(_v215.K.tostring())
03269         buff.write(_v215.R.tostring())
03270         buff.write(_v215.P.tostring())
03271         _x = _v215
03272         buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
03273         _v218 = _v215.roi
03274         _x = _v218
03275         buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
03276         _v219 = _v205.roi_box_pose
03277         _v220 = _v219.header
03278         buff.write(_struct_I.pack(_v220.seq))
03279         _v221 = _v220.stamp
03280         _x = _v221
03281         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03282         _x = _v220.frame_id
03283         length = len(_x)
03284         if python3 or type(_x) == unicode:
03285           _x = _x.encode('utf-8')
03286           length = len(_x)
03287         buff.write(struct.pack('<I%ss'%length, length, _x))
03288         _v222 = _v219.pose
03289         _v223 = _v222.position
03290         _x = _v223
03291         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03292         _v224 = _v222.orientation
03293         _x = _v224
03294         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03295         _v225 = _v205.roi_box_dims
03296         _x = _v225
03297         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03298         _x = val1.collision_name
03299         length = len(_x)
03300         if python3 or type(_x) == unicode:
03301           _x = _x.encode('utf-8')
03302           length = len(_x)
03303         buff.write(struct.pack('<I%ss'%length, length, _x))
03304     except struct.error as se: self._check_types(se)
03305     except TypeError as te: self._check_types(te)
03306 
03307   def deserialize_numpy(self, str, numpy):
03308     """
03309     unpack serialized message in str into this message instance using numpy for array types
03310     :param str: byte array of serialized message, ``str``
03311     :param numpy: numpy python module
03312     """
03313     try:
03314       if self.target is None:
03315         self.target = object_manipulation_msgs.msg.GraspableObject()
03316       if self.grasps_to_evaluate is None:
03317         self.grasps_to_evaluate = None
03318       if self.movable_obstacles is None:
03319         self.movable_obstacles = None
03320       end = 0
03321       start = end
03322       end += 4
03323       (length,) = _struct_I.unpack(str[start:end])
03324       start = end
03325       end += length
03326       if python3:
03327         self.arm_name = str[start:end].decode('utf-8')
03328       else:
03329         self.arm_name = str[start:end]
03330       start = end
03331       end += 4
03332       (length,) = _struct_I.unpack(str[start:end])
03333       start = end
03334       end += length
03335       if python3:
03336         self.target.reference_frame_id = str[start:end].decode('utf-8')
03337       else:
03338         self.target.reference_frame_id = str[start:end]
03339       start = end
03340       end += 4
03341       (length,) = _struct_I.unpack(str[start:end])
03342       self.target.potential_models = []
03343       for i in range(0, length):
03344         val1 = household_objects_database_msgs.msg.DatabaseModelPose()
03345         start = end
03346         end += 4
03347         (val1.model_id,) = _struct_i.unpack(str[start:end])
03348         _v226 = val1.pose
03349         _v227 = _v226.header
03350         start = end
03351         end += 4
03352         (_v227.seq,) = _struct_I.unpack(str[start:end])
03353         _v228 = _v227.stamp
03354         _x = _v228
03355         start = end
03356         end += 8
03357         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03358         start = end
03359         end += 4
03360         (length,) = _struct_I.unpack(str[start:end])
03361         start = end
03362         end += length
03363         if python3:
03364           _v227.frame_id = str[start:end].decode('utf-8')
03365         else:
03366           _v227.frame_id = str[start:end]
03367         _v229 = _v226.pose
03368         _v230 = _v229.position
03369         _x = _v230
03370         start = end
03371         end += 24
03372         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03373         _v231 = _v229.orientation
03374         _x = _v231
03375         start = end
03376         end += 32
03377         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03378         start = end
03379         end += 4
03380         (val1.confidence,) = _struct_f.unpack(str[start:end])
03381         start = end
03382         end += 4
03383         (length,) = _struct_I.unpack(str[start:end])
03384         start = end
03385         end += length
03386         if python3:
03387           val1.detector_name = str[start:end].decode('utf-8')
03388         else:
03389           val1.detector_name = str[start:end]
03390         self.target.potential_models.append(val1)
03391       _x = self
03392       start = end
03393       end += 12
03394       (_x.target.cluster.header.seq, _x.target.cluster.header.stamp.secs, _x.target.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03395       start = end
03396       end += 4
03397       (length,) = _struct_I.unpack(str[start:end])
03398       start = end
03399       end += length
03400       if python3:
03401         self.target.cluster.header.frame_id = str[start:end].decode('utf-8')
03402       else:
03403         self.target.cluster.header.frame_id = str[start:end]
03404       start = end
03405       end += 4
03406       (length,) = _struct_I.unpack(str[start:end])
03407       self.target.cluster.points = []
03408       for i in range(0, length):
03409         val1 = geometry_msgs.msg.Point32()
03410         _x = val1
03411         start = end
03412         end += 12
03413         (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
03414         self.target.cluster.points.append(val1)
03415       start = end
03416       end += 4
03417       (length,) = _struct_I.unpack(str[start:end])
03418       self.target.cluster.channels = []
03419       for i in range(0, length):
03420         val1 = sensor_msgs.msg.ChannelFloat32()
03421         start = end
03422         end += 4
03423         (length,) = _struct_I.unpack(str[start:end])
03424         start = end
03425         end += length
03426         if python3:
03427           val1.name = str[start:end].decode('utf-8')
03428         else:
03429           val1.name = str[start:end]
03430         start = end
03431         end += 4
03432         (length,) = _struct_I.unpack(str[start:end])
03433         pattern = '<%sf'%length
03434         start = end
03435         end += struct.calcsize(pattern)
03436         val1.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
03437         self.target.cluster.channels.append(val1)
03438       _x = self
03439       start = end
03440       end += 12
03441       (_x.target.region.cloud.header.seq, _x.target.region.cloud.header.stamp.secs, _x.target.region.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03442       start = end
03443       end += 4
03444       (length,) = _struct_I.unpack(str[start:end])
03445       start = end
03446       end += length
03447       if python3:
03448         self.target.region.cloud.header.frame_id = str[start:end].decode('utf-8')
03449       else:
03450         self.target.region.cloud.header.frame_id = str[start:end]
03451       _x = self
03452       start = end
03453       end += 8
03454       (_x.target.region.cloud.height, _x.target.region.cloud.width,) = _struct_2I.unpack(str[start:end])
03455       start = end
03456       end += 4
03457       (length,) = _struct_I.unpack(str[start:end])
03458       self.target.region.cloud.fields = []
03459       for i in range(0, length):
03460         val1 = sensor_msgs.msg.PointField()
03461         start = end
03462         end += 4
03463         (length,) = _struct_I.unpack(str[start:end])
03464         start = end
03465         end += length
03466         if python3:
03467           val1.name = str[start:end].decode('utf-8')
03468         else:
03469           val1.name = str[start:end]
03470         _x = val1
03471         start = end
03472         end += 9
03473         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
03474         self.target.region.cloud.fields.append(val1)
03475       _x = self
03476       start = end
03477       end += 9
03478       (_x.target.region.cloud.is_bigendian, _x.target.region.cloud.point_step, _x.target.region.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
03479       self.target.region.cloud.is_bigendian = bool(self.target.region.cloud.is_bigendian)
03480       start = end
03481       end += 4
03482       (length,) = _struct_I.unpack(str[start:end])
03483       start = end
03484       end += length
03485       if python3:
03486         self.target.region.cloud.data = str[start:end].decode('utf-8')
03487       else:
03488         self.target.region.cloud.data = str[start:end]
03489       start = end
03490       end += 1
03491       (self.target.region.cloud.is_dense,) = _struct_B.unpack(str[start:end])
03492       self.target.region.cloud.is_dense = bool(self.target.region.cloud.is_dense)
03493       start = end
03494       end += 4
03495       (length,) = _struct_I.unpack(str[start:end])
03496       pattern = '<%si'%length
03497       start = end
03498       end += struct.calcsize(pattern)
03499       self.target.region.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
03500       _x = self
03501       start = end
03502       end += 12
03503       (_x.target.region.image.header.seq, _x.target.region.image.header.stamp.secs, _x.target.region.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03504       start = end
03505       end += 4
03506       (length,) = _struct_I.unpack(str[start:end])
03507       start = end
03508       end += length
03509       if python3:
03510         self.target.region.image.header.frame_id = str[start:end].decode('utf-8')
03511       else:
03512         self.target.region.image.header.frame_id = str[start:end]
03513       _x = self
03514       start = end
03515       end += 8
03516       (_x.target.region.image.height, _x.target.region.image.width,) = _struct_2I.unpack(str[start:end])
03517       start = end
03518       end += 4
03519       (length,) = _struct_I.unpack(str[start:end])
03520       start = end
03521       end += length
03522       if python3:
03523         self.target.region.image.encoding = str[start:end].decode('utf-8')
03524       else:
03525         self.target.region.image.encoding = str[start:end]
03526       _x = self
03527       start = end
03528       end += 5
03529       (_x.target.region.image.is_bigendian, _x.target.region.image.step,) = _struct_BI.unpack(str[start:end])
03530       start = end
03531       end += 4
03532       (length,) = _struct_I.unpack(str[start:end])
03533       start = end
03534       end += length
03535       if python3:
03536         self.target.region.image.data = str[start:end].decode('utf-8')
03537       else:
03538         self.target.region.image.data = str[start:end]
03539       _x = self
03540       start = end
03541       end += 12
03542       (_x.target.region.disparity_image.header.seq, _x.target.region.disparity_image.header.stamp.secs, _x.target.region.disparity_image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03543       start = end
03544       end += 4
03545       (length,) = _struct_I.unpack(str[start:end])
03546       start = end
03547       end += length
03548       if python3:
03549         self.target.region.disparity_image.header.frame_id = str[start:end].decode('utf-8')
03550       else:
03551         self.target.region.disparity_image.header.frame_id = str[start:end]
03552       _x = self
03553       start = end
03554       end += 8
03555       (_x.target.region.disparity_image.height, _x.target.region.disparity_image.width,) = _struct_2I.unpack(str[start:end])
03556       start = end
03557       end += 4
03558       (length,) = _struct_I.unpack(str[start:end])
03559       start = end
03560       end += length
03561       if python3:
03562         self.target.region.disparity_image.encoding = str[start:end].decode('utf-8')
03563       else:
03564         self.target.region.disparity_image.encoding = str[start:end]
03565       _x = self
03566       start = end
03567       end += 5
03568       (_x.target.region.disparity_image.is_bigendian, _x.target.region.disparity_image.step,) = _struct_BI.unpack(str[start:end])
03569       start = end
03570       end += 4
03571       (length,) = _struct_I.unpack(str[start:end])
03572       start = end
03573       end += length
03574       if python3:
03575         self.target.region.disparity_image.data = str[start:end].decode('utf-8')
03576       else:
03577         self.target.region.disparity_image.data = str[start:end]
03578       _x = self
03579       start = end
03580       end += 12
03581       (_x.target.region.cam_info.header.seq, _x.target.region.cam_info.header.stamp.secs, _x.target.region.cam_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03582       start = end
03583       end += 4
03584       (length,) = _struct_I.unpack(str[start:end])
03585       start = end
03586       end += length
03587       if python3:
03588         self.target.region.cam_info.header.frame_id = str[start:end].decode('utf-8')
03589       else:
03590         self.target.region.cam_info.header.frame_id = str[start:end]
03591       _x = self
03592       start = end
03593       end += 8
03594       (_x.target.region.cam_info.height, _x.target.region.cam_info.width,) = _struct_2I.unpack(str[start:end])
03595       start = end
03596       end += 4
03597       (length,) = _struct_I.unpack(str[start:end])
03598       start = end
03599       end += length
03600       if python3:
03601         self.target.region.cam_info.distortion_model = str[start:end].decode('utf-8')
03602       else:
03603         self.target.region.cam_info.distortion_model = str[start:end]
03604       start = end
03605       end += 4
03606       (length,) = _struct_I.unpack(str[start:end])
03607       pattern = '<%sd'%length
03608       start = end
03609       end += struct.calcsize(pattern)
03610       self.target.region.cam_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03611       start = end
03612       end += 72
03613       self.target.region.cam_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
03614       start = end
03615       end += 72
03616       self.target.region.cam_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
03617       start = end
03618       end += 96
03619       self.target.region.cam_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
03620       _x = self
03621       start = end
03622       end += 37
03623       (_x.target.region.cam_info.binning_x, _x.target.region.cam_info.binning_y, _x.target.region.cam_info.roi.x_offset, _x.target.region.cam_info.roi.y_offset, _x.target.region.cam_info.roi.height, _x.target.region.cam_info.roi.width, _x.target.region.cam_info.roi.do_rectify, _x.target.region.roi_box_pose.header.seq, _x.target.region.roi_box_pose.header.stamp.secs, _x.target.region.roi_box_pose.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
03624       self.target.region.cam_info.roi.do_rectify = bool(self.target.region.cam_info.roi.do_rectify)
03625       start = end
03626       end += 4
03627       (length,) = _struct_I.unpack(str[start:end])
03628       start = end
03629       end += length
03630       if python3:
03631         self.target.region.roi_box_pose.header.frame_id = str[start:end].decode('utf-8')
03632       else:
03633         self.target.region.roi_box_pose.header.frame_id = str[start:end]
03634       _x = self
03635       start = end
03636       end += 80
03637       (_x.target.region.roi_box_pose.pose.position.x, _x.target.region.roi_box_pose.pose.position.y, _x.target.region.roi_box_pose.pose.position.z, _x.target.region.roi_box_pose.pose.orientation.x, _x.target.region.roi_box_pose.pose.orientation.y, _x.target.region.roi_box_pose.pose.orientation.z, _x.target.region.roi_box_pose.pose.orientation.w, _x.target.region.roi_box_dims.x, _x.target.region.roi_box_dims.y, _x.target.region.roi_box_dims.z,) = _struct_10d.unpack(str[start:end])
03638       start = end
03639       end += 4
03640       (length,) = _struct_I.unpack(str[start:end])
03641       start = end
03642       end += length
03643       if python3:
03644         self.target.collision_name = str[start:end].decode('utf-8')
03645       else:
03646         self.target.collision_name = str[start:end]
03647       start = end
03648       end += 4
03649       (length,) = _struct_I.unpack(str[start:end])
03650       start = end
03651       end += length
03652       if python3:
03653         self.collision_object_name = str[start:end].decode('utf-8')
03654       else:
03655         self.collision_object_name = str[start:end]
03656       start = end
03657       end += 4
03658       (length,) = _struct_I.unpack(str[start:end])
03659       start = end
03660       end += length
03661       if python3:
03662         self.collision_support_surface_name = str[start:end].decode('utf-8')
03663       else:
03664         self.collision_support_surface_name = str[start:end]
03665       start = end
03666       end += 4
03667       (length,) = _struct_I.unpack(str[start:end])
03668       self.grasps_to_evaluate = []
03669       for i in range(0, length):
03670         val1 = object_manipulation_msgs.msg.Grasp()
03671         _v232 = val1.pre_grasp_posture
03672         _v233 = _v232.header
03673         start = end
03674         end += 4
03675         (_v233.seq,) = _struct_I.unpack(str[start:end])
03676         _v234 = _v233.stamp
03677         _x = _v234
03678         start = end
03679         end += 8
03680         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03681         start = end
03682         end += 4
03683         (length,) = _struct_I.unpack(str[start:end])
03684         start = end
03685         end += length
03686         if python3:
03687           _v233.frame_id = str[start:end].decode('utf-8')
03688         else:
03689           _v233.frame_id = str[start:end]
03690         start = end
03691         end += 4
03692         (length,) = _struct_I.unpack(str[start:end])
03693         _v232.name = []
03694         for i in range(0, length):
03695           start = end
03696           end += 4
03697           (length,) = _struct_I.unpack(str[start:end])
03698           start = end
03699           end += length
03700           if python3:
03701             val3 = str[start:end].decode('utf-8')
03702           else:
03703             val3 = str[start:end]
03704           _v232.name.append(val3)
03705         start = end
03706         end += 4
03707         (length,) = _struct_I.unpack(str[start:end])
03708         pattern = '<%sd'%length
03709         start = end
03710         end += struct.calcsize(pattern)
03711         _v232.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03712         start = end
03713         end += 4
03714         (length,) = _struct_I.unpack(str[start:end])
03715         pattern = '<%sd'%length
03716         start = end
03717         end += struct.calcsize(pattern)
03718         _v232.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03719         start = end
03720         end += 4
03721         (length,) = _struct_I.unpack(str[start:end])
03722         pattern = '<%sd'%length
03723         start = end
03724         end += struct.calcsize(pattern)
03725         _v232.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03726         _v235 = val1.grasp_posture
03727         _v236 = _v235.header
03728         start = end
03729         end += 4
03730         (_v236.seq,) = _struct_I.unpack(str[start:end])
03731         _v237 = _v236.stamp
03732         _x = _v237
03733         start = end
03734         end += 8
03735         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03736         start = end
03737         end += 4
03738         (length,) = _struct_I.unpack(str[start:end])
03739         start = end
03740         end += length
03741         if python3:
03742           _v236.frame_id = str[start:end].decode('utf-8')
03743         else:
03744           _v236.frame_id = str[start:end]
03745         start = end
03746         end += 4
03747         (length,) = _struct_I.unpack(str[start:end])
03748         _v235.name = []
03749         for i in range(0, length):
03750           start = end
03751           end += 4
03752           (length,) = _struct_I.unpack(str[start:end])
03753           start = end
03754           end += length
03755           if python3:
03756             val3 = str[start:end].decode('utf-8')
03757           else:
03758             val3 = str[start:end]
03759           _v235.name.append(val3)
03760         start = end
03761         end += 4
03762         (length,) = _struct_I.unpack(str[start:end])
03763         pattern = '<%sd'%length
03764         start = end
03765         end += struct.calcsize(pattern)
03766         _v235.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03767         start = end
03768         end += 4
03769         (length,) = _struct_I.unpack(str[start:end])
03770         pattern = '<%sd'%length
03771         start = end
03772         end += struct.calcsize(pattern)
03773         _v235.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03774         start = end
03775         end += 4
03776         (length,) = _struct_I.unpack(str[start:end])
03777         pattern = '<%sd'%length
03778         start = end
03779         end += struct.calcsize(pattern)
03780         _v235.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03781         _v238 = val1.grasp_pose
03782         _v239 = _v238.position
03783         _x = _v239
03784         start = end
03785         end += 24
03786         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03787         _v240 = _v238.orientation
03788         _x = _v240
03789         start = end
03790         end += 32
03791         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03792         _x = val1
03793         start = end
03794         end += 17
03795         (_x.success_probability, _x.cluster_rep, _x.desired_approach_distance, _x.min_approach_distance,) = _struct_dB2f.unpack(str[start:end])
03796         val1.cluster_rep = bool(val1.cluster_rep)
03797         start = end
03798         end += 4
03799         (length,) = _struct_I.unpack(str[start:end])
03800         val1.moved_obstacles = []
03801         for i in range(0, length):
03802           val2 = object_manipulation_msgs.msg.GraspableObject()
03803           start = end
03804           end += 4
03805           (length,) = _struct_I.unpack(str[start:end])
03806           start = end
03807           end += length
03808           if python3:
03809             val2.reference_frame_id = str[start:end].decode('utf-8')
03810           else:
03811             val2.reference_frame_id = str[start:end]
03812           start = end
03813           end += 4
03814           (length,) = _struct_I.unpack(str[start:end])
03815           val2.potential_models = []
03816           for i in range(0, length):
03817             val3 = household_objects_database_msgs.msg.DatabaseModelPose()
03818             start = end
03819             end += 4
03820             (val3.model_id,) = _struct_i.unpack(str[start:end])
03821             _v241 = val3.pose
03822             _v242 = _v241.header
03823             start = end
03824             end += 4
03825             (_v242.seq,) = _struct_I.unpack(str[start:end])
03826             _v243 = _v242.stamp
03827             _x = _v243
03828             start = end
03829             end += 8
03830             (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03831             start = end
03832             end += 4
03833             (length,) = _struct_I.unpack(str[start:end])
03834             start = end
03835             end += length
03836             if python3:
03837               _v242.frame_id = str[start:end].decode('utf-8')
03838             else:
03839               _v242.frame_id = str[start:end]
03840             _v244 = _v241.pose
03841             _v245 = _v244.position
03842             _x = _v245
03843             start = end
03844             end += 24
03845             (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03846             _v246 = _v244.orientation
03847             _x = _v246
03848             start = end
03849             end += 32
03850             (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03851             start = end
03852             end += 4
03853             (val3.confidence,) = _struct_f.unpack(str[start:end])
03854             start = end
03855             end += 4
03856             (length,) = _struct_I.unpack(str[start:end])
03857             start = end
03858             end += length
03859             if python3:
03860               val3.detector_name = str[start:end].decode('utf-8')
03861             else:
03862               val3.detector_name = str[start:end]
03863             val2.potential_models.append(val3)
03864           _v247 = val2.cluster
03865           _v248 = _v247.header
03866           start = end
03867           end += 4
03868           (_v248.seq,) = _struct_I.unpack(str[start:end])
03869           _v249 = _v248.stamp
03870           _x = _v249
03871           start = end
03872           end += 8
03873           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03874           start = end
03875           end += 4
03876           (length,) = _struct_I.unpack(str[start:end])
03877           start = end
03878           end += length
03879           if python3:
03880             _v248.frame_id = str[start:end].decode('utf-8')
03881           else:
03882             _v248.frame_id = str[start:end]
03883           start = end
03884           end += 4
03885           (length,) = _struct_I.unpack(str[start:end])
03886           _v247.points = []
03887           for i in range(0, length):
03888             val4 = geometry_msgs.msg.Point32()
03889             _x = val4
03890             start = end
03891             end += 12
03892             (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
03893             _v247.points.append(val4)
03894           start = end
03895           end += 4
03896           (length,) = _struct_I.unpack(str[start:end])
03897           _v247.channels = []
03898           for i in range(0, length):
03899             val4 = sensor_msgs.msg.ChannelFloat32()
03900             start = end
03901             end += 4
03902             (length,) = _struct_I.unpack(str[start:end])
03903             start = end
03904             end += length
03905             if python3:
03906               val4.name = str[start:end].decode('utf-8')
03907             else:
03908               val4.name = str[start:end]
03909             start = end
03910             end += 4
03911             (length,) = _struct_I.unpack(str[start:end])
03912             pattern = '<%sf'%length
03913             start = end
03914             end += struct.calcsize(pattern)
03915             val4.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
03916             _v247.channels.append(val4)
03917           _v250 = val2.region
03918           _v251 = _v250.cloud
03919           _v252 = _v251.header
03920           start = end
03921           end += 4
03922           (_v252.seq,) = _struct_I.unpack(str[start:end])
03923           _v253 = _v252.stamp
03924           _x = _v253
03925           start = end
03926           end += 8
03927           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03928           start = end
03929           end += 4
03930           (length,) = _struct_I.unpack(str[start:end])
03931           start = end
03932           end += length
03933           if python3:
03934             _v252.frame_id = str[start:end].decode('utf-8')
03935           else:
03936             _v252.frame_id = str[start:end]
03937           _x = _v251
03938           start = end
03939           end += 8
03940           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
03941           start = end
03942           end += 4
03943           (length,) = _struct_I.unpack(str[start:end])
03944           _v251.fields = []
03945           for i in range(0, length):
03946             val5 = sensor_msgs.msg.PointField()
03947             start = end
03948             end += 4
03949             (length,) = _struct_I.unpack(str[start:end])
03950             start = end
03951             end += length
03952             if python3:
03953               val5.name = str[start:end].decode('utf-8')
03954             else:
03955               val5.name = str[start:end]
03956             _x = val5
03957             start = end
03958             end += 9
03959             (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
03960             _v251.fields.append(val5)
03961           _x = _v251
03962           start = end
03963           end += 9
03964           (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
03965           _v251.is_bigendian = bool(_v251.is_bigendian)
03966           start = end
03967           end += 4
03968           (length,) = _struct_I.unpack(str[start:end])
03969           start = end
03970           end += length
03971           if python3:
03972             _v251.data = str[start:end].decode('utf-8')
03973           else:
03974             _v251.data = str[start:end]
03975           start = end
03976           end += 1
03977           (_v251.is_dense,) = _struct_B.unpack(str[start:end])
03978           _v251.is_dense = bool(_v251.is_dense)
03979           start = end
03980           end += 4
03981           (length,) = _struct_I.unpack(str[start:end])
03982           pattern = '<%si'%length
03983           start = end
03984           end += struct.calcsize(pattern)
03985           _v250.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
03986           _v254 = _v250.image
03987           _v255 = _v254.header
03988           start = end
03989           end += 4
03990           (_v255.seq,) = _struct_I.unpack(str[start:end])
03991           _v256 = _v255.stamp
03992           _x = _v256
03993           start = end
03994           end += 8
03995           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03996           start = end
03997           end += 4
03998           (length,) = _struct_I.unpack(str[start:end])
03999           start = end
04000           end += length
04001           if python3:
04002             _v255.frame_id = str[start:end].decode('utf-8')
04003           else:
04004             _v255.frame_id = str[start:end]
04005           _x = _v254
04006           start = end
04007           end += 8
04008           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04009           start = end
04010           end += 4
04011           (length,) = _struct_I.unpack(str[start:end])
04012           start = end
04013           end += length
04014           if python3:
04015             _v254.encoding = str[start:end].decode('utf-8')
04016           else:
04017             _v254.encoding = str[start:end]
04018           _x = _v254
04019           start = end
04020           end += 5
04021           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
04022           start = end
04023           end += 4
04024           (length,) = _struct_I.unpack(str[start:end])
04025           start = end
04026           end += length
04027           if python3:
04028             _v254.data = str[start:end].decode('utf-8')
04029           else:
04030             _v254.data = str[start:end]
04031           _v257 = _v250.disparity_image
04032           _v258 = _v257.header
04033           start = end
04034           end += 4
04035           (_v258.seq,) = _struct_I.unpack(str[start:end])
04036           _v259 = _v258.stamp
04037           _x = _v259
04038           start = end
04039           end += 8
04040           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04041           start = end
04042           end += 4
04043           (length,) = _struct_I.unpack(str[start:end])
04044           start = end
04045           end += length
04046           if python3:
04047             _v258.frame_id = str[start:end].decode('utf-8')
04048           else:
04049             _v258.frame_id = str[start:end]
04050           _x = _v257
04051           start = end
04052           end += 8
04053           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04054           start = end
04055           end += 4
04056           (length,) = _struct_I.unpack(str[start:end])
04057           start = end
04058           end += length
04059           if python3:
04060             _v257.encoding = str[start:end].decode('utf-8')
04061           else:
04062             _v257.encoding = str[start:end]
04063           _x = _v257
04064           start = end
04065           end += 5
04066           (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
04067           start = end
04068           end += 4
04069           (length,) = _struct_I.unpack(str[start:end])
04070           start = end
04071           end += length
04072           if python3:
04073             _v257.data = str[start:end].decode('utf-8')
04074           else:
04075             _v257.data = str[start:end]
04076           _v260 = _v250.cam_info
04077           _v261 = _v260.header
04078           start = end
04079           end += 4
04080           (_v261.seq,) = _struct_I.unpack(str[start:end])
04081           _v262 = _v261.stamp
04082           _x = _v262
04083           start = end
04084           end += 8
04085           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04086           start = end
04087           end += 4
04088           (length,) = _struct_I.unpack(str[start:end])
04089           start = end
04090           end += length
04091           if python3:
04092             _v261.frame_id = str[start:end].decode('utf-8')
04093           else:
04094             _v261.frame_id = str[start:end]
04095           _x = _v260
04096           start = end
04097           end += 8
04098           (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04099           start = end
04100           end += 4
04101           (length,) = _struct_I.unpack(str[start:end])
04102           start = end
04103           end += length
04104           if python3:
04105             _v260.distortion_model = str[start:end].decode('utf-8')
04106           else:
04107             _v260.distortion_model = str[start:end]
04108           start = end
04109           end += 4
04110           (length,) = _struct_I.unpack(str[start:end])
04111           pattern = '<%sd'%length
04112           start = end
04113           end += struct.calcsize(pattern)
04114           _v260.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
04115           start = end
04116           end += 72
04117           _v260.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
04118           start = end
04119           end += 72
04120           _v260.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
04121           start = end
04122           end += 96
04123           _v260.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
04124           _x = _v260
04125           start = end
04126           end += 8
04127           (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
04128           _v263 = _v260.roi
04129           _x = _v263
04130           start = end
04131           end += 17
04132           (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
04133           _v263.do_rectify = bool(_v263.do_rectify)
04134           _v264 = _v250.roi_box_pose
04135           _v265 = _v264.header
04136           start = end
04137           end += 4
04138           (_v265.seq,) = _struct_I.unpack(str[start:end])
04139           _v266 = _v265.stamp
04140           _x = _v266
04141           start = end
04142           end += 8
04143           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04144           start = end
04145           end += 4
04146           (length,) = _struct_I.unpack(str[start:end])
04147           start = end
04148           end += length
04149           if python3:
04150             _v265.frame_id = str[start:end].decode('utf-8')
04151           else:
04152             _v265.frame_id = str[start:end]
04153           _v267 = _v264.pose
04154           _v268 = _v267.position
04155           _x = _v268
04156           start = end
04157           end += 24
04158           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04159           _v269 = _v267.orientation
04160           _x = _v269
04161           start = end
04162           end += 32
04163           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04164           _v270 = _v250.roi_box_dims
04165           _x = _v270
04166           start = end
04167           end += 24
04168           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04169           start = end
04170           end += 4
04171           (length,) = _struct_I.unpack(str[start:end])
04172           start = end
04173           end += length
04174           if python3:
04175             val2.collision_name = str[start:end].decode('utf-8')
04176           else:
04177             val2.collision_name = str[start:end]
04178           val1.moved_obstacles.append(val2)
04179         self.grasps_to_evaluate.append(val1)
04180       start = end
04181       end += 4
04182       (length,) = _struct_I.unpack(str[start:end])
04183       self.movable_obstacles = []
04184       for i in range(0, length):
04185         val1 = object_manipulation_msgs.msg.GraspableObject()
04186         start = end
04187         end += 4
04188         (length,) = _struct_I.unpack(str[start:end])
04189         start = end
04190         end += length
04191         if python3:
04192           val1.reference_frame_id = str[start:end].decode('utf-8')
04193         else:
04194           val1.reference_frame_id = str[start:end]
04195         start = end
04196         end += 4
04197         (length,) = _struct_I.unpack(str[start:end])
04198         val1.potential_models = []
04199         for i in range(0, length):
04200           val2 = household_objects_database_msgs.msg.DatabaseModelPose()
04201           start = end
04202           end += 4
04203           (val2.model_id,) = _struct_i.unpack(str[start:end])
04204           _v271 = val2.pose
04205           _v272 = _v271.header
04206           start = end
04207           end += 4
04208           (_v272.seq,) = _struct_I.unpack(str[start:end])
04209           _v273 = _v272.stamp
04210           _x = _v273
04211           start = end
04212           end += 8
04213           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04214           start = end
04215           end += 4
04216           (length,) = _struct_I.unpack(str[start:end])
04217           start = end
04218           end += length
04219           if python3:
04220             _v272.frame_id = str[start:end].decode('utf-8')
04221           else:
04222             _v272.frame_id = str[start:end]
04223           _v274 = _v271.pose
04224           _v275 = _v274.position
04225           _x = _v275
04226           start = end
04227           end += 24
04228           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04229           _v276 = _v274.orientation
04230           _x = _v276
04231           start = end
04232           end += 32
04233           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04234           start = end
04235           end += 4
04236           (val2.confidence,) = _struct_f.unpack(str[start:end])
04237           start = end
04238           end += 4
04239           (length,) = _struct_I.unpack(str[start:end])
04240           start = end
04241           end += length
04242           if python3:
04243             val2.detector_name = str[start:end].decode('utf-8')
04244           else:
04245             val2.detector_name = str[start:end]
04246           val1.potential_models.append(val2)
04247         _v277 = val1.cluster
04248         _v278 = _v277.header
04249         start = end
04250         end += 4
04251         (_v278.seq,) = _struct_I.unpack(str[start:end])
04252         _v279 = _v278.stamp
04253         _x = _v279
04254         start = end
04255         end += 8
04256         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04257         start = end
04258         end += 4
04259         (length,) = _struct_I.unpack(str[start:end])
04260         start = end
04261         end += length
04262         if python3:
04263           _v278.frame_id = str[start:end].decode('utf-8')
04264         else:
04265           _v278.frame_id = str[start:end]
04266         start = end
04267         end += 4
04268         (length,) = _struct_I.unpack(str[start:end])
04269         _v277.points = []
04270         for i in range(0, length):
04271           val3 = geometry_msgs.msg.Point32()
04272           _x = val3
04273           start = end
04274           end += 12
04275           (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
04276           _v277.points.append(val3)
04277         start = end
04278         end += 4
04279         (length,) = _struct_I.unpack(str[start:end])
04280         _v277.channels = []
04281         for i in range(0, length):
04282           val3 = sensor_msgs.msg.ChannelFloat32()
04283           start = end
04284           end += 4
04285           (length,) = _struct_I.unpack(str[start:end])
04286           start = end
04287           end += length
04288           if python3:
04289             val3.name = str[start:end].decode('utf-8')
04290           else:
04291             val3.name = str[start:end]
04292           start = end
04293           end += 4
04294           (length,) = _struct_I.unpack(str[start:end])
04295           pattern = '<%sf'%length
04296           start = end
04297           end += struct.calcsize(pattern)
04298           val3.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
04299           _v277.channels.append(val3)
04300         _v280 = val1.region
04301         _v281 = _v280.cloud
04302         _v282 = _v281.header
04303         start = end
04304         end += 4
04305         (_v282.seq,) = _struct_I.unpack(str[start:end])
04306         _v283 = _v282.stamp
04307         _x = _v283
04308         start = end
04309         end += 8
04310         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04311         start = end
04312         end += 4
04313         (length,) = _struct_I.unpack(str[start:end])
04314         start = end
04315         end += length
04316         if python3:
04317           _v282.frame_id = str[start:end].decode('utf-8')
04318         else:
04319           _v282.frame_id = str[start:end]
04320         _x = _v281
04321         start = end
04322         end += 8
04323         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04324         start = end
04325         end += 4
04326         (length,) = _struct_I.unpack(str[start:end])
04327         _v281.fields = []
04328         for i in range(0, length):
04329           val4 = sensor_msgs.msg.PointField()
04330           start = end
04331           end += 4
04332           (length,) = _struct_I.unpack(str[start:end])
04333           start = end
04334           end += length
04335           if python3:
04336             val4.name = str[start:end].decode('utf-8')
04337           else:
04338             val4.name = str[start:end]
04339           _x = val4
04340           start = end
04341           end += 9
04342           (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
04343           _v281.fields.append(val4)
04344         _x = _v281
04345         start = end
04346         end += 9
04347         (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
04348         _v281.is_bigendian = bool(_v281.is_bigendian)
04349         start = end
04350         end += 4
04351         (length,) = _struct_I.unpack(str[start:end])
04352         start = end
04353         end += length
04354         if python3:
04355           _v281.data = str[start:end].decode('utf-8')
04356         else:
04357           _v281.data = str[start:end]
04358         start = end
04359         end += 1
04360         (_v281.is_dense,) = _struct_B.unpack(str[start:end])
04361         _v281.is_dense = bool(_v281.is_dense)
04362         start = end
04363         end += 4
04364         (length,) = _struct_I.unpack(str[start:end])
04365         pattern = '<%si'%length
04366         start = end
04367         end += struct.calcsize(pattern)
04368         _v280.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
04369         _v284 = _v280.image
04370         _v285 = _v284.header
04371         start = end
04372         end += 4
04373         (_v285.seq,) = _struct_I.unpack(str[start:end])
04374         _v286 = _v285.stamp
04375         _x = _v286
04376         start = end
04377         end += 8
04378         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04379         start = end
04380         end += 4
04381         (length,) = _struct_I.unpack(str[start:end])
04382         start = end
04383         end += length
04384         if python3:
04385           _v285.frame_id = str[start:end].decode('utf-8')
04386         else:
04387           _v285.frame_id = str[start:end]
04388         _x = _v284
04389         start = end
04390         end += 8
04391         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04392         start = end
04393         end += 4
04394         (length,) = _struct_I.unpack(str[start:end])
04395         start = end
04396         end += length
04397         if python3:
04398           _v284.encoding = str[start:end].decode('utf-8')
04399         else:
04400           _v284.encoding = str[start:end]
04401         _x = _v284
04402         start = end
04403         end += 5
04404         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
04405         start = end
04406         end += 4
04407         (length,) = _struct_I.unpack(str[start:end])
04408         start = end
04409         end += length
04410         if python3:
04411           _v284.data = str[start:end].decode('utf-8')
04412         else:
04413           _v284.data = str[start:end]
04414         _v287 = _v280.disparity_image
04415         _v288 = _v287.header
04416         start = end
04417         end += 4
04418         (_v288.seq,) = _struct_I.unpack(str[start:end])
04419         _v289 = _v288.stamp
04420         _x = _v289
04421         start = end
04422         end += 8
04423         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04424         start = end
04425         end += 4
04426         (length,) = _struct_I.unpack(str[start:end])
04427         start = end
04428         end += length
04429         if python3:
04430           _v288.frame_id = str[start:end].decode('utf-8')
04431         else:
04432           _v288.frame_id = str[start:end]
04433         _x = _v287
04434         start = end
04435         end += 8
04436         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04437         start = end
04438         end += 4
04439         (length,) = _struct_I.unpack(str[start:end])
04440         start = end
04441         end += length
04442         if python3:
04443           _v287.encoding = str[start:end].decode('utf-8')
04444         else:
04445           _v287.encoding = str[start:end]
04446         _x = _v287
04447         start = end
04448         end += 5
04449         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
04450         start = end
04451         end += 4
04452         (length,) = _struct_I.unpack(str[start:end])
04453         start = end
04454         end += length
04455         if python3:
04456           _v287.data = str[start:end].decode('utf-8')
04457         else:
04458           _v287.data = str[start:end]
04459         _v290 = _v280.cam_info
04460         _v291 = _v290.header
04461         start = end
04462         end += 4
04463         (_v291.seq,) = _struct_I.unpack(str[start:end])
04464         _v292 = _v291.stamp
04465         _x = _v292
04466         start = end
04467         end += 8
04468         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04469         start = end
04470         end += 4
04471         (length,) = _struct_I.unpack(str[start:end])
04472         start = end
04473         end += length
04474         if python3:
04475           _v291.frame_id = str[start:end].decode('utf-8')
04476         else:
04477           _v291.frame_id = str[start:end]
04478         _x = _v290
04479         start = end
04480         end += 8
04481         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
04482         start = end
04483         end += 4
04484         (length,) = _struct_I.unpack(str[start:end])
04485         start = end
04486         end += length
04487         if python3:
04488           _v290.distortion_model = str[start:end].decode('utf-8')
04489         else:
04490           _v290.distortion_model = str[start:end]
04491         start = end
04492         end += 4
04493         (length,) = _struct_I.unpack(str[start:end])
04494         pattern = '<%sd'%length
04495         start = end
04496         end += struct.calcsize(pattern)
04497         _v290.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
04498         start = end
04499         end += 72
04500         _v290.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
04501         start = end
04502         end += 72
04503         _v290.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
04504         start = end
04505         end += 96
04506         _v290.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
04507         _x = _v290
04508         start = end
04509         end += 8
04510         (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
04511         _v293 = _v290.roi
04512         _x = _v293
04513         start = end
04514         end += 17
04515         (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
04516         _v293.do_rectify = bool(_v293.do_rectify)
04517         _v294 = _v280.roi_box_pose
04518         _v295 = _v294.header
04519         start = end
04520         end += 4
04521         (_v295.seq,) = _struct_I.unpack(str[start:end])
04522         _v296 = _v295.stamp
04523         _x = _v296
04524         start = end
04525         end += 8
04526         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04527         start = end
04528         end += 4
04529         (length,) = _struct_I.unpack(str[start:end])
04530         start = end
04531         end += length
04532         if python3:
04533           _v295.frame_id = str[start:end].decode('utf-8')
04534         else:
04535           _v295.frame_id = str[start:end]
04536         _v297 = _v294.pose
04537         _v298 = _v297.position
04538         _x = _v298
04539         start = end
04540         end += 24
04541         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04542         _v299 = _v297.orientation
04543         _x = _v299
04544         start = end
04545         end += 32
04546         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04547         _v300 = _v280.roi_box_dims
04548         _x = _v300
04549         start = end
04550         end += 24
04551         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04552         start = end
04553         end += 4
04554         (length,) = _struct_I.unpack(str[start:end])
04555         start = end
04556         end += length
04557         if python3:
04558           val1.collision_name = str[start:end].decode('utf-8')
04559         else:
04560           val1.collision_name = str[start:end]
04561         self.movable_obstacles.append(val1)
04562       return self
04563     except struct.error as e:
04564       raise genpy.DeserializationError(e) #most likely buffer underfill
04565 
04566 _struct_I = genpy.struct_I
04567 _struct_IBI = struct.Struct("<IBI")
04568 _struct_6IB3I = struct.Struct("<6IB3I")
04569 _struct_B = struct.Struct("<B")
04570 _struct_12d = struct.Struct("<12d")
04571 _struct_f = struct.Struct("<f")
04572 _struct_i = struct.Struct("<i")
04573 _struct_dB2f = struct.Struct("<dB2f")
04574 _struct_BI = struct.Struct("<BI")
04575 _struct_10d = struct.Struct("<10d")
04576 _struct_3f = struct.Struct("<3f")
04577 _struct_3I = struct.Struct("<3I")
04578 _struct_9d = struct.Struct("<9d")
04579 _struct_B2I = struct.Struct("<B2I")
04580 _struct_4d = struct.Struct("<4d")
04581 _struct_2I = struct.Struct("<2I")
04582 _struct_4IB = struct.Struct("<4IB")
04583 _struct_3d = struct.Struct("<3d")


object_manipulation_msgs
Author(s): Matei Ciocarlie
autogenerated on Thu Jan 2 2014 11:38:11