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


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