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