Runs the GraspIt! Eigengrasp planning algorithm without using Qt signals/slots. More...
#include <EigenGraspPlannerNoQt.h>
Public Types | |
enum | PlannerType { SimAnn } |
Public Member Functions | |
EigenGraspPlannerNoQt (const std::string &name, const SHARED_PTR< GraspItSceneManager > &i) | |
void | getResults (std::vector< EigenGraspResult > &allGrasps) const |
bool | plan (const int maxPlanningSteps=DEFAULT_MAX_PLANNING_STEPS, const PlannerType &planType=SimAnn) |
bool | plan (const std::string &handName, const std::string &objectName, const EigenTransform *objectPose=NULL, const int maxPlanningSteps=DEFAULT_MAX_PLANNING_STEPS, const PlannerType &planType=SimAnn) |
bool | saveResultsAsWorldFiles (const std::string &inDirectory, const std::string &fileNamePrefix, bool asGraspIt=true, bool asInventor=false, bool createDir=true) |
virtual | ~EigenGraspPlannerNoQt () |
Protected Member Functions | |
virtual void | idleEventFromSceneManager () |
virtual void | onSceneManagerShutdown () |
Private Member Functions | |
bool | checkStateValidity (const GraspPlanningState *s) const |
void | getEigenGraspValues (const GraspPlanningState *s, std::vector< double > &egVals) const |
void | getGraspJointDOFs (const GraspPlanningState *s, std::vector< double > &dofs) const |
EigenTransform | getHandTransform (const GraspPlanningState *s) const |
EigenTransform | getObjectTransform (const GraspPlanningState *s) const |
void | getPregraspJointDOFs (const GraspPlanningState *s, std::vector< double > &dofs) const |
bool | initPlanner (const int maxPlanningSteps, const PlannerType &planType=SimAnn) |
void | initPlannerType (const GraspPlanningState &stateTemplate, const PlannerType &pt) |
void | initSearchType (GraspPlanningState &stateTemplate, const StateType &st) |
void | plannerComplete () |
void | plannerReset () |
void | plannerUpdate () |
void | printPlanningResults () |
void | printResult (int i, bool detailed=false) |
void | setPlanningParameters () |
void | updateResults () |
Static Private Member Functions | |
static void | statusThreadLoop (EigenGraspPlannerNoQt *_this) |
Private Attributes | |
EGPlanner * | graspitEgPlanner |
RECURSIVE_MUTEX | graspitEgPlannerMtx |
std::string | graspitSearchEnergyType |
StateType | graspitStateType |
std::vector< const GraspPlanningState * > | results |
THREAD * | statusThread |
bool | useContacts |
Runs the GraspIt! Eigengrasp planning algorithm without using Qt signals/slots.
This class extends the GraspItAccessor class to run the Eigengrasp planning algorithms in the original graspit source on the world. It is an example implementation of how access to the original graspit eigengrasp planner source without requiring direct Qt dependencies from within this class, as is the case with class EigenGraspPlanner.
*Notes*:
Definition at line 68 of file EigenGraspPlannerNoQt.h.
Definition at line 79 of file EigenGraspPlannerNoQt.h.
EigenGraspPlannerNoQt::EigenGraspPlannerNoQt | ( | const std::string & | name, |
const SHARED_PTR< GraspItSceneManager > & | i | ||
) |
Creates and initializes the planner.
Definition at line 60 of file EigenGraspPlannerNoQt.cpp.
EigenGraspPlannerNoQt::~EigenGraspPlannerNoQt | ( | ) | [virtual] |
Definition at line 73 of file EigenGraspPlannerNoQt.cpp.
bool EigenGraspPlannerNoQt::checkStateValidity | ( | const GraspPlanningState * | s | ) | const [private] |
Check if this is a state that the current implementation can work with
Definition at line 378 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::getEigenGraspValues | ( | const GraspPlanningState * | s, |
std::vector< double > & | egVals | ||
) | const [private] |
gets the Eigengrasp values associated with this grasp state
Definition at line 360 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::getGraspJointDOFs | ( | const GraspPlanningState * | s, |
std::vector< double > & | dofs | ||
) | const [private] |
Gets the DOFs of the joints for the grasp of this state
Definition at line 296 of file EigenGraspPlannerNoQt.cpp.
GraspIt::EigenTransform EigenGraspPlannerNoQt::getHandTransform | ( | const GraspPlanningState * | s | ) | const [private] |
Gets the transform of the Hand in a search state
Definition at line 261 of file EigenGraspPlannerNoQt.cpp.
GraspIt::EigenTransform EigenGraspPlannerNoQt::getObjectTransform | ( | const GraspPlanningState * | s | ) | const [private] |
Gets the transform of the object in a search state
Definition at line 268 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::getPregraspJointDOFs | ( | const GraspPlanningState * | s, |
std::vector< double > & | dofs | ||
) | const [private] |
Gets the DOFs of the joints for the pre-grasp of this state. This will execute an auto-grasp to open the hand before reading the DOF values.
Definition at line 322 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::getResults | ( | std::vector< EigenGraspResult > & | allGrasps | ) | const |
Returns the results of the grasp planning as EigenGraspResult objects.
Definition at line 473 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::idleEventFromSceneManager | ( | ) | [protected, virtual] |
This method will be called from within the scene manager thread in its next loop, **if** the method addAsIdleListener() was called for this instance **and** isScheduledForIdleEvent() returns true.
To trigger repeated calls of this function in each loop of the scene manager event loop, call scheduleForIdleEventUpdate() from within this function.
IMPORTANT: To not slow down the whole system this method should be kept very efficient! Any more complex operations should be done in other threads.
TIPP: While Qt is still used in GraspItSceneManager, this method will be called from the thread which also runs the Inventor stuff. So it is also possible to use this method only once (without re-scheduling with scheduleForIdleEventUpdate()) to create a SoIdleSensor object, which will then also be run from within the inventor thread.
Implements GraspIt::GraspItAccessor.
Definition at line 116 of file EigenGraspPlannerNoQt.cpp.
bool EigenGraspPlannerNoQt::initPlanner | ( | const int | maxPlanningSteps, |
const PlannerType & | planType = SimAnn |
||
) | [private] |
initializes the planner to use the specified planning type. This method needs to be called before the GraspIt planner is started.
maxPlanningSteps | maximum steps (iterations) for the planning algorithm to use |
planType | the type of planning algorithm to use. To this point, only simulated annealing is supported. |
Definition at line 578 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::initPlannerType | ( | const GraspPlanningState & | stateTemplate, |
const PlannerType & | pt | ||
) | [private] |
stateTemplate | tells the planner how the state it is searching on looks like (how many variables, etc). |
Definition at line 653 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::initSearchType | ( | GraspPlanningState & | stateTemplate, |
const StateType & | st | ||
) | [private] |
stateTemplate | tells the planner how the state it is searching on looks like (how many variables, etc). This object is initialized in this function according to the state type and the current hand and the object set to grasp. |
Definition at line 527 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::onSceneManagerShutdown | ( | ) | [protected, virtual] |
If this GraspItAccessor is registered with GraspItSceneManager (by a call of addAsIdleListener()), this method will be called from GraspItSceneManager when it shuts down.
Implements GraspIt::GraspItAccessor.
Definition at line 98 of file EigenGraspPlannerNoQt.cpp.
bool EigenGraspPlannerNoQt::plan | ( | const int | maxPlanningSteps = DEFAULT_MAX_PLANNING_STEPS , |
const PlannerType & | planType = SimAnn |
||
) |
Starts planning with the specified planner type. NOTE: Only simulated annealing is tested so far.
maxPlanningSteps | maximum steps (iterations) for the planning algorithm to use |
planType | the type of planning algorithm to use. To this point, only simulated annealing is supported. |
Definition at line 186 of file EigenGraspPlannerNoQt.cpp.
bool EigenGraspPlannerNoQt::plan | ( | const std::string & | handName, |
const std::string & | objectName, | ||
const EigenTransform * | objectPose = NULL , |
||
const int | maxPlanningSteps = DEFAULT_MAX_PLANNING_STEPS , |
||
const PlannerType & | planType = SimAnn |
||
) |
Sets the current hand and object before calling plan(const int, const int). This is achieved by calling GraspItSceneManager::setCurrentHand(std::string&) and GraspItSceneManager::setCurrentGraspableObject(std::string&), so it involves checking if these objects are currently loaded in the GraspIt world. And if they are not, this method returns false.
Aside from providing the possibility to change current hand and object, it is also possible to specify a new object pose, if the parameter is not NULL (otherwise the current pose will be used).
This method is threadsafe in regards to world changes. So if thread safety is a concern, you should rather use this method rather than first calling GraspItSceneManager::setCurrentHand() and then GraspItSceneManager::setCurrentGraspableObject() before calling plan(const int, const int).
Definition at line 150 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::plannerComplete | ( | ) | [private] |
To be called when the planning is finished to display the final results
Definition at line 755 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::plannerReset | ( | ) | [private] |
Definition at line 727 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::plannerUpdate | ( | ) | [private] |
To be called at regular intervals to display the current state of the planning process
Definition at line 748 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::printPlanningResults | ( | ) | [private] |
Definition at line 846 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::printResult | ( | int | i, |
bool | detailed = false |
||
) | [private] |
Load an input grasp file (".txt") TODO TEST ME
Definition at line 777 of file EigenGraspPlannerNoQt.cpp.
bool EigenGraspPlannerNoQt::saveResultsAsWorldFiles | ( | const std::string & | inDirectory, |
const std::string & | fileNamePrefix, | ||
bool | asGraspIt = true , |
||
bool | asInventor = false , |
||
bool | createDir = true |
||
) |
Saves the results as a GraspIt world files and/or inventor files in the given directory, with the given filename prefix. The files can be used to display the results with the original GraspIt simulator GUI or an Inventor files viewer.
createDir | if true, the directory in which the files are to be saved is created if it does not exist. |
asGraspIt | if true, the world files will be saved in the GraspIt world format |
asInventor | if true, the world files will be saved in the Inventor format. Saving as Inventor is slower than as GraspIt. |
Definition at line 421 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::setPlanningParameters | ( | ) | [private] |
Sets the planning parameters as specified in the fields graspitSearchEnergyType and useContacts
Definition at line 702 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::statusThreadLoop | ( | EigenGraspPlannerNoQt * | _this | ) | [static, private] |
Definition at line 122 of file EigenGraspPlannerNoQt.cpp.
void EigenGraspPlannerNoQt::updateResults | ( | ) | [private] |
Definition at line 760 of file EigenGraspPlannerNoQt.cpp.
EGPlanner* GraspIt::EigenGraspPlannerNoQt::graspitEgPlanner [private] |
Definition at line 257 of file EigenGraspPlannerNoQt.h.
Definition at line 258 of file EigenGraspPlannerNoQt.h.
std::string GraspIt::EigenGraspPlannerNoQt::graspitSearchEnergyType [private] |
Definition at line 269 of file EigenGraspPlannerNoQt.h.
StateType GraspIt::EigenGraspPlannerNoQt::graspitStateType [private] |
Definition at line 261 of file EigenGraspPlannerNoQt.h.
std::vector<const GraspPlanningState*> GraspIt::EigenGraspPlannerNoQt::results [private] |
Definition at line 274 of file EigenGraspPlannerNoQt.h.
Definition at line 252 of file EigenGraspPlannerNoQt.h.
bool GraspIt::EigenGraspPlannerNoQt::useContacts [private] |
Definition at line 272 of file EigenGraspPlannerNoQt.h.