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


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