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


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