#include <sequential_tasks.h>
Public Member Functions | |
| void | checkSurface (int location, std::string surfaceLink) |
| void | makeFruitBasket () |
| void | obtainObject (int location, std::string object, std::string surfaceLink) |
| Navigate to a surface, pick up an object, and store it on the robot. | |
| void | packSchoolBag () |
| Perform a sequence that collects and packs all of the objects needed to pack a school bag. | |
| SequentialTasks () | |
| Constructor. | |
Private Attributes | |
| actionlib::SimpleActionClient < rail_manipulation_msgs::ArmAction > | armClient |
| actionlib::SimpleActionClient < wpi_jaco_msgs::HomeArmAction > | armHomeClient |
| ros::ServiceClient | lookAtFrameClient |
| actionlib::SimpleActionClient < carl_navigation::MoveCarlAction > | moveCarlClient |
| ros::NodeHandle | n |
| actionlib::SimpleActionClient < carl_demos::ObtainObjectAction > | obtainObjectClient |
Definition at line 16 of file sequential_tasks.h.
Constructor.
Definition at line 5 of file sequential_tasks.cpp.
| void SequentialTasks::checkSurface | ( | int | location, |
| std::string | surfaceLink | ||
| ) |
Definition at line 127 of file sequential_tasks.cpp.
| void SequentialTasks::makeFruitBasket | ( | ) |
Definition at line 21 of file sequential_tasks.cpp.
| void SequentialTasks::obtainObject | ( | int | location, |
| std::string | object, | ||
| std::string | surfaceLink | ||
| ) |
Navigate to a surface, pick up an object, and store it on the robot.
| location | navigation location, pass -1 for no navigation |
| object | name of the object to pick up |
| surfaceLink | name of the surface link to look at (only used if navigation is specified) |
Definition at line 165 of file sequential_tasks.cpp.
| void SequentialTasks::packSchoolBag | ( | ) |
Perform a sequence that collects and packs all of the objects needed to pack a school bag.
Note that this task is designed to show a use case for object replacement.
Definition at line 39 of file sequential_tasks.cpp.
actionlib::SimpleActionClient<rail_manipulation_msgs::ArmAction> SequentialTasks::armClient [private] |
Definition at line 51 of file sequential_tasks.h.
actionlib::SimpleActionClient<wpi_jaco_msgs::HomeArmAction> SequentialTasks::armHomeClient [private] |
Definition at line 52 of file sequential_tasks.h.
Definition at line 49 of file sequential_tasks.h.
actionlib::SimpleActionClient<carl_navigation::MoveCarlAction> SequentialTasks::moveCarlClient [private] |
Definition at line 54 of file sequential_tasks.h.
ros::NodeHandle SequentialTasks::n [private] |
Definition at line 47 of file sequential_tasks.h.
actionlib::SimpleActionClient<carl_demos::ObtainObjectAction> SequentialTasks::obtainObjectClient [private] |
Definition at line 53 of file sequential_tasks.h.