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


object_manipulation_msgs
Author(s): Matei Ciocarlie
autogenerated on Mon Oct 6 2014 02:58:11