Plans grasps for the hand and object, and stores them in the database. More...
#include <graspPlanningTask.h>
Public Slots | |
void | plannerComplete () |
Connected to the complete() signal of the planner. | |
void | plannerLoopUpdate () |
Connected to the loopUpdate() signal of the planner. | |
Public Member Functions | |
GraspPlanningTask (TaskDispatcher *disp, db_planner::DatabaseManager *mgr, db_planner::TaskRecord rec) | |
Just a stub for now. | |
virtual void | start () |
Loads the hand and the object, initializes and starts a loop planner. | |
~GraspPlanningTask () | |
Removes the object that has been used from the sim world, but not the hand. | |
Private Member Functions | |
bool | saveGrasp (const GraspPlanningState *gps) |
Saves a solution grasp to the database. | |
Private Attributes | |
Hand * | mHand |
The hand we are planning with. | |
int | mLastSolution |
The index of the last solution that was already saved in the database. | |
GraspableBody * | mObject |
The object we are planning on. | |
EGPlanner * | mPlanner |
The planner that we are using. | |
db_planner::PlanningTaskRecord | mPlanningTask |
The record of the actual planning task. |
Plans grasps for the hand and object, and stores them in the database.
For now, it does its own cleanup in the sense that it will remove from the world and delete the object that was used for planning. However, it will leave the hand in, as it might be used by subsequent tasks.
On startup, it will load the hand it needs, unless that hand is already the currently selected hand in the world. It will also load the object it needs. It will not delete anything from the world ar startup.
The init and cleanup so that the world is used by subsequent tasks is not well-defined yet, needs more work. Exactly what initialization and cleanup in the GraspIt world such a planner should do is unclear, might change in the future.
Definition at line 53 of file graspPlanningTask.h.
GraspPlanningTask::GraspPlanningTask | ( | TaskDispatcher * | disp, | |
db_planner::DatabaseManager * | mgr, | |||
db_planner::TaskRecord | rec | |||
) |
Just a stub for now.
Definition at line 45 of file graspPlanningTask.cpp.
GraspPlanningTask::~GraspPlanningTask | ( | ) |
Removes the object that has been used from the sim world, but not the hand.
Definition at line 54 of file graspPlanningTask.cpp.
void GraspPlanningTask::plannerComplete | ( | ) | [slot] |
Connected to the complete() signal of the planner.
Definition at line 169 of file graspPlanningTask.cpp.
void GraspPlanningTask::plannerLoopUpdate | ( | ) | [slot] |
Connected to the loopUpdate() signal of the planner.
Definition at line 177 of file graspPlanningTask.cpp.
bool GraspPlanningTask::saveGrasp | ( | const GraspPlanningState * | gps | ) | [private] |
Saves a solution grasp to the database.
Definition at line 209 of file graspPlanningTask.cpp.
void GraspPlanningTask::start | ( | ) | [virtual] |
Loads the hand and the object, initializes and starts a loop planner.
Implements Task.
Definition at line 66 of file graspPlanningTask.cpp.
Hand* GraspPlanningTask::mHand [private] |
The hand we are planning with.
Definition at line 57 of file graspPlanningTask.h.
int GraspPlanningTask::mLastSolution [private] |
The index of the last solution that was already saved in the database.
Definition at line 63 of file graspPlanningTask.h.
GraspableBody* GraspPlanningTask::mObject [private] |
The object we are planning on.
Definition at line 59 of file graspPlanningTask.h.
EGPlanner* GraspPlanningTask::mPlanner [private] |
The planner that we are using.
Definition at line 61 of file graspPlanningTask.h.
The record of the actual planning task.
Definition at line 65 of file graspPlanningTask.h.