object_manipulation_msgs/PickupActionGoal Message

File: object_manipulation_msgs/PickupActionGoal.msg

Header header
actionlib_msgs/GoalID goal_id
PickupGoal goal

Expanded Definition

Header header
    uint32 seq
    time stamp
    string frame_id
actionlib_msgs/GoalID goal_id
    time stamp
    string id
PickupGoal goal
    string arm_name
    object_manipulation_msgs/GraspableObject target
        string reference_frame_id
        household_objects_database_msgs/DatabaseModelPose[] potential_models
            int32 model_id
            geometry_msgs/PoseStamped pose
                Header header
                    uint32 seq
                    time stamp
                    string frame_id
                geometry_msgs/Pose pose
                    geometry_msgs/Point position
                        float64 x
                        float64 y
                        float64 z
                    geometry_msgs/Quaternion orientation
                        float64 x
                        float64 y
                        float64 z
                        float64 w
            float32 confidence
        sensor_msgs/PointCloud cluster
            Header header
                uint32 seq
                time stamp
                string frame_id
            geometry_msgs/Point32[] points
                float32 x
                float32 y
                float32 z
            sensor_msgs/ChannelFloat32[] channels
                string name
                float32[] values
        object_manipulation_msgs/SceneRegion region
            sensor_msgs/PointCloud2 cloud
                Header header
                    uint32 seq
                    time stamp
                    string frame_id
                uint32 height
                uint32 width
                sensor_msgs/PointField[] fields
                    uint8 INT8=1
                    uint8 UINT8=2
                    uint8 INT16=3
                    uint8 UINT16=4
                    uint8 INT32=5
                    uint8 UINT32=6
                    uint8 FLOAT32=7
                    uint8 FLOAT64=8
                    string name
                    uint32 offset
                    uint8 datatype
                    uint32 count
                bool is_bigendian
                uint32 point_step
                uint32 row_step
                uint8[] data
                bool is_dense
            int32[] mask
            sensor_msgs/Image image
                Header header
                    uint32 seq
                    time stamp
                    string frame_id
                uint32 height
                uint32 width
                string encoding
                uint8 is_bigendian
                uint32 step
                uint8[] data
            sensor_msgs/Image disparity_image
                Header header
                    uint32 seq
                    time stamp
                    string frame_id
                uint32 height
                uint32 width
                string encoding
                uint8 is_bigendian
                uint32 step
                uint8[] data
            sensor_msgs/CameraInfo cam_info
                Header header
                    uint32 seq
                    time stamp
                    string frame_id
                uint32 height
                uint32 width
                string distortion_model
                float64[] D
                float64[9] K
                float64[9] R
                float64[12] P
                uint32 binning_x
                uint32 binning_y
                sensor_msgs/RegionOfInterest roi
                    uint32 x_offset
                    uint32 y_offset
                    uint32 height
                    uint32 width
                    bool do_rectify
    object_manipulation_msgs/Grasp[] desired_grasps
        sensor_msgs/JointState pre_grasp_posture
            Header header
                uint32 seq
                time stamp
                string frame_id
            string[] name
            float64[] position
            float64[] velocity
            float64[] effort
        sensor_msgs/JointState grasp_posture
            Header header
                uint32 seq
                time stamp
                string frame_id
            string[] name
            float64[] position
            float64[] velocity
            float64[] effort
        geometry_msgs/Pose grasp_pose
            geometry_msgs/Point position
                float64 x
                float64 y
                float64 z
            geometry_msgs/Quaternion orientation
                float64 x
                float64 y
                float64 z
                float64 w
        float64 success_probability
        bool cluster_rep
    float32 desired_approach_distance
    float32 min_approach_distance
    object_manipulation_msgs/GripperTranslation lift
        geometry_msgs/Vector3Stamped direction
            Header header
                uint32 seq
                time stamp
                string frame_id
            geometry_msgs/Vector3 vector
                float64 x
                float64 y
                float64 z
        float32 desired_distance
        float32 min_distance
    string collision_object_name
    string collision_support_surface_name
    bool allow_gripper_support_collision
    bool use_reactive_execution
    bool use_reactive_lift
    motion_planning_msgs/Constraints path_constraints
        motion_planning_msgs/JointConstraint[] joint_constraints
            string joint_name
            float64 position
            float64 tolerance_above
            float64 tolerance_below
            float64 weight
        motion_planning_msgs/PositionConstraint[] position_constraints
            Header header
                uint32 seq
                time stamp
                string frame_id
            string link_name
            geometry_msgs/Point target_point_offset
                float64 x
                float64 y
                float64 z
            geometry_msgs/Point position
                float64 x
                float64 y
                float64 z
            geometric_shapes_msgs/Shape constraint_region_shape
                byte SPHERE=0
                byte BOX=1
                byte CYLINDER=2
                byte MESH=3
                byte type
                float64[] dimensions
                int32[] triangles
                geometry_msgs/Point[] vertices
                    float64 x
                    float64 y
                    float64 z
            geometry_msgs/Quaternion constraint_region_orientation
                float64 x
                float64 y
                float64 z
                float64 w
            float64 weight
        motion_planning_msgs/OrientationConstraint[] orientation_constraints
            int32 LINK_FRAME=0
            int32 HEADER_FRAME=1
            Header header
                uint32 seq
                time stamp
                string frame_id
            string link_name
            int32 type
            geometry_msgs/Quaternion orientation
                float64 x
                float64 y
                float64 z
                float64 w
            float64 absolute_roll_tolerance
            float64 absolute_pitch_tolerance
            float64 absolute_yaw_tolerance
            float64 weight
        motion_planning_msgs/VisibilityConstraint[] visibility_constraints
            Header header
                uint32 seq
                time stamp
                string frame_id
            geometry_msgs/PointStamped target
                Header header
                    uint32 seq
                    time stamp
                    string frame_id
                geometry_msgs/Point point
                    float64 x
                    float64 y
                    float64 z
            geometry_msgs/PoseStamped sensor_pose
                Header header
                    uint32 seq
                    time stamp
                    string frame_id
                geometry_msgs/Pose pose
                    geometry_msgs/Point position
                        float64 x
                        float64 y
                        float64 z
                    geometry_msgs/Quaternion orientation
                        float64 x
                        float64 y
                        float64 z
                        float64 w
            float64 absolute_tolerance
    motion_planning_msgs/OrderedCollisionOperations additional_collision_operations
        motion_planning_msgs/CollisionOperation[] collision_operations
            string COLLISION_SET_ALL="all"
            string COLLISION_SET_OBJECTS="objects"
            string COLLISION_SET_ATTACHED_OBJECTS="attached"
            int32 DISABLE=0
            int32 ENABLE=1
            string object1
            string object2
            float64 penetration_distance
            int32 operation
    motion_planning_msgs/LinkPadding[] additional_link_padding
        string link_name
        float64 padding