Functions | |
bool | moveit::planning_interface::MoveGroup::pick (const std::string &object) |
Pick up an object. | |
bool | moveit::planning_interface::MoveGroup::pick (const std::string &object, const manipulation_msgs::Grasp &grasp) |
Pick up an object given a grasp pose. | |
bool | moveit::planning_interface::MoveGroup::pick (const std::string &object, const std::vector< manipulation_msgs::Grasp > &grasps) |
Pick up an object given possible grasp poses. | |
bool | moveit::planning_interface::MoveGroup::place (const std::string &object) |
Place an object somewhere safe in the world (a safe location will be detected) | |
bool | moveit::planning_interface::MoveGroup::place (const std::string &object, const std::vector< manipulation_msgs::PlaceLocation > &locations) |
Place an object at one of the specified possible locations. | |
bool | moveit::planning_interface::MoveGroup::place (const std::string &object, const std::vector< geometry_msgs::PoseStamped > &poses) |
Place an object at one of the specified possible locations. | |
bool | moveit::planning_interface::MoveGroup::place (const std::string &object, const geometry_msgs::PoseStamped &pose) |
Place an object at one of the specified possible location. |
bool moveit::planning_interface::MoveGroup::pick | ( | const std::string & | object | ) |
Pick up an object.
Definition at line 901 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::pick | ( | const std::string & | object, |
const manipulation_msgs::Grasp & | grasp | ||
) |
Pick up an object given a grasp pose.
Definition at line 906 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::pick | ( | const std::string & | object, |
const std::vector< manipulation_msgs::Grasp > & | grasps | ||
) |
Pick up an object given possible grasp poses.
Definition at line 911 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::place | ( | const std::string & | object | ) |
Place an object somewhere safe in the world (a safe location will be detected)
Definition at line 916 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::place | ( | const std::string & | object, |
const std::vector< manipulation_msgs::PlaceLocation > & | locations | ||
) |
Place an object at one of the specified possible locations.
Definition at line 921 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::place | ( | const std::string & | object, |
const std::vector< geometry_msgs::PoseStamped > & | poses | ||
) |
Place an object at one of the specified possible locations.
Definition at line 926 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::place | ( | const std::string & | object, |
const geometry_msgs::PoseStamped & | pose | ||
) |
Place an object at one of the specified possible location.
Definition at line 931 of file move_group.cpp.