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