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


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