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


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