_GraspStatus.py
Go to the documentation of this file.
00001 """autogenerated by genpy from object_manipulation_msgs/GraspStatusRequest.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006 
00007 import geometry_msgs.msg
00008 import std_msgs.msg
00009 import object_manipulation_msgs.msg
00010 import household_objects_database_msgs.msg
00011 import sensor_msgs.msg
00012 
00013 class GraspStatusRequest(genpy.Message):
00014   _md5sum = "46f92cc36c8200695a0cfa52ac75eb0a"
00015   _type = "object_manipulation_msgs/GraspStatusRequest"
00016   _has_header = False #flag to mark the presence of a Header object
00017   _full_text = """
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 object_manipulation_msgs/Grasp grasp
00026 
00027 
00028 ================================================================================
00029 MSG: object_manipulation_msgs/Grasp
00030 
00031 # The internal posture of the hand for the pre-grasp
00032 # only positions are used
00033 sensor_msgs/JointState pre_grasp_posture
00034 
00035 # The internal posture of the hand for the grasp
00036 # positions and efforts are used
00037 sensor_msgs/JointState grasp_posture
00038 
00039 # The position of the end-effector for the grasp relative to a reference frame 
00040 # (that is always specified elsewhere, not in this message)
00041 geometry_msgs/Pose grasp_pose
00042 
00043 # The estimated probability of success for this grasp
00044 float64 success_probability
00045 
00046 # Debug flag to indicate that this grasp would be the best in its cluster
00047 bool cluster_rep
00048 
00049 # how far the pre-grasp should ideally be away from the grasp
00050 float32 desired_approach_distance
00051 
00052 # how much distance between pre-grasp and grasp must actually be feasible 
00053 # for the grasp not to be rejected
00054 float32 min_approach_distance
00055 
00056 # an optional list of obstacles that we have semantic information about
00057 # and that we expect might move in the course of executing this grasp
00058 # the grasp planner is expected to make sure they move in an OK way; during
00059 # execution, grasp executors will not check for collisions against these objects
00060 GraspableObject[] moved_obstacles
00061 
00062 ================================================================================
00063 MSG: sensor_msgs/JointState
00064 # This is a message that holds data to describe the state of a set of torque controlled joints. 
00065 #
00066 # The state of each joint (revolute or prismatic) is defined by:
00067 #  * the position of the joint (rad or m),
00068 #  * the velocity of the joint (rad/s or m/s) and 
00069 #  * the effort that is applied in the joint (Nm or N).
00070 #
00071 # Each joint is uniquely identified by its name
00072 # The header specifies the time at which the joint states were recorded. All the joint states
00073 # in one message have to be recorded at the same time.
00074 #
00075 # This message consists of a multiple arrays, one for each part of the joint state. 
00076 # The goal is to make each of the fields optional. When e.g. your joints have no
00077 # effort associated with them, you can leave the effort array empty. 
00078 #
00079 # All arrays in this message should have the same size, or be empty.
00080 # This is the only way to uniquely associate the joint name with the correct
00081 # states.
00082 
00083 
00084 Header header
00085 
00086 string[] name
00087 float64[] position
00088 float64[] velocity
00089 float64[] effort
00090 
00091 ================================================================================
00092 MSG: std_msgs/Header
00093 # Standard metadata for higher-level stamped data types.
00094 # This is generally used to communicate timestamped data 
00095 # in a particular coordinate frame.
00096 # 
00097 # sequence ID: consecutively increasing ID 
00098 uint32 seq
00099 #Two-integer timestamp that is expressed as:
00100 # * stamp.secs: seconds (stamp_secs) since epoch
00101 # * stamp.nsecs: nanoseconds since stamp_secs
00102 # time-handling sugar is provided by the client library
00103 time stamp
00104 #Frame this data is associated with
00105 # 0: no frame
00106 # 1: global frame
00107 string frame_id
00108 
00109 ================================================================================
00110 MSG: geometry_msgs/Pose
00111 # A representation of pose in free space, composed of postion and orientation. 
00112 Point position
00113 Quaternion orientation
00114 
00115 ================================================================================
00116 MSG: geometry_msgs/Point
00117 # This contains the position of a point in free space
00118 float64 x
00119 float64 y
00120 float64 z
00121 
00122 ================================================================================
00123 MSG: geometry_msgs/Quaternion
00124 # This represents an orientation in free space in quaternion form.
00125 
00126 float64 x
00127 float64 y
00128 float64 z
00129 float64 w
00130 
00131 ================================================================================
00132 MSG: object_manipulation_msgs/GraspableObject
00133 # an object that the object_manipulator can work on
00134 
00135 # a graspable object can be represented in multiple ways. This message
00136 # can contain all of them. Which one is actually used is up to the receiver
00137 # of this message. When adding new representations, one must be careful that
00138 # they have reasonable lightweight defaults indicating that that particular
00139 # representation is not available.
00140 
00141 # the tf frame to be used as a reference frame when combining information from
00142 # the different representations below
00143 string reference_frame_id
00144 
00145 # potential recognition results from a database of models
00146 # all poses are relative to the object reference pose
00147 household_objects_database_msgs/DatabaseModelPose[] potential_models
00148 
00149 # the point cloud itself
00150 sensor_msgs/PointCloud cluster
00151 
00152 # a region of a PointCloud2 of interest
00153 object_manipulation_msgs/SceneRegion region
00154 
00155 # the name that this object has in the collision environment
00156 string collision_name
00157 ================================================================================
00158 MSG: household_objects_database_msgs/DatabaseModelPose
00159 # Informs that a specific model from the Model Database has been 
00160 # identified at a certain location
00161 
00162 # the database id of the model
00163 int32 model_id
00164 
00165 # the pose that it can be found in
00166 geometry_msgs/PoseStamped pose
00167 
00168 # a measure of the confidence level in this detection result
00169 float32 confidence
00170 
00171 # the name of the object detector that generated this detection result
00172 string detector_name
00173 
00174 ================================================================================
00175 MSG: geometry_msgs/PoseStamped
00176 # A Pose with reference coordinate frame and timestamp
00177 Header header
00178 Pose pose
00179 
00180 ================================================================================
00181 MSG: sensor_msgs/PointCloud
00182 # This message holds a collection of 3d points, plus optional additional
00183 # information about each point.
00184 
00185 # Time of sensor data acquisition, coordinate frame ID.
00186 Header header
00187 
00188 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00189 # in the frame given in the header.
00190 geometry_msgs/Point32[] points
00191 
00192 # Each channel should have the same number of elements as points array,
00193 # and the data in each channel should correspond 1:1 with each point.
00194 # Channel names in common practice are listed in ChannelFloat32.msg.
00195 ChannelFloat32[] channels
00196 
00197 ================================================================================
00198 MSG: geometry_msgs/Point32
00199 # This contains the position of a point in free space(with 32 bits of precision).
00200 # It is recommeded to use Point wherever possible instead of Point32.  
00201 # 
00202 # This recommendation is to promote interoperability.  
00203 #
00204 # This message is designed to take up less space when sending
00205 # lots of points at once, as in the case of a PointCloud.  
00206 
00207 float32 x
00208 float32 y
00209 float32 z
00210 ================================================================================
00211 MSG: sensor_msgs/ChannelFloat32
00212 # This message is used by the PointCloud message to hold optional data
00213 # associated with each point in the cloud. The length of the values
00214 # array should be the same as the length of the points array in the
00215 # PointCloud, and each value should be associated with the corresponding
00216 # point.
00217 
00218 # Channel names in existing practice include:
00219 #   "u", "v" - row and column (respectively) in the left stereo image.
00220 #              This is opposite to usual conventions but remains for
00221 #              historical reasons. The newer PointCloud2 message has no
00222 #              such problem.
00223 #   "rgb" - For point clouds produced by color stereo cameras. uint8
00224 #           (R,G,B) values packed into the least significant 24 bits,
00225 #           in order.
00226 #   "intensity" - laser or pixel intensity.
00227 #   "distance"
00228 
00229 # The channel name should give semantics of the channel (e.g.
00230 # "intensity" instead of "value").
00231 string name
00232 
00233 # The values array should be 1-1 with the elements of the associated
00234 # PointCloud.
00235 float32[] values
00236 
00237 ================================================================================
00238 MSG: object_manipulation_msgs/SceneRegion
00239 # Point cloud
00240 sensor_msgs/PointCloud2 cloud
00241 
00242 # Indices for the region of interest
00243 int32[] mask
00244 
00245 # One of the corresponding 2D images, if applicable
00246 sensor_msgs/Image image
00247 
00248 # The disparity image, if applicable
00249 sensor_msgs/Image disparity_image
00250 
00251 # Camera info for the camera that took the image
00252 sensor_msgs/CameraInfo cam_info
00253 
00254 # a 3D region of interest for grasp planning
00255 geometry_msgs/PoseStamped  roi_box_pose
00256 geometry_msgs/Vector3      roi_box_dims
00257 
00258 ================================================================================
00259 MSG: sensor_msgs/PointCloud2
00260 # This message holds a collection of N-dimensional points, which may
00261 # contain additional information such as normals, intensity, etc. The
00262 # point data is stored as a binary blob, its layout described by the
00263 # contents of the "fields" array.
00264 
00265 # The point cloud data may be organized 2d (image-like) or 1d
00266 # (unordered). Point clouds organized as 2d images may be produced by
00267 # camera depth sensors such as stereo or time-of-flight.
00268 
00269 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00270 # points).
00271 Header header
00272 
00273 # 2D structure of the point cloud. If the cloud is unordered, height is
00274 # 1 and width is the length of the point cloud.
00275 uint32 height
00276 uint32 width
00277 
00278 # Describes the channels and their layout in the binary data blob.
00279 PointField[] fields
00280 
00281 bool    is_bigendian # Is this data bigendian?
00282 uint32  point_step   # Length of a point in bytes
00283 uint32  row_step     # Length of a row in bytes
00284 uint8[] data         # Actual point data, size is (row_step*height)
00285 
00286 bool is_dense        # True if there are no invalid points
00287 
00288 ================================================================================
00289 MSG: sensor_msgs/PointField
00290 # This message holds the description of one point entry in the
00291 # PointCloud2 message format.
00292 uint8 INT8    = 1
00293 uint8 UINT8   = 2
00294 uint8 INT16   = 3
00295 uint8 UINT16  = 4
00296 uint8 INT32   = 5
00297 uint8 UINT32  = 6
00298 uint8 FLOAT32 = 7
00299 uint8 FLOAT64 = 8
00300 
00301 string name      # Name of field
00302 uint32 offset    # Offset from start of point struct
00303 uint8  datatype  # Datatype enumeration, see above
00304 uint32 count     # How many elements in the field
00305 
00306 ================================================================================
00307 MSG: sensor_msgs/Image
00308 # This message contains an uncompressed image
00309 # (0, 0) is at top-left corner of image
00310 #
00311 
00312 Header header        # Header timestamp should be acquisition time of image
00313                      # Header frame_id should be optical frame of camera
00314                      # origin of frame should be optical center of cameara
00315                      # +x should point to the right in the image
00316                      # +y should point down in the image
00317                      # +z should point into to plane of the image
00318                      # If the frame_id here and the frame_id of the CameraInfo
00319                      # message associated with the image conflict
00320                      # the behavior is undefined
00321 
00322 uint32 height         # image height, that is, number of rows
00323 uint32 width          # image width, that is, number of columns
00324 
00325 # The legal values for encoding are in file src/image_encodings.cpp
00326 # If you want to standardize a new string format, join
00327 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00328 
00329 string encoding       # Encoding of pixels -- channel meaning, ordering, size
00330                       # taken from the list of strings in src/image_encodings.cpp
00331 
00332 uint8 is_bigendian    # is this data bigendian?
00333 uint32 step           # Full row length in bytes
00334 uint8[] data          # actual matrix data, size is (step * rows)
00335 
00336 ================================================================================
00337 MSG: sensor_msgs/CameraInfo
00338 # This message defines meta information for a camera. It should be in a
00339 # camera namespace on topic "camera_info" and accompanied by up to five
00340 # image topics named:
00341 #
00342 #   image_raw - raw data from the camera driver, possibly Bayer encoded
00343 #   image            - monochrome, distorted
00344 #   image_color      - color, distorted
00345 #   image_rect       - monochrome, rectified
00346 #   image_rect_color - color, rectified
00347 #
00348 # The image_pipeline contains packages (image_proc, stereo_image_proc)
00349 # for producing the four processed image topics from image_raw and
00350 # camera_info. The meaning of the camera parameters are described in
00351 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
00352 #
00353 # The image_geometry package provides a user-friendly interface to
00354 # common operations using this meta information. If you want to, e.g.,
00355 # project a 3d point into image coordinates, we strongly recommend
00356 # using image_geometry.
00357 #
00358 # If the camera is uncalibrated, the matrices D, K, R, P should be left
00359 # zeroed out. In particular, clients may assume that K[0] == 0.0
00360 # indicates an uncalibrated camera.
00361 
00362 #######################################################################
00363 #                     Image acquisition info                          #
00364 #######################################################################
00365 
00366 # Time of image acquisition, camera coordinate frame ID
00367 Header header    # Header timestamp should be acquisition time of image
00368                  # Header frame_id should be optical frame of camera
00369                  # origin of frame should be optical center of camera
00370                  # +x should point to the right in the image
00371                  # +y should point down in the image
00372                  # +z should point into the plane of the image
00373 
00374 
00375 #######################################################################
00376 #                      Calibration Parameters                         #
00377 #######################################################################
00378 # These are fixed during camera calibration. Their values will be the #
00379 # same in all messages until the camera is recalibrated. Note that    #
00380 # self-calibrating systems may "recalibrate" frequently.              #
00381 #                                                                     #
00382 # The internal parameters can be used to warp a raw (distorted) image #
00383 # to:                                                                 #
00384 #   1. An undistorted image (requires D and K)                        #
00385 #   2. A rectified image (requires D, K, R)                           #
00386 # The projection matrix P projects 3D points into the rectified image.#
00387 #######################################################################
00388 
00389 # The image dimensions with which the camera was calibrated. Normally
00390 # this will be the full camera resolution in pixels.
00391 uint32 height
00392 uint32 width
00393 
00394 # The distortion model used. Supported models are listed in
00395 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
00396 # simple model of radial and tangential distortion - is sufficent.
00397 string distortion_model
00398 
00399 # The distortion parameters, size depending on the distortion model.
00400 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
00401 float64[] D
00402 
00403 # Intrinsic camera matrix for the raw (distorted) images.
00404 #     [fx  0 cx]
00405 # K = [ 0 fy cy]
00406 #     [ 0  0  1]
00407 # Projects 3D points in the camera coordinate frame to 2D pixel
00408 # coordinates using the focal lengths (fx, fy) and principal point
00409 # (cx, cy).
00410 float64[9]  K # 3x3 row-major matrix
00411 
00412 # Rectification matrix (stereo cameras only)
00413 # A rotation matrix aligning the camera coordinate system to the ideal
00414 # stereo image plane so that epipolar lines in both stereo images are
00415 # parallel.
00416 float64[9]  R # 3x3 row-major matrix
00417 
00418 # Projection/camera matrix
00419 #     [fx'  0  cx' Tx]
00420 # P = [ 0  fy' cy' Ty]
00421 #     [ 0   0   1   0]
00422 # By convention, this matrix specifies the intrinsic (camera) matrix
00423 #  of the processed (rectified) image. That is, the left 3x3 portion
00424 #  is the normal camera intrinsic matrix for the rectified image.
00425 # It projects 3D points in the camera coordinate frame to 2D pixel
00426 #  coordinates using the focal lengths (fx', fy') and principal point
00427 #  (cx', cy') - these may differ from the values in K.
00428 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
00429 #  also have R = the identity and P[1:3,1:3] = K.
00430 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
00431 #  position of the optical center of the second camera in the first
00432 #  camera's frame. We assume Tz = 0 so both cameras are in the same
00433 #  stereo image plane. The first camera always has Tx = Ty = 0. For
00434 #  the right (second) camera of a horizontal stereo pair, Ty = 0 and
00435 #  Tx = -fx' * B, where B is the baseline between the cameras.
00436 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
00437 #  the rectified image is given by:
00438 #  [u v w]' = P * [X Y Z 1]'
00439 #         x = u / w
00440 #         y = v / w
00441 #  This holds for both images of a stereo pair.
00442 float64[12] P # 3x4 row-major matrix
00443 
00444 
00445 #######################################################################
00446 #                      Operational Parameters                         #
00447 #######################################################################
00448 # These define the image region actually captured by the camera       #
00449 # driver. Although they affect the geometry of the output image, they #
00450 # may be changed freely without recalibrating the camera.             #
00451 #######################################################################
00452 
00453 # Binning refers here to any camera setting which combines rectangular
00454 #  neighborhoods of pixels into larger "super-pixels." It reduces the
00455 #  resolution of the output image to
00456 #  (width / binning_x) x (height / binning_y).
00457 # The default values binning_x = binning_y = 0 is considered the same
00458 #  as binning_x = binning_y = 1 (no subsampling).
00459 uint32 binning_x
00460 uint32 binning_y
00461 
00462 # Region of interest (subwindow of full camera resolution), given in
00463 #  full resolution (unbinned) image coordinates. A particular ROI
00464 #  always denotes the same window of pixels on the camera sensor,
00465 #  regardless of binning settings.
00466 # The default setting of roi (all values 0) is considered the same as
00467 #  full resolution (roi.width = width, roi.height = height).
00468 RegionOfInterest roi
00469 
00470 ================================================================================
00471 MSG: sensor_msgs/RegionOfInterest
00472 # This message is used to specify a region of interest within an image.
00473 #
00474 # When used to specify the ROI setting of the camera when the image was
00475 # taken, the height and width fields should either match the height and
00476 # width fields for the associated image; or height = width = 0
00477 # indicates that the full resolution image was captured.
00478 
00479 uint32 x_offset  # Leftmost pixel of the ROI
00480                  # (0 if the ROI includes the left edge of the image)
00481 uint32 y_offset  # Topmost pixel of the ROI
00482                  # (0 if the ROI includes the top edge of the image)
00483 uint32 height    # Height of ROI
00484 uint32 width     # Width of ROI
00485 
00486 # True if a distinct rectified ROI should be calculated from the "raw"
00487 # ROI in this message. Typically this should be False if the full image
00488 # is captured (ROI not used), and True if a subwindow is captured (ROI
00489 # used).
00490 bool do_rectify
00491 
00492 ================================================================================
00493 MSG: geometry_msgs/Vector3
00494 # This represents a vector in free space. 
00495 
00496 float64 x
00497 float64 y
00498 float64 z
00499 """
00500   __slots__ = ['grasp']
00501   _slot_types = ['object_manipulation_msgs/Grasp']
00502 
00503   def __init__(self, *args, **kwds):
00504     """
00505     Constructor. Any message fields that are implicitly/explicitly
00506     set to None will be assigned a default value. The recommend
00507     use is keyword arguments as this is more robust to future message
00508     changes.  You cannot mix in-order arguments and keyword arguments.
00509 
00510     The available fields are:
00511        grasp
00512 
00513     :param args: complete set of field values, in .msg order
00514     :param kwds: use keyword arguments corresponding to message field names
00515     to set specific fields.
00516     """
00517     if args or kwds:
00518       super(GraspStatusRequest, self).__init__(*args, **kwds)
00519       #message fields cannot be None, assign default values for those that are
00520       if self.grasp is None:
00521         self.grasp = object_manipulation_msgs.msg.Grasp()
00522     else:
00523       self.grasp = object_manipulation_msgs.msg.Grasp()
00524 
00525   def _get_types(self):
00526     """
00527     internal API method
00528     """
00529     return self._slot_types
00530 
00531   def serialize(self, buff):
00532     """
00533     serialize message into buffer
00534     :param buff: buffer, ``StringIO``
00535     """
00536     try:
00537       _x = self
00538       buff.write(_struct_3I.pack(_x.grasp.pre_grasp_posture.header.seq, _x.grasp.pre_grasp_posture.header.stamp.secs, _x.grasp.pre_grasp_posture.header.stamp.nsecs))
00539       _x = self.grasp.pre_grasp_posture.header.frame_id
00540       length = len(_x)
00541       if python3 or type(_x) == unicode:
00542         _x = _x.encode('utf-8')
00543         length = len(_x)
00544       buff.write(struct.pack('<I%ss'%length, length, _x))
00545       length = len(self.grasp.pre_grasp_posture.name)
00546       buff.write(_struct_I.pack(length))
00547       for val1 in self.grasp.pre_grasp_posture.name:
00548         length = len(val1)
00549         if python3 or type(val1) == unicode:
00550           val1 = val1.encode('utf-8')
00551           length = len(val1)
00552         buff.write(struct.pack('<I%ss'%length, length, val1))
00553       length = len(self.grasp.pre_grasp_posture.position)
00554       buff.write(_struct_I.pack(length))
00555       pattern = '<%sd'%length
00556       buff.write(struct.pack(pattern, *self.grasp.pre_grasp_posture.position))
00557       length = len(self.grasp.pre_grasp_posture.velocity)
00558       buff.write(_struct_I.pack(length))
00559       pattern = '<%sd'%length
00560       buff.write(struct.pack(pattern, *self.grasp.pre_grasp_posture.velocity))
00561       length = len(self.grasp.pre_grasp_posture.effort)
00562       buff.write(_struct_I.pack(length))
00563       pattern = '<%sd'%length
00564       buff.write(struct.pack(pattern, *self.grasp.pre_grasp_posture.effort))
00565       _x = self
00566       buff.write(_struct_3I.pack(_x.grasp.grasp_posture.header.seq, _x.grasp.grasp_posture.header.stamp.secs, _x.grasp.grasp_posture.header.stamp.nsecs))
00567       _x = self.grasp.grasp_posture.header.frame_id
00568       length = len(_x)
00569       if python3 or type(_x) == unicode:
00570         _x = _x.encode('utf-8')
00571         length = len(_x)
00572       buff.write(struct.pack('<I%ss'%length, length, _x))
00573       length = len(self.grasp.grasp_posture.name)
00574       buff.write(_struct_I.pack(length))
00575       for val1 in self.grasp.grasp_posture.name:
00576         length = len(val1)
00577         if python3 or type(val1) == unicode:
00578           val1 = val1.encode('utf-8')
00579           length = len(val1)
00580         buff.write(struct.pack('<I%ss'%length, length, val1))
00581       length = len(self.grasp.grasp_posture.position)
00582       buff.write(_struct_I.pack(length))
00583       pattern = '<%sd'%length
00584       buff.write(struct.pack(pattern, *self.grasp.grasp_posture.position))
00585       length = len(self.grasp.grasp_posture.velocity)
00586       buff.write(_struct_I.pack(length))
00587       pattern = '<%sd'%length
00588       buff.write(struct.pack(pattern, *self.grasp.grasp_posture.velocity))
00589       length = len(self.grasp.grasp_posture.effort)
00590       buff.write(_struct_I.pack(length))
00591       pattern = '<%sd'%length
00592       buff.write(struct.pack(pattern, *self.grasp.grasp_posture.effort))
00593       _x = self
00594       buff.write(_struct_8dB2f.pack(_x.grasp.grasp_pose.position.x, _x.grasp.grasp_pose.position.y, _x.grasp.grasp_pose.position.z, _x.grasp.grasp_pose.orientation.x, _x.grasp.grasp_pose.orientation.y, _x.grasp.grasp_pose.orientation.z, _x.grasp.grasp_pose.orientation.w, _x.grasp.success_probability, _x.grasp.cluster_rep, _x.grasp.desired_approach_distance, _x.grasp.min_approach_distance))
00595       length = len(self.grasp.moved_obstacles)
00596       buff.write(_struct_I.pack(length))
00597       for val1 in self.grasp.moved_obstacles:
00598         _x = val1.reference_frame_id
00599         length = len(_x)
00600         if python3 or type(_x) == unicode:
00601           _x = _x.encode('utf-8')
00602           length = len(_x)
00603         buff.write(struct.pack('<I%ss'%length, length, _x))
00604         length = len(val1.potential_models)
00605         buff.write(_struct_I.pack(length))
00606         for val2 in val1.potential_models:
00607           buff.write(_struct_i.pack(val2.model_id))
00608           _v1 = val2.pose
00609           _v2 = _v1.header
00610           buff.write(_struct_I.pack(_v2.seq))
00611           _v3 = _v2.stamp
00612           _x = _v3
00613           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00614           _x = _v2.frame_id
00615           length = len(_x)
00616           if python3 or type(_x) == unicode:
00617             _x = _x.encode('utf-8')
00618             length = len(_x)
00619           buff.write(struct.pack('<I%ss'%length, length, _x))
00620           _v4 = _v1.pose
00621           _v5 = _v4.position
00622           _x = _v5
00623           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00624           _v6 = _v4.orientation
00625           _x = _v6
00626           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00627           buff.write(_struct_f.pack(val2.confidence))
00628           _x = val2.detector_name
00629           length = len(_x)
00630           if python3 or type(_x) == unicode:
00631             _x = _x.encode('utf-8')
00632             length = len(_x)
00633           buff.write(struct.pack('<I%ss'%length, length, _x))
00634         _v7 = val1.cluster
00635         _v8 = _v7.header
00636         buff.write(_struct_I.pack(_v8.seq))
00637         _v9 = _v8.stamp
00638         _x = _v9
00639         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00640         _x = _v8.frame_id
00641         length = len(_x)
00642         if python3 or type(_x) == unicode:
00643           _x = _x.encode('utf-8')
00644           length = len(_x)
00645         buff.write(struct.pack('<I%ss'%length, length, _x))
00646         length = len(_v7.points)
00647         buff.write(_struct_I.pack(length))
00648         for val3 in _v7.points:
00649           _x = val3
00650           buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00651         length = len(_v7.channels)
00652         buff.write(_struct_I.pack(length))
00653         for val3 in _v7.channels:
00654           _x = val3.name
00655           length = len(_x)
00656           if python3 or type(_x) == unicode:
00657             _x = _x.encode('utf-8')
00658             length = len(_x)
00659           buff.write(struct.pack('<I%ss'%length, length, _x))
00660           length = len(val3.values)
00661           buff.write(_struct_I.pack(length))
00662           pattern = '<%sf'%length
00663           buff.write(struct.pack(pattern, *val3.values))
00664         _v10 = val1.region
00665         _v11 = _v10.cloud
00666         _v12 = _v11.header
00667         buff.write(_struct_I.pack(_v12.seq))
00668         _v13 = _v12.stamp
00669         _x = _v13
00670         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00671         _x = _v12.frame_id
00672         length = len(_x)
00673         if python3 or type(_x) == unicode:
00674           _x = _x.encode('utf-8')
00675           length = len(_x)
00676         buff.write(struct.pack('<I%ss'%length, length, _x))
00677         _x = _v11
00678         buff.write(_struct_2I.pack(_x.height, _x.width))
00679         length = len(_v11.fields)
00680         buff.write(_struct_I.pack(length))
00681         for val4 in _v11.fields:
00682           _x = val4.name
00683           length = len(_x)
00684           if python3 or type(_x) == unicode:
00685             _x = _x.encode('utf-8')
00686             length = len(_x)
00687           buff.write(struct.pack('<I%ss'%length, length, _x))
00688           _x = val4
00689           buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00690         _x = _v11
00691         buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
00692         _x = _v11.data
00693         length = len(_x)
00694         # - if encoded as a list instead, serialize as bytes instead of string
00695         if type(_x) in [list, tuple]:
00696           buff.write(struct.pack('<I%sB'%length, length, *_x))
00697         else:
00698           buff.write(struct.pack('<I%ss'%length, length, _x))
00699         buff.write(_struct_B.pack(_v11.is_dense))
00700         length = len(_v10.mask)
00701         buff.write(_struct_I.pack(length))
00702         pattern = '<%si'%length
00703         buff.write(struct.pack(pattern, *_v10.mask))
00704         _v14 = _v10.image
00705         _v15 = _v14.header
00706         buff.write(_struct_I.pack(_v15.seq))
00707         _v16 = _v15.stamp
00708         _x = _v16
00709         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00710         _x = _v15.frame_id
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 = _v14
00717         buff.write(_struct_2I.pack(_x.height, _x.width))
00718         _x = _v14.encoding
00719         length = len(_x)
00720         if python3 or type(_x) == unicode:
00721           _x = _x.encode('utf-8')
00722           length = len(_x)
00723         buff.write(struct.pack('<I%ss'%length, length, _x))
00724         _x = _v14
00725         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
00726         _x = _v14.data
00727         length = len(_x)
00728         # - if encoded as a list instead, serialize as bytes instead of string
00729         if type(_x) in [list, tuple]:
00730           buff.write(struct.pack('<I%sB'%length, length, *_x))
00731         else:
00732           buff.write(struct.pack('<I%ss'%length, length, _x))
00733         _v17 = _v10.disparity_image
00734         _v18 = _v17.header
00735         buff.write(_struct_I.pack(_v18.seq))
00736         _v19 = _v18.stamp
00737         _x = _v19
00738         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00739         _x = _v18.frame_id
00740         length = len(_x)
00741         if python3 or type(_x) == unicode:
00742           _x = _x.encode('utf-8')
00743           length = len(_x)
00744         buff.write(struct.pack('<I%ss'%length, length, _x))
00745         _x = _v17
00746         buff.write(_struct_2I.pack(_x.height, _x.width))
00747         _x = _v17.encoding
00748         length = len(_x)
00749         if python3 or type(_x) == unicode:
00750           _x = _x.encode('utf-8')
00751           length = len(_x)
00752         buff.write(struct.pack('<I%ss'%length, length, _x))
00753         _x = _v17
00754         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
00755         _x = _v17.data
00756         length = len(_x)
00757         # - if encoded as a list instead, serialize as bytes instead of string
00758         if type(_x) in [list, tuple]:
00759           buff.write(struct.pack('<I%sB'%length, length, *_x))
00760         else:
00761           buff.write(struct.pack('<I%ss'%length, length, _x))
00762         _v20 = _v10.cam_info
00763         _v21 = _v20.header
00764         buff.write(_struct_I.pack(_v21.seq))
00765         _v22 = _v21.stamp
00766         _x = _v22
00767         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00768         _x = _v21.frame_id
00769         length = len(_x)
00770         if python3 or type(_x) == unicode:
00771           _x = _x.encode('utf-8')
00772           length = len(_x)
00773         buff.write(struct.pack('<I%ss'%length, length, _x))
00774         _x = _v20
00775         buff.write(_struct_2I.pack(_x.height, _x.width))
00776         _x = _v20.distortion_model
00777         length = len(_x)
00778         if python3 or type(_x) == unicode:
00779           _x = _x.encode('utf-8')
00780           length = len(_x)
00781         buff.write(struct.pack('<I%ss'%length, length, _x))
00782         length = len(_v20.D)
00783         buff.write(_struct_I.pack(length))
00784         pattern = '<%sd'%length
00785         buff.write(struct.pack(pattern, *_v20.D))
00786         buff.write(_struct_9d.pack(*_v20.K))
00787         buff.write(_struct_9d.pack(*_v20.R))
00788         buff.write(_struct_12d.pack(*_v20.P))
00789         _x = _v20
00790         buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
00791         _v23 = _v20.roi
00792         _x = _v23
00793         buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
00794         _v24 = _v10.roi_box_pose
00795         _v25 = _v24.header
00796         buff.write(_struct_I.pack(_v25.seq))
00797         _v26 = _v25.stamp
00798         _x = _v26
00799         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00800         _x = _v25.frame_id
00801         length = len(_x)
00802         if python3 or type(_x) == unicode:
00803           _x = _x.encode('utf-8')
00804           length = len(_x)
00805         buff.write(struct.pack('<I%ss'%length, length, _x))
00806         _v27 = _v24.pose
00807         _v28 = _v27.position
00808         _x = _v28
00809         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00810         _v29 = _v27.orientation
00811         _x = _v29
00812         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00813         _v30 = _v10.roi_box_dims
00814         _x = _v30
00815         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00816         _x = val1.collision_name
00817         length = len(_x)
00818         if python3 or type(_x) == unicode:
00819           _x = _x.encode('utf-8')
00820           length = len(_x)
00821         buff.write(struct.pack('<I%ss'%length, length, _x))
00822     except struct.error as se: self._check_types(se)
00823     except TypeError as te: self._check_types(te)
00824 
00825   def deserialize(self, str):
00826     """
00827     unpack serialized message in str into this message instance
00828     :param str: byte array of serialized message, ``str``
00829     """
00830     try:
00831       if self.grasp is None:
00832         self.grasp = object_manipulation_msgs.msg.Grasp()
00833       end = 0
00834       _x = self
00835       start = end
00836       end += 12
00837       (_x.grasp.pre_grasp_posture.header.seq, _x.grasp.pre_grasp_posture.header.stamp.secs, _x.grasp.pre_grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00838       start = end
00839       end += 4
00840       (length,) = _struct_I.unpack(str[start:end])
00841       start = end
00842       end += length
00843       if python3:
00844         self.grasp.pre_grasp_posture.header.frame_id = str[start:end].decode('utf-8')
00845       else:
00846         self.grasp.pre_grasp_posture.header.frame_id = str[start:end]
00847       start = end
00848       end += 4
00849       (length,) = _struct_I.unpack(str[start:end])
00850       self.grasp.pre_grasp_posture.name = []
00851       for i in range(0, length):
00852         start = end
00853         end += 4
00854         (length,) = _struct_I.unpack(str[start:end])
00855         start = end
00856         end += length
00857         if python3:
00858           val1 = str[start:end].decode('utf-8')
00859         else:
00860           val1 = str[start:end]
00861         self.grasp.pre_grasp_posture.name.append(val1)
00862       start = end
00863       end += 4
00864       (length,) = _struct_I.unpack(str[start:end])
00865       pattern = '<%sd'%length
00866       start = end
00867       end += struct.calcsize(pattern)
00868       self.grasp.pre_grasp_posture.position = struct.unpack(pattern, str[start:end])
00869       start = end
00870       end += 4
00871       (length,) = _struct_I.unpack(str[start:end])
00872       pattern = '<%sd'%length
00873       start = end
00874       end += struct.calcsize(pattern)
00875       self.grasp.pre_grasp_posture.velocity = struct.unpack(pattern, str[start:end])
00876       start = end
00877       end += 4
00878       (length,) = _struct_I.unpack(str[start:end])
00879       pattern = '<%sd'%length
00880       start = end
00881       end += struct.calcsize(pattern)
00882       self.grasp.pre_grasp_posture.effort = struct.unpack(pattern, str[start:end])
00883       _x = self
00884       start = end
00885       end += 12
00886       (_x.grasp.grasp_posture.header.seq, _x.grasp.grasp_posture.header.stamp.secs, _x.grasp.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00887       start = end
00888       end += 4
00889       (length,) = _struct_I.unpack(str[start:end])
00890       start = end
00891       end += length
00892       if python3:
00893         self.grasp.grasp_posture.header.frame_id = str[start:end].decode('utf-8')
00894       else:
00895         self.grasp.grasp_posture.header.frame_id = str[start:end]
00896       start = end
00897       end += 4
00898       (length,) = _struct_I.unpack(str[start:end])
00899       self.grasp.grasp_posture.name = []
00900       for i in range(0, length):
00901         start = end
00902         end += 4
00903         (length,) = _struct_I.unpack(str[start:end])
00904         start = end
00905         end += length
00906         if python3:
00907           val1 = str[start:end].decode('utf-8')
00908         else:
00909           val1 = str[start:end]
00910         self.grasp.grasp_posture.name.append(val1)
00911       start = end
00912       end += 4
00913       (length,) = _struct_I.unpack(str[start:end])
00914       pattern = '<%sd'%length
00915       start = end
00916       end += struct.calcsize(pattern)
00917       self.grasp.grasp_posture.position = struct.unpack(pattern, str[start:end])
00918       start = end
00919       end += 4
00920       (length,) = _struct_I.unpack(str[start:end])
00921       pattern = '<%sd'%length
00922       start = end
00923       end += struct.calcsize(pattern)
00924       self.grasp.grasp_posture.velocity = struct.unpack(pattern, str[start:end])
00925       start = end
00926       end += 4
00927       (length,) = _struct_I.unpack(str[start:end])
00928       pattern = '<%sd'%length
00929       start = end
00930       end += struct.calcsize(pattern)
00931       self.grasp.grasp_posture.effort = struct.unpack(pattern, str[start:end])
00932       _x = self
00933       start = end
00934       end += 73
00935       (_x.grasp.grasp_pose.position.x, _x.grasp.grasp_pose.position.y, _x.grasp.grasp_pose.position.z, _x.grasp.grasp_pose.orientation.x, _x.grasp.grasp_pose.orientation.y, _x.grasp.grasp_pose.orientation.z, _x.grasp.grasp_pose.orientation.w, _x.grasp.success_probability, _x.grasp.cluster_rep, _x.grasp.desired_approach_distance, _x.grasp.min_approach_distance,) = _struct_8dB2f.unpack(str[start:end])
00936       self.grasp.cluster_rep = bool(self.grasp.cluster_rep)
00937       start = end
00938       end += 4
00939       (length,) = _struct_I.unpack(str[start:end])
00940       self.grasp.moved_obstacles = []
00941       for i in range(0, length):
00942         val1 = object_manipulation_msgs.msg.GraspableObject()
00943         start = end
00944         end += 4
00945         (length,) = _struct_I.unpack(str[start:end])
00946         start = end
00947         end += length
00948         if python3:
00949           val1.reference_frame_id = str[start:end].decode('utf-8')
00950         else:
00951           val1.reference_frame_id = str[start:end]
00952         start = end
00953         end += 4
00954         (length,) = _struct_I.unpack(str[start:end])
00955         val1.potential_models = []
00956         for i in range(0, length):
00957           val2 = household_objects_database_msgs.msg.DatabaseModelPose()
00958           start = end
00959           end += 4
00960           (val2.model_id,) = _struct_i.unpack(str[start:end])
00961           _v31 = val2.pose
00962           _v32 = _v31.header
00963           start = end
00964           end += 4
00965           (_v32.seq,) = _struct_I.unpack(str[start:end])
00966           _v33 = _v32.stamp
00967           _x = _v33
00968           start = end
00969           end += 8
00970           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00971           start = end
00972           end += 4
00973           (length,) = _struct_I.unpack(str[start:end])
00974           start = end
00975           end += length
00976           if python3:
00977             _v32.frame_id = str[start:end].decode('utf-8')
00978           else:
00979             _v32.frame_id = str[start:end]
00980           _v34 = _v31.pose
00981           _v35 = _v34.position
00982           _x = _v35
00983           start = end
00984           end += 24
00985           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00986           _v36 = _v34.orientation
00987           _x = _v36
00988           start = end
00989           end += 32
00990           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00991           start = end
00992           end += 4
00993           (val2.confidence,) = _struct_f.unpack(str[start:end])
00994           start = end
00995           end += 4
00996           (length,) = _struct_I.unpack(str[start:end])
00997           start = end
00998           end += length
00999           if python3:
01000             val2.detector_name = str[start:end].decode('utf-8')
01001           else:
01002             val2.detector_name = str[start:end]
01003           val1.potential_models.append(val2)
01004         _v37 = val1.cluster
01005         _v38 = _v37.header
01006         start = end
01007         end += 4
01008         (_v38.seq,) = _struct_I.unpack(str[start:end])
01009         _v39 = _v38.stamp
01010         _x = _v39
01011         start = end
01012         end += 8
01013         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01014         start = end
01015         end += 4
01016         (length,) = _struct_I.unpack(str[start:end])
01017         start = end
01018         end += length
01019         if python3:
01020           _v38.frame_id = str[start:end].decode('utf-8')
01021         else:
01022           _v38.frame_id = str[start:end]
01023         start = end
01024         end += 4
01025         (length,) = _struct_I.unpack(str[start:end])
01026         _v37.points = []
01027         for i in range(0, length):
01028           val3 = geometry_msgs.msg.Point32()
01029           _x = val3
01030           start = end
01031           end += 12
01032           (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01033           _v37.points.append(val3)
01034         start = end
01035         end += 4
01036         (length,) = _struct_I.unpack(str[start:end])
01037         _v37.channels = []
01038         for i in range(0, length):
01039           val3 = sensor_msgs.msg.ChannelFloat32()
01040           start = end
01041           end += 4
01042           (length,) = _struct_I.unpack(str[start:end])
01043           start = end
01044           end += length
01045           if python3:
01046             val3.name = str[start:end].decode('utf-8')
01047           else:
01048             val3.name = str[start:end]
01049           start = end
01050           end += 4
01051           (length,) = _struct_I.unpack(str[start:end])
01052           pattern = '<%sf'%length
01053           start = end
01054           end += struct.calcsize(pattern)
01055           val3.values = struct.unpack(pattern, str[start:end])
01056           _v37.channels.append(val3)
01057         _v40 = val1.region
01058         _v41 = _v40.cloud
01059         _v42 = _v41.header
01060         start = end
01061         end += 4
01062         (_v42.seq,) = _struct_I.unpack(str[start:end])
01063         _v43 = _v42.stamp
01064         _x = _v43
01065         start = end
01066         end += 8
01067         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01068         start = end
01069         end += 4
01070         (length,) = _struct_I.unpack(str[start:end])
01071         start = end
01072         end += length
01073         if python3:
01074           _v42.frame_id = str[start:end].decode('utf-8')
01075         else:
01076           _v42.frame_id = str[start:end]
01077         _x = _v41
01078         start = end
01079         end += 8
01080         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01081         start = end
01082         end += 4
01083         (length,) = _struct_I.unpack(str[start:end])
01084         _v41.fields = []
01085         for i in range(0, length):
01086           val4 = sensor_msgs.msg.PointField()
01087           start = end
01088           end += 4
01089           (length,) = _struct_I.unpack(str[start:end])
01090           start = end
01091           end += length
01092           if python3:
01093             val4.name = str[start:end].decode('utf-8')
01094           else:
01095             val4.name = str[start:end]
01096           _x = val4
01097           start = end
01098           end += 9
01099           (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01100           _v41.fields.append(val4)
01101         _x = _v41
01102         start = end
01103         end += 9
01104         (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
01105         _v41.is_bigendian = bool(_v41.is_bigendian)
01106         start = end
01107         end += 4
01108         (length,) = _struct_I.unpack(str[start:end])
01109         start = end
01110         end += length
01111         if python3:
01112           _v41.data = str[start:end].decode('utf-8')
01113         else:
01114           _v41.data = str[start:end]
01115         start = end
01116         end += 1
01117         (_v41.is_dense,) = _struct_B.unpack(str[start:end])
01118         _v41.is_dense = bool(_v41.is_dense)
01119         start = end
01120         end += 4
01121         (length,) = _struct_I.unpack(str[start:end])
01122         pattern = '<%si'%length
01123         start = end
01124         end += struct.calcsize(pattern)
01125         _v40.mask = struct.unpack(pattern, str[start:end])
01126         _v44 = _v40.image
01127         _v45 = _v44.header
01128         start = end
01129         end += 4
01130         (_v45.seq,) = _struct_I.unpack(str[start:end])
01131         _v46 = _v45.stamp
01132         _x = _v46
01133         start = end
01134         end += 8
01135         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01136         start = end
01137         end += 4
01138         (length,) = _struct_I.unpack(str[start:end])
01139         start = end
01140         end += length
01141         if python3:
01142           _v45.frame_id = str[start:end].decode('utf-8')
01143         else:
01144           _v45.frame_id = str[start:end]
01145         _x = _v44
01146         start = end
01147         end += 8
01148         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01149         start = end
01150         end += 4
01151         (length,) = _struct_I.unpack(str[start:end])
01152         start = end
01153         end += length
01154         if python3:
01155           _v44.encoding = str[start:end].decode('utf-8')
01156         else:
01157           _v44.encoding = str[start:end]
01158         _x = _v44
01159         start = end
01160         end += 5
01161         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
01162         start = end
01163         end += 4
01164         (length,) = _struct_I.unpack(str[start:end])
01165         start = end
01166         end += length
01167         if python3:
01168           _v44.data = str[start:end].decode('utf-8')
01169         else:
01170           _v44.data = str[start:end]
01171         _v47 = _v40.disparity_image
01172         _v48 = _v47.header
01173         start = end
01174         end += 4
01175         (_v48.seq,) = _struct_I.unpack(str[start:end])
01176         _v49 = _v48.stamp
01177         _x = _v49
01178         start = end
01179         end += 8
01180         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01181         start = end
01182         end += 4
01183         (length,) = _struct_I.unpack(str[start:end])
01184         start = end
01185         end += length
01186         if python3:
01187           _v48.frame_id = str[start:end].decode('utf-8')
01188         else:
01189           _v48.frame_id = str[start:end]
01190         _x = _v47
01191         start = end
01192         end += 8
01193         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01194         start = end
01195         end += 4
01196         (length,) = _struct_I.unpack(str[start:end])
01197         start = end
01198         end += length
01199         if python3:
01200           _v47.encoding = str[start:end].decode('utf-8')
01201         else:
01202           _v47.encoding = str[start:end]
01203         _x = _v47
01204         start = end
01205         end += 5
01206         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
01207         start = end
01208         end += 4
01209         (length,) = _struct_I.unpack(str[start:end])
01210         start = end
01211         end += length
01212         if python3:
01213           _v47.data = str[start:end].decode('utf-8')
01214         else:
01215           _v47.data = str[start:end]
01216         _v50 = _v40.cam_info
01217         _v51 = _v50.header
01218         start = end
01219         end += 4
01220         (_v51.seq,) = _struct_I.unpack(str[start:end])
01221         _v52 = _v51.stamp
01222         _x = _v52
01223         start = end
01224         end += 8
01225         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01226         start = end
01227         end += 4
01228         (length,) = _struct_I.unpack(str[start:end])
01229         start = end
01230         end += length
01231         if python3:
01232           _v51.frame_id = str[start:end].decode('utf-8')
01233         else:
01234           _v51.frame_id = str[start:end]
01235         _x = _v50
01236         start = end
01237         end += 8
01238         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01239         start = end
01240         end += 4
01241         (length,) = _struct_I.unpack(str[start:end])
01242         start = end
01243         end += length
01244         if python3:
01245           _v50.distortion_model = str[start:end].decode('utf-8')
01246         else:
01247           _v50.distortion_model = str[start:end]
01248         start = end
01249         end += 4
01250         (length,) = _struct_I.unpack(str[start:end])
01251         pattern = '<%sd'%length
01252         start = end
01253         end += struct.calcsize(pattern)
01254         _v50.D = struct.unpack(pattern, str[start:end])
01255         start = end
01256         end += 72
01257         _v50.K = _struct_9d.unpack(str[start:end])
01258         start = end
01259         end += 72
01260         _v50.R = _struct_9d.unpack(str[start:end])
01261         start = end
01262         end += 96
01263         _v50.P = _struct_12d.unpack(str[start:end])
01264         _x = _v50
01265         start = end
01266         end += 8
01267         (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
01268         _v53 = _v50.roi
01269         _x = _v53
01270         start = end
01271         end += 17
01272         (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
01273         _v53.do_rectify = bool(_v53.do_rectify)
01274         _v54 = _v40.roi_box_pose
01275         _v55 = _v54.header
01276         start = end
01277         end += 4
01278         (_v55.seq,) = _struct_I.unpack(str[start:end])
01279         _v56 = _v55.stamp
01280         _x = _v56
01281         start = end
01282         end += 8
01283         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01284         start = end
01285         end += 4
01286         (length,) = _struct_I.unpack(str[start:end])
01287         start = end
01288         end += length
01289         if python3:
01290           _v55.frame_id = str[start:end].decode('utf-8')
01291         else:
01292           _v55.frame_id = str[start:end]
01293         _v57 = _v54.pose
01294         _v58 = _v57.position
01295         _x = _v58
01296         start = end
01297         end += 24
01298         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01299         _v59 = _v57.orientation
01300         _x = _v59
01301         start = end
01302         end += 32
01303         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01304         _v60 = _v40.roi_box_dims
01305         _x = _v60
01306         start = end
01307         end += 24
01308         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01309         start = end
01310         end += 4
01311         (length,) = _struct_I.unpack(str[start:end])
01312         start = end
01313         end += length
01314         if python3:
01315           val1.collision_name = str[start:end].decode('utf-8')
01316         else:
01317           val1.collision_name = str[start:end]
01318         self.grasp.moved_obstacles.append(val1)
01319       return self
01320     except struct.error as e:
01321       raise genpy.DeserializationError(e) #most likely buffer underfill
01322 
01323 
01324   def serialize_numpy(self, buff, numpy):
01325     """
01326     serialize message with numpy array types into buffer
01327     :param buff: buffer, ``StringIO``
01328     :param numpy: numpy python module
01329     """
01330     try:
01331       _x = self
01332       buff.write(_struct_3I.pack(_x.grasp.pre_grasp_posture.header.seq, _x.grasp.pre_grasp_posture.header.stamp.secs, _x.grasp.pre_grasp_posture.header.stamp.nsecs))
01333       _x = self.grasp.pre_grasp_posture.header.frame_id
01334       length = len(_x)
01335       if python3 or type(_x) == unicode:
01336         _x = _x.encode('utf-8')
01337         length = len(_x)
01338       buff.write(struct.pack('<I%ss'%length, length, _x))
01339       length = len(self.grasp.pre_grasp_posture.name)
01340       buff.write(_struct_I.pack(length))
01341       for val1 in self.grasp.pre_grasp_posture.name:
01342         length = len(val1)
01343         if python3 or type(val1) == unicode:
01344           val1 = val1.encode('utf-8')
01345           length = len(val1)
01346         buff.write(struct.pack('<I%ss'%length, length, val1))
01347       length = len(self.grasp.pre_grasp_posture.position)
01348       buff.write(_struct_I.pack(length))
01349       pattern = '<%sd'%length
01350       buff.write(self.grasp.pre_grasp_posture.position.tostring())
01351       length = len(self.grasp.pre_grasp_posture.velocity)
01352       buff.write(_struct_I.pack(length))
01353       pattern = '<%sd'%length
01354       buff.write(self.grasp.pre_grasp_posture.velocity.tostring())
01355       length = len(self.grasp.pre_grasp_posture.effort)
01356       buff.write(_struct_I.pack(length))
01357       pattern = '<%sd'%length
01358       buff.write(self.grasp.pre_grasp_posture.effort.tostring())
01359       _x = self
01360       buff.write(_struct_3I.pack(_x.grasp.grasp_posture.header.seq, _x.grasp.grasp_posture.header.stamp.secs, _x.grasp.grasp_posture.header.stamp.nsecs))
01361       _x = self.grasp.grasp_posture.header.frame_id
01362       length = len(_x)
01363       if python3 or type(_x) == unicode:
01364         _x = _x.encode('utf-8')
01365         length = len(_x)
01366       buff.write(struct.pack('<I%ss'%length, length, _x))
01367       length = len(self.grasp.grasp_posture.name)
01368       buff.write(_struct_I.pack(length))
01369       for val1 in self.grasp.grasp_posture.name:
01370         length = len(val1)
01371         if python3 or type(val1) == unicode:
01372           val1 = val1.encode('utf-8')
01373           length = len(val1)
01374         buff.write(struct.pack('<I%ss'%length, length, val1))
01375       length = len(self.grasp.grasp_posture.position)
01376       buff.write(_struct_I.pack(length))
01377       pattern = '<%sd'%length
01378       buff.write(self.grasp.grasp_posture.position.tostring())
01379       length = len(self.grasp.grasp_posture.velocity)
01380       buff.write(_struct_I.pack(length))
01381       pattern = '<%sd'%length
01382       buff.write(self.grasp.grasp_posture.velocity.tostring())
01383       length = len(self.grasp.grasp_posture.effort)
01384       buff.write(_struct_I.pack(length))
01385       pattern = '<%sd'%length
01386       buff.write(self.grasp.grasp_posture.effort.tostring())
01387       _x = self
01388       buff.write(_struct_8dB2f.pack(_x.grasp.grasp_pose.position.x, _x.grasp.grasp_pose.position.y, _x.grasp.grasp_pose.position.z, _x.grasp.grasp_pose.orientation.x, _x.grasp.grasp_pose.orientation.y, _x.grasp.grasp_pose.orientation.z, _x.grasp.grasp_pose.orientation.w, _x.grasp.success_probability, _x.grasp.cluster_rep, _x.grasp.desired_approach_distance, _x.grasp.min_approach_distance))
01389       length = len(self.grasp.moved_obstacles)
01390       buff.write(_struct_I.pack(length))
01391       for val1 in self.grasp.moved_obstacles:
01392         _x = val1.reference_frame_id
01393         length = len(_x)
01394         if python3 or type(_x) == unicode:
01395           _x = _x.encode('utf-8')
01396           length = len(_x)
01397         buff.write(struct.pack('<I%ss'%length, length, _x))
01398         length = len(val1.potential_models)
01399         buff.write(_struct_I.pack(length))
01400         for val2 in val1.potential_models:
01401           buff.write(_struct_i.pack(val2.model_id))
01402           _v61 = val2.pose
01403           _v62 = _v61.header
01404           buff.write(_struct_I.pack(_v62.seq))
01405           _v63 = _v62.stamp
01406           _x = _v63
01407           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01408           _x = _v62.frame_id
01409           length = len(_x)
01410           if python3 or type(_x) == unicode:
01411             _x = _x.encode('utf-8')
01412             length = len(_x)
01413           buff.write(struct.pack('<I%ss'%length, length, _x))
01414           _v64 = _v61.pose
01415           _v65 = _v64.position
01416           _x = _v65
01417           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01418           _v66 = _v64.orientation
01419           _x = _v66
01420           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01421           buff.write(_struct_f.pack(val2.confidence))
01422           _x = val2.detector_name
01423           length = len(_x)
01424           if python3 or type(_x) == unicode:
01425             _x = _x.encode('utf-8')
01426             length = len(_x)
01427           buff.write(struct.pack('<I%ss'%length, length, _x))
01428         _v67 = val1.cluster
01429         _v68 = _v67.header
01430         buff.write(_struct_I.pack(_v68.seq))
01431         _v69 = _v68.stamp
01432         _x = _v69
01433         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01434         _x = _v68.frame_id
01435         length = len(_x)
01436         if python3 or type(_x) == unicode:
01437           _x = _x.encode('utf-8')
01438           length = len(_x)
01439         buff.write(struct.pack('<I%ss'%length, length, _x))
01440         length = len(_v67.points)
01441         buff.write(_struct_I.pack(length))
01442         for val3 in _v67.points:
01443           _x = val3
01444           buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
01445         length = len(_v67.channels)
01446         buff.write(_struct_I.pack(length))
01447         for val3 in _v67.channels:
01448           _x = val3.name
01449           length = len(_x)
01450           if python3 or type(_x) == unicode:
01451             _x = _x.encode('utf-8')
01452             length = len(_x)
01453           buff.write(struct.pack('<I%ss'%length, length, _x))
01454           length = len(val3.values)
01455           buff.write(_struct_I.pack(length))
01456           pattern = '<%sf'%length
01457           buff.write(val3.values.tostring())
01458         _v70 = val1.region
01459         _v71 = _v70.cloud
01460         _v72 = _v71.header
01461         buff.write(_struct_I.pack(_v72.seq))
01462         _v73 = _v72.stamp
01463         _x = _v73
01464         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01465         _x = _v72.frame_id
01466         length = len(_x)
01467         if python3 or type(_x) == unicode:
01468           _x = _x.encode('utf-8')
01469           length = len(_x)
01470         buff.write(struct.pack('<I%ss'%length, length, _x))
01471         _x = _v71
01472         buff.write(_struct_2I.pack(_x.height, _x.width))
01473         length = len(_v71.fields)
01474         buff.write(_struct_I.pack(length))
01475         for val4 in _v71.fields:
01476           _x = val4.name
01477           length = len(_x)
01478           if python3 or type(_x) == unicode:
01479             _x = _x.encode('utf-8')
01480             length = len(_x)
01481           buff.write(struct.pack('<I%ss'%length, length, _x))
01482           _x = val4
01483           buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
01484         _x = _v71
01485         buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
01486         _x = _v71.data
01487         length = len(_x)
01488         # - if encoded as a list instead, serialize as bytes instead of string
01489         if type(_x) in [list, tuple]:
01490           buff.write(struct.pack('<I%sB'%length, length, *_x))
01491         else:
01492           buff.write(struct.pack('<I%ss'%length, length, _x))
01493         buff.write(_struct_B.pack(_v71.is_dense))
01494         length = len(_v70.mask)
01495         buff.write(_struct_I.pack(length))
01496         pattern = '<%si'%length
01497         buff.write(_v70.mask.tostring())
01498         _v74 = _v70.image
01499         _v75 = _v74.header
01500         buff.write(_struct_I.pack(_v75.seq))
01501         _v76 = _v75.stamp
01502         _x = _v76
01503         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01504         _x = _v75.frame_id
01505         length = len(_x)
01506         if python3 or type(_x) == unicode:
01507           _x = _x.encode('utf-8')
01508           length = len(_x)
01509         buff.write(struct.pack('<I%ss'%length, length, _x))
01510         _x = _v74
01511         buff.write(_struct_2I.pack(_x.height, _x.width))
01512         _x = _v74.encoding
01513         length = len(_x)
01514         if python3 or type(_x) == unicode:
01515           _x = _x.encode('utf-8')
01516           length = len(_x)
01517         buff.write(struct.pack('<I%ss'%length, length, _x))
01518         _x = _v74
01519         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
01520         _x = _v74.data
01521         length = len(_x)
01522         # - if encoded as a list instead, serialize as bytes instead of string
01523         if type(_x) in [list, tuple]:
01524           buff.write(struct.pack('<I%sB'%length, length, *_x))
01525         else:
01526           buff.write(struct.pack('<I%ss'%length, length, _x))
01527         _v77 = _v70.disparity_image
01528         _v78 = _v77.header
01529         buff.write(_struct_I.pack(_v78.seq))
01530         _v79 = _v78.stamp
01531         _x = _v79
01532         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01533         _x = _v78.frame_id
01534         length = len(_x)
01535         if python3 or type(_x) == unicode:
01536           _x = _x.encode('utf-8')
01537           length = len(_x)
01538         buff.write(struct.pack('<I%ss'%length, length, _x))
01539         _x = _v77
01540         buff.write(_struct_2I.pack(_x.height, _x.width))
01541         _x = _v77.encoding
01542         length = len(_x)
01543         if python3 or type(_x) == unicode:
01544           _x = _x.encode('utf-8')
01545           length = len(_x)
01546         buff.write(struct.pack('<I%ss'%length, length, _x))
01547         _x = _v77
01548         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
01549         _x = _v77.data
01550         length = len(_x)
01551         # - if encoded as a list instead, serialize as bytes instead of string
01552         if type(_x) in [list, tuple]:
01553           buff.write(struct.pack('<I%sB'%length, length, *_x))
01554         else:
01555           buff.write(struct.pack('<I%ss'%length, length, _x))
01556         _v80 = _v70.cam_info
01557         _v81 = _v80.header
01558         buff.write(_struct_I.pack(_v81.seq))
01559         _v82 = _v81.stamp
01560         _x = _v82
01561         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01562         _x = _v81.frame_id
01563         length = len(_x)
01564         if python3 or type(_x) == unicode:
01565           _x = _x.encode('utf-8')
01566           length = len(_x)
01567         buff.write(struct.pack('<I%ss'%length, length, _x))
01568         _x = _v80
01569         buff.write(_struct_2I.pack(_x.height, _x.width))
01570         _x = _v80.distortion_model
01571         length = len(_x)
01572         if python3 or type(_x) == unicode:
01573           _x = _x.encode('utf-8')
01574           length = len(_x)
01575         buff.write(struct.pack('<I%ss'%length, length, _x))
01576         length = len(_v80.D)
01577         buff.write(_struct_I.pack(length))
01578         pattern = '<%sd'%length
01579         buff.write(_v80.D.tostring())
01580         buff.write(_v80.K.tostring())
01581         buff.write(_v80.R.tostring())
01582         buff.write(_v80.P.tostring())
01583         _x = _v80
01584         buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
01585         _v83 = _v80.roi
01586         _x = _v83
01587         buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
01588         _v84 = _v70.roi_box_pose
01589         _v85 = _v84.header
01590         buff.write(_struct_I.pack(_v85.seq))
01591         _v86 = _v85.stamp
01592         _x = _v86
01593         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01594         _x = _v85.frame_id
01595         length = len(_x)
01596         if python3 or type(_x) == unicode:
01597           _x = _x.encode('utf-8')
01598           length = len(_x)
01599         buff.write(struct.pack('<I%ss'%length, length, _x))
01600         _v87 = _v84.pose
01601         _v88 = _v87.position
01602         _x = _v88
01603         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01604         _v89 = _v87.orientation
01605         _x = _v89
01606         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01607         _v90 = _v70.roi_box_dims
01608         _x = _v90
01609         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01610         _x = val1.collision_name
01611         length = len(_x)
01612         if python3 or type(_x) == unicode:
01613           _x = _x.encode('utf-8')
01614           length = len(_x)
01615         buff.write(struct.pack('<I%ss'%length, length, _x))
01616     except struct.error as se: self._check_types(se)
01617     except TypeError as te: self._check_types(te)
01618 
01619   def deserialize_numpy(self, str, numpy):
01620     """
01621     unpack serialized message in str into this message instance using numpy for array types
01622     :param str: byte array of serialized message, ``str``
01623     :param numpy: numpy python module
01624     """
01625     try:
01626       if self.grasp is None:
01627         self.grasp = object_manipulation_msgs.msg.Grasp()
01628       end = 0
01629       _x = self
01630       start = end
01631       end += 12
01632       (_x.grasp.pre_grasp_posture.header.seq, _x.grasp.pre_grasp_posture.header.stamp.secs, _x.grasp.pre_grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01633       start = end
01634       end += 4
01635       (length,) = _struct_I.unpack(str[start:end])
01636       start = end
01637       end += length
01638       if python3:
01639         self.grasp.pre_grasp_posture.header.frame_id = str[start:end].decode('utf-8')
01640       else:
01641         self.grasp.pre_grasp_posture.header.frame_id = str[start:end]
01642       start = end
01643       end += 4
01644       (length,) = _struct_I.unpack(str[start:end])
01645       self.grasp.pre_grasp_posture.name = []
01646       for i in range(0, length):
01647         start = end
01648         end += 4
01649         (length,) = _struct_I.unpack(str[start:end])
01650         start = end
01651         end += length
01652         if python3:
01653           val1 = str[start:end].decode('utf-8')
01654         else:
01655           val1 = str[start:end]
01656         self.grasp.pre_grasp_posture.name.append(val1)
01657       start = end
01658       end += 4
01659       (length,) = _struct_I.unpack(str[start:end])
01660       pattern = '<%sd'%length
01661       start = end
01662       end += struct.calcsize(pattern)
01663       self.grasp.pre_grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01664       start = end
01665       end += 4
01666       (length,) = _struct_I.unpack(str[start:end])
01667       pattern = '<%sd'%length
01668       start = end
01669       end += struct.calcsize(pattern)
01670       self.grasp.pre_grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01671       start = end
01672       end += 4
01673       (length,) = _struct_I.unpack(str[start:end])
01674       pattern = '<%sd'%length
01675       start = end
01676       end += struct.calcsize(pattern)
01677       self.grasp.pre_grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01678       _x = self
01679       start = end
01680       end += 12
01681       (_x.grasp.grasp_posture.header.seq, _x.grasp.grasp_posture.header.stamp.secs, _x.grasp.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01682       start = end
01683       end += 4
01684       (length,) = _struct_I.unpack(str[start:end])
01685       start = end
01686       end += length
01687       if python3:
01688         self.grasp.grasp_posture.header.frame_id = str[start:end].decode('utf-8')
01689       else:
01690         self.grasp.grasp_posture.header.frame_id = str[start:end]
01691       start = end
01692       end += 4
01693       (length,) = _struct_I.unpack(str[start:end])
01694       self.grasp.grasp_posture.name = []
01695       for i in range(0, length):
01696         start = end
01697         end += 4
01698         (length,) = _struct_I.unpack(str[start:end])
01699         start = end
01700         end += length
01701         if python3:
01702           val1 = str[start:end].decode('utf-8')
01703         else:
01704           val1 = str[start:end]
01705         self.grasp.grasp_posture.name.append(val1)
01706       start = end
01707       end += 4
01708       (length,) = _struct_I.unpack(str[start:end])
01709       pattern = '<%sd'%length
01710       start = end
01711       end += struct.calcsize(pattern)
01712       self.grasp.grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01713       start = end
01714       end += 4
01715       (length,) = _struct_I.unpack(str[start:end])
01716       pattern = '<%sd'%length
01717       start = end
01718       end += struct.calcsize(pattern)
01719       self.grasp.grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01720       start = end
01721       end += 4
01722       (length,) = _struct_I.unpack(str[start:end])
01723       pattern = '<%sd'%length
01724       start = end
01725       end += struct.calcsize(pattern)
01726       self.grasp.grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01727       _x = self
01728       start = end
01729       end += 73
01730       (_x.grasp.grasp_pose.position.x, _x.grasp.grasp_pose.position.y, _x.grasp.grasp_pose.position.z, _x.grasp.grasp_pose.orientation.x, _x.grasp.grasp_pose.orientation.y, _x.grasp.grasp_pose.orientation.z, _x.grasp.grasp_pose.orientation.w, _x.grasp.success_probability, _x.grasp.cluster_rep, _x.grasp.desired_approach_distance, _x.grasp.min_approach_distance,) = _struct_8dB2f.unpack(str[start:end])
01731       self.grasp.cluster_rep = bool(self.grasp.cluster_rep)
01732       start = end
01733       end += 4
01734       (length,) = _struct_I.unpack(str[start:end])
01735       self.grasp.moved_obstacles = []
01736       for i in range(0, length):
01737         val1 = object_manipulation_msgs.msg.GraspableObject()
01738         start = end
01739         end += 4
01740         (length,) = _struct_I.unpack(str[start:end])
01741         start = end
01742         end += length
01743         if python3:
01744           val1.reference_frame_id = str[start:end].decode('utf-8')
01745         else:
01746           val1.reference_frame_id = str[start:end]
01747         start = end
01748         end += 4
01749         (length,) = _struct_I.unpack(str[start:end])
01750         val1.potential_models = []
01751         for i in range(0, length):
01752           val2 = household_objects_database_msgs.msg.DatabaseModelPose()
01753           start = end
01754           end += 4
01755           (val2.model_id,) = _struct_i.unpack(str[start:end])
01756           _v91 = val2.pose
01757           _v92 = _v91.header
01758           start = end
01759           end += 4
01760           (_v92.seq,) = _struct_I.unpack(str[start:end])
01761           _v93 = _v92.stamp
01762           _x = _v93
01763           start = end
01764           end += 8
01765           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01766           start = end
01767           end += 4
01768           (length,) = _struct_I.unpack(str[start:end])
01769           start = end
01770           end += length
01771           if python3:
01772             _v92.frame_id = str[start:end].decode('utf-8')
01773           else:
01774             _v92.frame_id = str[start:end]
01775           _v94 = _v91.pose
01776           _v95 = _v94.position
01777           _x = _v95
01778           start = end
01779           end += 24
01780           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01781           _v96 = _v94.orientation
01782           _x = _v96
01783           start = end
01784           end += 32
01785           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01786           start = end
01787           end += 4
01788           (val2.confidence,) = _struct_f.unpack(str[start:end])
01789           start = end
01790           end += 4
01791           (length,) = _struct_I.unpack(str[start:end])
01792           start = end
01793           end += length
01794           if python3:
01795             val2.detector_name = str[start:end].decode('utf-8')
01796           else:
01797             val2.detector_name = str[start:end]
01798           val1.potential_models.append(val2)
01799         _v97 = val1.cluster
01800         _v98 = _v97.header
01801         start = end
01802         end += 4
01803         (_v98.seq,) = _struct_I.unpack(str[start:end])
01804         _v99 = _v98.stamp
01805         _x = _v99
01806         start = end
01807         end += 8
01808         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01809         start = end
01810         end += 4
01811         (length,) = _struct_I.unpack(str[start:end])
01812         start = end
01813         end += length
01814         if python3:
01815           _v98.frame_id = str[start:end].decode('utf-8')
01816         else:
01817           _v98.frame_id = str[start:end]
01818         start = end
01819         end += 4
01820         (length,) = _struct_I.unpack(str[start:end])
01821         _v97.points = []
01822         for i in range(0, length):
01823           val3 = geometry_msgs.msg.Point32()
01824           _x = val3
01825           start = end
01826           end += 12
01827           (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01828           _v97.points.append(val3)
01829         start = end
01830         end += 4
01831         (length,) = _struct_I.unpack(str[start:end])
01832         _v97.channels = []
01833         for i in range(0, length):
01834           val3 = sensor_msgs.msg.ChannelFloat32()
01835           start = end
01836           end += 4
01837           (length,) = _struct_I.unpack(str[start:end])
01838           start = end
01839           end += length
01840           if python3:
01841             val3.name = str[start:end].decode('utf-8')
01842           else:
01843             val3.name = str[start:end]
01844           start = end
01845           end += 4
01846           (length,) = _struct_I.unpack(str[start:end])
01847           pattern = '<%sf'%length
01848           start = end
01849           end += struct.calcsize(pattern)
01850           val3.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
01851           _v97.channels.append(val3)
01852         _v100 = val1.region
01853         _v101 = _v100.cloud
01854         _v102 = _v101.header
01855         start = end
01856         end += 4
01857         (_v102.seq,) = _struct_I.unpack(str[start:end])
01858         _v103 = _v102.stamp
01859         _x = _v103
01860         start = end
01861         end += 8
01862         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01863         start = end
01864         end += 4
01865         (length,) = _struct_I.unpack(str[start:end])
01866         start = end
01867         end += length
01868         if python3:
01869           _v102.frame_id = str[start:end].decode('utf-8')
01870         else:
01871           _v102.frame_id = str[start:end]
01872         _x = _v101
01873         start = end
01874         end += 8
01875         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01876         start = end
01877         end += 4
01878         (length,) = _struct_I.unpack(str[start:end])
01879         _v101.fields = []
01880         for i in range(0, length):
01881           val4 = sensor_msgs.msg.PointField()
01882           start = end
01883           end += 4
01884           (length,) = _struct_I.unpack(str[start:end])
01885           start = end
01886           end += length
01887           if python3:
01888             val4.name = str[start:end].decode('utf-8')
01889           else:
01890             val4.name = str[start:end]
01891           _x = val4
01892           start = end
01893           end += 9
01894           (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01895           _v101.fields.append(val4)
01896         _x = _v101
01897         start = end
01898         end += 9
01899         (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
01900         _v101.is_bigendian = bool(_v101.is_bigendian)
01901         start = end
01902         end += 4
01903         (length,) = _struct_I.unpack(str[start:end])
01904         start = end
01905         end += length
01906         if python3:
01907           _v101.data = str[start:end].decode('utf-8')
01908         else:
01909           _v101.data = str[start:end]
01910         start = end
01911         end += 1
01912         (_v101.is_dense,) = _struct_B.unpack(str[start:end])
01913         _v101.is_dense = bool(_v101.is_dense)
01914         start = end
01915         end += 4
01916         (length,) = _struct_I.unpack(str[start:end])
01917         pattern = '<%si'%length
01918         start = end
01919         end += struct.calcsize(pattern)
01920         _v100.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
01921         _v104 = _v100.image
01922         _v105 = _v104.header
01923         start = end
01924         end += 4
01925         (_v105.seq,) = _struct_I.unpack(str[start:end])
01926         _v106 = _v105.stamp
01927         _x = _v106
01928         start = end
01929         end += 8
01930         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01931         start = end
01932         end += 4
01933         (length,) = _struct_I.unpack(str[start:end])
01934         start = end
01935         end += length
01936         if python3:
01937           _v105.frame_id = str[start:end].decode('utf-8')
01938         else:
01939           _v105.frame_id = str[start:end]
01940         _x = _v104
01941         start = end
01942         end += 8
01943         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01944         start = end
01945         end += 4
01946         (length,) = _struct_I.unpack(str[start:end])
01947         start = end
01948         end += length
01949         if python3:
01950           _v104.encoding = str[start:end].decode('utf-8')
01951         else:
01952           _v104.encoding = str[start:end]
01953         _x = _v104
01954         start = end
01955         end += 5
01956         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
01957         start = end
01958         end += 4
01959         (length,) = _struct_I.unpack(str[start:end])
01960         start = end
01961         end += length
01962         if python3:
01963           _v104.data = str[start:end].decode('utf-8')
01964         else:
01965           _v104.data = str[start:end]
01966         _v107 = _v100.disparity_image
01967         _v108 = _v107.header
01968         start = end
01969         end += 4
01970         (_v108.seq,) = _struct_I.unpack(str[start:end])
01971         _v109 = _v108.stamp
01972         _x = _v109
01973         start = end
01974         end += 8
01975         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01976         start = end
01977         end += 4
01978         (length,) = _struct_I.unpack(str[start:end])
01979         start = end
01980         end += length
01981         if python3:
01982           _v108.frame_id = str[start:end].decode('utf-8')
01983         else:
01984           _v108.frame_id = str[start:end]
01985         _x = _v107
01986         start = end
01987         end += 8
01988         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01989         start = end
01990         end += 4
01991         (length,) = _struct_I.unpack(str[start:end])
01992         start = end
01993         end += length
01994         if python3:
01995           _v107.encoding = str[start:end].decode('utf-8')
01996         else:
01997           _v107.encoding = str[start:end]
01998         _x = _v107
01999         start = end
02000         end += 5
02001         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
02002         start = end
02003         end += 4
02004         (length,) = _struct_I.unpack(str[start:end])
02005         start = end
02006         end += length
02007         if python3:
02008           _v107.data = str[start:end].decode('utf-8')
02009         else:
02010           _v107.data = str[start:end]
02011         _v110 = _v100.cam_info
02012         _v111 = _v110.header
02013         start = end
02014         end += 4
02015         (_v111.seq,) = _struct_I.unpack(str[start:end])
02016         _v112 = _v111.stamp
02017         _x = _v112
02018         start = end
02019         end += 8
02020         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02021         start = end
02022         end += 4
02023         (length,) = _struct_I.unpack(str[start:end])
02024         start = end
02025         end += length
02026         if python3:
02027           _v111.frame_id = str[start:end].decode('utf-8')
02028         else:
02029           _v111.frame_id = str[start:end]
02030         _x = _v110
02031         start = end
02032         end += 8
02033         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02034         start = end
02035         end += 4
02036         (length,) = _struct_I.unpack(str[start:end])
02037         start = end
02038         end += length
02039         if python3:
02040           _v110.distortion_model = str[start:end].decode('utf-8')
02041         else:
02042           _v110.distortion_model = str[start:end]
02043         start = end
02044         end += 4
02045         (length,) = _struct_I.unpack(str[start:end])
02046         pattern = '<%sd'%length
02047         start = end
02048         end += struct.calcsize(pattern)
02049         _v110.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02050         start = end
02051         end += 72
02052         _v110.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
02053         start = end
02054         end += 72
02055         _v110.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
02056         start = end
02057         end += 96
02058         _v110.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
02059         _x = _v110
02060         start = end
02061         end += 8
02062         (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
02063         _v113 = _v110.roi
02064         _x = _v113
02065         start = end
02066         end += 17
02067         (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
02068         _v113.do_rectify = bool(_v113.do_rectify)
02069         _v114 = _v100.roi_box_pose
02070         _v115 = _v114.header
02071         start = end
02072         end += 4
02073         (_v115.seq,) = _struct_I.unpack(str[start:end])
02074         _v116 = _v115.stamp
02075         _x = _v116
02076         start = end
02077         end += 8
02078         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02079         start = end
02080         end += 4
02081         (length,) = _struct_I.unpack(str[start:end])
02082         start = end
02083         end += length
02084         if python3:
02085           _v115.frame_id = str[start:end].decode('utf-8')
02086         else:
02087           _v115.frame_id = str[start:end]
02088         _v117 = _v114.pose
02089         _v118 = _v117.position
02090         _x = _v118
02091         start = end
02092         end += 24
02093         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02094         _v119 = _v117.orientation
02095         _x = _v119
02096         start = end
02097         end += 32
02098         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02099         _v120 = _v100.roi_box_dims
02100         _x = _v120
02101         start = end
02102         end += 24
02103         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02104         start = end
02105         end += 4
02106         (length,) = _struct_I.unpack(str[start:end])
02107         start = end
02108         end += length
02109         if python3:
02110           val1.collision_name = str[start:end].decode('utf-8')
02111         else:
02112           val1.collision_name = str[start:end]
02113         self.grasp.moved_obstacles.append(val1)
02114       return self
02115     except struct.error as e:
02116       raise genpy.DeserializationError(e) #most likely buffer underfill
02117 
02118 _struct_I = genpy.struct_I
02119 _struct_IBI = struct.Struct("<IBI")
02120 _struct_8dB2f = struct.Struct("<8dB2f")
02121 _struct_12d = struct.Struct("<12d")
02122 _struct_f = struct.Struct("<f")
02123 _struct_i = struct.Struct("<i")
02124 _struct_BI = struct.Struct("<BI")
02125 _struct_3f = struct.Struct("<3f")
02126 _struct_3I = struct.Struct("<3I")
02127 _struct_B = struct.Struct("<B")
02128 _struct_9d = struct.Struct("<9d")
02129 _struct_B2I = struct.Struct("<B2I")
02130 _struct_4d = struct.Struct("<4d")
02131 _struct_2I = struct.Struct("<2I")
02132 _struct_4IB = struct.Struct("<4IB")
02133 _struct_3d = struct.Struct("<3d")
02134 """autogenerated by genpy from object_manipulation_msgs/GraspStatusResponse.msg. Do not edit."""
02135 import sys
02136 python3 = True if sys.hexversion > 0x03000000 else False
02137 import genpy
02138 import struct
02139 
02140 
02141 class GraspStatusResponse(genpy.Message):
02142   _md5sum = "d58cf7836f039d8e002583af45001d6d"
02143   _type = "object_manipulation_msgs/GraspStatusResponse"
02144   _has_header = False #flag to mark the presence of a Header object
02145   _full_text = """
02146 bool is_hand_occupied
02147 
02148 
02149 """
02150   __slots__ = ['is_hand_occupied']
02151   _slot_types = ['bool']
02152 
02153   def __init__(self, *args, **kwds):
02154     """
02155     Constructor. Any message fields that are implicitly/explicitly
02156     set to None will be assigned a default value. The recommend
02157     use is keyword arguments as this is more robust to future message
02158     changes.  You cannot mix in-order arguments and keyword arguments.
02159 
02160     The available fields are:
02161        is_hand_occupied
02162 
02163     :param args: complete set of field values, in .msg order
02164     :param kwds: use keyword arguments corresponding to message field names
02165     to set specific fields.
02166     """
02167     if args or kwds:
02168       super(GraspStatusResponse, self).__init__(*args, **kwds)
02169       #message fields cannot be None, assign default values for those that are
02170       if self.is_hand_occupied is None:
02171         self.is_hand_occupied = False
02172     else:
02173       self.is_hand_occupied = False
02174 
02175   def _get_types(self):
02176     """
02177     internal API method
02178     """
02179     return self._slot_types
02180 
02181   def serialize(self, buff):
02182     """
02183     serialize message into buffer
02184     :param buff: buffer, ``StringIO``
02185     """
02186     try:
02187       buff.write(_struct_B.pack(self.is_hand_occupied))
02188     except struct.error as se: self._check_types(se)
02189     except TypeError as te: self._check_types(te)
02190 
02191   def deserialize(self, str):
02192     """
02193     unpack serialized message in str into this message instance
02194     :param str: byte array of serialized message, ``str``
02195     """
02196     try:
02197       end = 0
02198       start = end
02199       end += 1
02200       (self.is_hand_occupied,) = _struct_B.unpack(str[start:end])
02201       self.is_hand_occupied = bool(self.is_hand_occupied)
02202       return self
02203     except struct.error as e:
02204       raise genpy.DeserializationError(e) #most likely buffer underfill
02205 
02206 
02207   def serialize_numpy(self, buff, numpy):
02208     """
02209     serialize message with numpy array types into buffer
02210     :param buff: buffer, ``StringIO``
02211     :param numpy: numpy python module
02212     """
02213     try:
02214       buff.write(_struct_B.pack(self.is_hand_occupied))
02215     except struct.error as se: self._check_types(se)
02216     except TypeError as te: self._check_types(te)
02217 
02218   def deserialize_numpy(self, str, numpy):
02219     """
02220     unpack serialized message in str into this message instance using numpy for array types
02221     :param str: byte array of serialized message, ``str``
02222     :param numpy: numpy python module
02223     """
02224     try:
02225       end = 0
02226       start = end
02227       end += 1
02228       (self.is_hand_occupied,) = _struct_B.unpack(str[start:end])
02229       self.is_hand_occupied = bool(self.is_hand_occupied)
02230       return self
02231     except struct.error as e:
02232       raise genpy.DeserializationError(e) #most likely buffer underfill
02233 
02234 _struct_I = genpy.struct_I
02235 _struct_B = struct.Struct("<B")
02236 class GraspStatus(object):
02237   _type          = 'object_manipulation_msgs/GraspStatus'
02238   _md5sum = '222f0090ca965a030dae07c0a77db48b'
02239   _request_class  = GraspStatusRequest
02240   _response_class = GraspStatusResponse


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