EGPlanner Class Reference

#include <egPlanner.h>

Inheritance diagram for EGPlanner:
Inheritance graph
[legend]

List of all members.

Signals

void complete ()
 To be emitted when planner stops.
void update ()
 To be emitted during the searh as a measure of progress.

Public Member Functions

virtual void clearSolutions ()
 Clears the list of solutions mBestList.
void createAndUseClone ()
 Tells the planner to create and use a clone of the hand passed to the constructor.
 EGPlanner (Hand *h)
 The constructor is desigend NOT to be called by sub-classes.
int getCurrentStep ()
virtual const GraspPlanningStategetGrasp (int i)
 Returns the i-th state from the list of solutions mBestList.
HandgetHand ()
unsigned char getInputType ()
virtual int getListSize ()
 Returns the size of the mBestList list of solutions.
double getRunningTime ()
 The time elapsed since the last reset.
PlannerState getState ()
 Get the current state of the planner (ready, running, etc.). Thread-safe.
GraspPlanningStategetTargetState ()
 Sets the "target state" that is used as a model during the search.
virtual PlannerType getType ()=0
 The type of this planner, for easier run-time check.
virtual bool initialized ()
 Tells the planner if it has all the information needed to start planning.
void invalidateReset ()
 Tells the planner that its initialization is no longer valid and new input must be provided.
virtual bool isActive ()
 Convenience function; return whether current state is RUNNING or not.
virtual bool isReady ()
 Convenience function; return whether current state is READY or not.
virtual void pausePlanner ()
 Pause the loops; planner can be re-started.
virtual bool resetPlanner ()
 Used to restart the search from the beginning.
void setContactType (SearchContactType c)
 Tells the planner what kind of virtual contact computation to use.
virtual void setEnergyType (SearchEnergyType s)
 Tells the planner what kind of energy calculator to use.
bool setInput (unsigned char input, bool on=true)
 Can be used to set what kind of information is used from the "target state".
void setMaxSteps (int s)
void setMaxTime (int t)
void setRenderType (RenderType r)
void setRepeat (bool r)
void setStatStream (std::ostream *out) const
 Set the stream for outputting stats and info.
virtual void showClone (bool s)
 Add (and thus render) or remove (and thus hide) the clone from the world scene graph.
virtual void showGrasp (int i)
 Renders the i-th state from the list of solutions mBestList.
virtual void startPlanner ()
 Start the loops.
void startThread ()
 Tells the planner to start and run in its own thread.
virtual void stopPlanner ()
 Stops the planner FOR GOOD.
virtual ~EGPlanner ()

Protected Member Functions

bool addToListOfUniqueSolutions (GraspPlanningState *s, std::list< GraspPlanningState * > *list, double distance)
 Helper function that helps maintain a list of UNIQUE solutions.
virtual bool checkTerminationConditions ()
 Checks whether we should terminate the planner, either because maxSteps or maxTime have been exceeded.
 EGPlanner ()
void init ()
 Contains initialization that is COMMON between this and all subclasses.
virtual void mainLoop ()=0
 Pure abstract function to be written in all subclasses. This is where most of the real planning is done.
virtual bool processInput ()
 Sets the values in the mTargetState based in the mInputType flag.
void render ()
 A decision is made whether to put in a redraw request to the scene graph.
virtual void resetParameters ()
 Resets all the inner parameters. Can be called while planner is running as well.
virtual void run ()
 The entry point of child threads.
void setState (PlannerState s)
 Sets the current state of the planner.
virtual double stateDistance (const GraspPlanningState *s1, const GraspPlanningState *s2)
 Helper function that returns a measure of how similar two states are.
virtual void threadLoop ()
 The main loop that child threads run in.

Static Protected Member Functions

static void sensorCB (void *data, SoSensor *)
 The idle sensor callback, which calls mainLoop() during single-threaded operation.

Protected Attributes

std::list< GraspPlanningState * > mBestList
 A list that is normally used to keep track of solutions found so far.
QMutex mControlMutex
 Mutex for synchronizing threads.
GraspPlanningStatemCurrentState
 The current state of the planner (see the HandObjectState class for details).
int mCurrentStep
 How many iterations this planner has done since the last reset.
SearchEnergymEnergyCalculator
 The instance of the SearchEnergy class that this planner can use to compute the "quality" of a state.
HandmHand
 This is the hand that the planner is using. Might be a real hand from the GraspIt world or a clone of one.
SoSensor * mIdleSensor
 For single-threaded operation, using an idle sensor.
unsigned char mInputType
 Tells the planner if it should process its own input state, based on Cyberglove, Flock of Birds etc.
const GraspPlanningStatemLastRenderState
 The last rendered state.
int mMaxSteps
 Maximum number of iterations allowed. mMaxSteps = -1 means run forever.
double mMaxTime
 Maximum time allowed, in seconds. mMaxTime = -1 means no time limit.
bool mMultiThread
 Flag that indicates single- or multi-threaded operation.
std::ostream * mOut
 This is where the planner (and its SearchEnergy) will spit their output.
Profiling::ProfileInstancemProfileInstance
 The profiling instance used to time this planner.
int mRenderCount
int mRenderType
 These options decide when and what the planner should render.
bool mRepeat
 Tells us what happens when mMaxSteps have been exceeded: the planner will either stop or restart.
PlannerState mState
 The current state of the planner (ready, running, paused, etc.).
GraspPlanningStatemTargetState
 If used, this is a target state, or an "input" state provided by the user as a guideline.
bool mUsesClone

Detailed Description

The EGPlanner is one of the main classes that are available in GraspIt! for doing grasp planning. Unlike the name suggests, it is not necessarily restricted to running in EigenGrasp space. It is designed to take care of loops, lists of solutions, etc. and allow sub-classes to just focus on the planning itself. When subclassing from this class, you just have to define the mainLoop() function which here is pure abstract.

It can operate either in a single-thread fashion, where the looping functionality is provided using a Coin IdleSensor, or it can start it's own thread which spins forever and calls the mainLoop().

It can either operate on the GraspIt hand that is passed as an argument, or it can create its own "clone" of the hand to do the planning on. If multi-threaded, the planner will ALWAYS run on a clone.

Definition at line 67 of file egPlanner.h.


Constructor & Destructor Documentation

EGPlanner::EGPlanner (  )  [inline, protected]

Definition at line 71 of file egPlanner.h.

EGPlanner::EGPlanner ( Hand h  ) 

The constructor is desigend NOT to be called by sub-classes.

Definition at line 51 of file egPlanner.cpp.

EGPlanner::~EGPlanner (  )  [virtual]

Definition at line 83 of file egPlanner.cpp.


Member Function Documentation

bool EGPlanner::addToListOfUniqueSolutions ( GraspPlanningState s,
std::list< GraspPlanningState * > *  list,
double  distance 
) [protected]

Helper function that helps maintain a list of UNIQUE solutions.

Attempts to maintain a list of unique solutions. Therefore, whenever a new state is added to the list, we check if any of the states that are already in the list are within a given distance of the new state. If so, the best one is kept and the other one is thrown away. This method does not gurantee unique states, but it comes close and runs in linear time for each addition, rather than square time for maintenance.

Definition at line 514 of file egPlanner.cpp.

bool EGPlanner::checkTerminationConditions (  )  [protected, virtual]

Checks whether we should terminate the planner, either because maxSteps or maxTime have been exceeded.

Definition at line 168 of file egPlanner.cpp.

void EGPlanner::clearSolutions (  )  [virtual]

Clears the list of solutions mBestList.

Reimplemented in LoopPlanner.

Definition at line 453 of file egPlanner.cpp.

void EGPlanner::complete (  )  [signal]

To be emitted when planner stops.

To be emitted when planner stops, either through an explicit termination user command or by exceeding mMaxSteps or mMaxTime.

Definition at line 89 of file moc_egPlanner.cpp.

void EGPlanner::createAndUseClone (  ) 

Tells the planner to create and use a clone of the hand passed to the constructor.

Definition at line 198 of file egPlanner.cpp.

int EGPlanner::getCurrentStep (  )  [inline]

Definition at line 218 of file egPlanner.h.

const GraspPlanningState * EGPlanner::getGrasp ( int  i  )  [virtual]

Returns the i-th state from the list of solutions mBestList.

Reimplemented in LoopPlanner.

Definition at line 431 of file egPlanner.cpp.

Hand* EGPlanner::getHand (  )  [inline]

Definition at line 219 of file egPlanner.h.

unsigned char EGPlanner::getInputType (  )  [inline]

Definition at line 228 of file egPlanner.h.

virtual int EGPlanner::getListSize (  )  [inline, virtual]

Returns the size of the mBestList list of solutions.

Reimplemented in LoopPlanner.

Definition at line 214 of file egPlanner.h.

double EGPlanner::getRunningTime (  ) 

The time elapsed since the last reset.

Definition at line 306 of file egPlanner.cpp.

PlannerState EGPlanner::getState (  ) 

Get the current state of the planner (ready, running, etc.). Thread-safe.

Definition at line 117 of file egPlanner.cpp.

GraspPlanningState* EGPlanner::getTargetState (  )  [inline]

Sets the "target state" that is used as a model during the search.

Definition at line 227 of file egPlanner.h.

virtual PlannerType EGPlanner::getType (  )  [pure virtual]

The type of this planner, for easier run-time check.

Implemented in GraspTester, GuidedPlanner, ListPlanner, LoopPlanner, OnLinePlanner, SimAnnPlanner, and TimeTester.

void EGPlanner::init (  )  [protected]

Contains initialization that is COMMON between this and all subclasses.

Class-specific initialization will go in the constructor.

Also sets the state of the planner to INIT, which is default initialization.

Definition at line 62 of file egPlanner.cpp.

virtual bool EGPlanner::initialized (  )  [inline, virtual]

Tells the planner if it has all the information needed to start planning.

Reimplemented in ListPlanner, and SimAnnPlanner.

Definition at line 167 of file egPlanner.h.

void EGPlanner::invalidateReset (  )  [inline]

Tells the planner that its initialization is no longer valid and new input must be provided.

Definition at line 197 of file egPlanner.h.

virtual bool EGPlanner::isActive (  )  [inline, virtual]

Convenience function; return whether current state is RUNNING or not.

Definition at line 192 of file egPlanner.h.

virtual bool EGPlanner::isReady (  )  [inline, virtual]

Convenience function; return whether current state is READY or not.

Definition at line 194 of file egPlanner.h.

virtual void EGPlanner::mainLoop (  )  [protected, pure virtual]

Pure abstract function to be written in all subclasses. This is where most of the real planning is done.

Implemented in GraspTester, GuidedPlanner, ListPlanner, OnLinePlanner, SimAnnPlanner, TimeTester, and MTTester.

void EGPlanner::pausePlanner (  )  [virtual]

Pause the loops; planner can be re-started.

Reimplemented in GuidedPlanner, OnLinePlanner, and MTTester.

Definition at line 389 of file egPlanner.cpp.

bool EGPlanner::processInput (  )  [protected, virtual]

Sets the values in the mTargetState based in the mInputType flag.

Definition at line 474 of file egPlanner.cpp.

void EGPlanner::render (  )  [protected]

A decision is made whether to put in a redraw request to the scene graph.

WARNING: when multi-threaded, it is best to avoid ALL rendering requests issued from inside the planner.

Definition at line 405 of file egPlanner.cpp.

void EGPlanner::resetParameters (  )  [protected, virtual]

Resets all the inner parameters. Can be called while planner is running as well.

This is the part of resetPlanner() that can also be called while the planner is running to cause it to start from the beginning, without affecting the currently computed solutions.

Reimplemented in ListPlanner, LoopPlanner, OnLinePlanner, and SimAnnPlanner.

Definition at line 130 of file egPlanner.cpp.

bool EGPlanner::resetPlanner (  )  [virtual]

Used to restart the search from the beginning.

The only function available externally to set the planner to the READY state. However, before that can actually happen, the planner must receive all needed input, which depends on the type of implementation.

It will clear any solutions saved so far and re-start the timer and the step count as well. It can not be used while the planner is running, you must pause the planner first. This function will also move the planner from INIT to READY as long as all the necessary conditions for initilized() have been met.

Reimplemented in GraspTester, GuidedPlanner, and OnLinePlanner.

Definition at line 147 of file egPlanner.cpp.

void EGPlanner::run (  )  [protected, virtual]

The entry point of child threads.

Definition at line 312 of file egPlanner.cpp.

void EGPlanner::sensorCB ( void *  data,
SoSensor *   
) [static, protected]

The idle sensor callback, which calls mainLoop() during single-threaded operation.

Definition at line 268 of file egPlanner.cpp.

void EGPlanner::setContactType ( SearchContactType  c  ) 

Tells the planner what kind of virtual contact computation to use.

Definition at line 261 of file egPlanner.cpp.

void EGPlanner::setEnergyType ( SearchEnergyType  s  )  [virtual]

Tells the planner what kind of energy calculator to use.

Reimplemented in GraspTester.

Definition at line 254 of file egPlanner.cpp.

bool EGPlanner::setInput ( unsigned char  input,
bool  on = true 
)

Can be used to set what kind of information is used from the "target state".

Definition at line 461 of file egPlanner.cpp.

void EGPlanner::setMaxSteps ( int  s  )  [inline]

Definition at line 205 of file egPlanner.h.

void EGPlanner::setMaxTime ( int  t  )  [inline]

Definition at line 207 of file egPlanner.h.

void EGPlanner::setRenderType ( RenderType  r  )  [inline]

Definition at line 204 of file egPlanner.h.

void EGPlanner::setRepeat ( bool  r  )  [inline]

Definition at line 206 of file egPlanner.h.

void EGPlanner::setState ( PlannerState  s  )  [protected]

Sets the current state of the planner.

Set the current state of the planner. It will accept any state, as long as the current state is not DONE or EXITED. Once the planner is DONE it can only go to EXITED when the thread stops spinning. DONE is essentially just a flag that is guaranteed to stop the thread. There's no going back...

Definition at line 103 of file egPlanner.cpp.

void EGPlanner::setStatStream ( std::ostream *  out  )  const

Set the stream for outputting stats and info.

Definition at line 546 of file egPlanner.cpp.

void EGPlanner::showClone ( bool  s  )  [virtual]

Add (and thus render) or remove (and thus hide) the clone from the world scene graph.

The planner can remove the clone from the scene graph. The clone still exists in the collision detection system and can be used normally, it is just not rendered anymore. HIGHLY RECOMMENDED for multi-threaded operation, since Inventor is not thread-safe. The clone should be rendered just for debug purposes.

Reimplemented in OnLinePlanner.

Definition at line 240 of file egPlanner.cpp.

void EGPlanner::showGrasp ( int  i  )  [virtual]

Renders the i-th state from the list of solutions mBestList.

Definition at line 442 of file egPlanner.cpp.

void EGPlanner::startPlanner (  )  [virtual]

Start the loops.

Reimplemented in GuidedPlanner, OnLinePlanner, TimeTester, and MTTester.

Definition at line 349 of file egPlanner.cpp.

void EGPlanner::startThread (  ) 

Tells the planner to start and run in its own thread.

Automatically calls createAndUseClone(). Does not return until new thread is up and ready. However, it does not also start planning, it just spins. Use startPlanner(), like you would for single-threaded operation, for that.

Definition at line 329 of file egPlanner.cpp.

double EGPlanner::stateDistance ( const GraspPlanningState s1,
const GraspPlanningState s2 
) [protected, virtual]

Helper function that returns a measure of how similar two states are.

Reimplemented in OnLinePlanner.

Definition at line 501 of file egPlanner.cpp.

void EGPlanner::stopPlanner (  )  [virtual]

Stops the planner FOR GOOD.

After this is called, the planner can no longer be re-started. This differentiation is needed mainly for the multi-threaded case: this function stops the planner's thread.

Reimplemented in GuidedPlanner.

Definition at line 373 of file egPlanner.cpp.

void EGPlanner::threadLoop (  )  [protected, virtual]

The main loop that child threads run in.

Definition at line 279 of file egPlanner.cpp.

void EGPlanner::update (  )  [signal]

To be emitted during the searh as a measure of progress.

Definition at line 83 of file moc_egPlanner.cpp.


Member Data Documentation

std::list<GraspPlanningState*> EGPlanner::mBestList [protected]

A list that is normally used to keep track of solutions found so far.

Definition at line 142 of file egPlanner.h.

QMutex EGPlanner::mControlMutex [protected]

Mutex for synchronizing threads.

Definition at line 130 of file egPlanner.h.

The current state of the planner (see the HandObjectState class for details).

Definition at line 83 of file egPlanner.h.

int EGPlanner::mCurrentStep [protected]

How many iterations this planner has done since the last reset.

Definition at line 88 of file egPlanner.h.

The instance of the SearchEnergy class that this planner can use to compute the "quality" of a state.

Definition at line 85 of file egPlanner.h.

Hand* EGPlanner::mHand [protected]

This is the hand that the planner is using. Might be a real hand from the GraspIt world or a clone of one.

Definition at line 77 of file egPlanner.h.

SoSensor* EGPlanner::mIdleSensor [protected]

For single-threaded operation, using an idle sensor.

Definition at line 123 of file egPlanner.h.

unsigned char EGPlanner::mInputType [protected]

Tells the planner if it should process its own input state, based on Cyberglove, Flock of Birds etc.

Definition at line 112 of file egPlanner.h.

The last rendered state.

Definition at line 97 of file egPlanner.h.

int EGPlanner::mMaxSteps [protected]

Maximum number of iterations allowed. mMaxSteps = -1 means run forever.

Definition at line 90 of file egPlanner.h.

double EGPlanner::mMaxTime [protected]

Maximum time allowed, in seconds. mMaxTime = -1 means no time limit.

Definition at line 105 of file egPlanner.h.

bool EGPlanner::mMultiThread [protected]

Flag that indicates single- or multi-threaded operation.

Definition at line 128 of file egPlanner.h.

std::ostream* EGPlanner::mOut [mutable, protected]

This is where the planner (and its SearchEnergy) will spit their output.

Definition at line 81 of file egPlanner.h.

The profiling instance used to time this planner.

Definition at line 107 of file egPlanner.h.

int EGPlanner::mRenderCount [protected]

Definition at line 95 of file egPlanner.h.

int EGPlanner::mRenderType [protected]

These options decide when and what the planner should render.

Definition at line 95 of file egPlanner.h.

bool EGPlanner::mRepeat [protected]

Tells us what happens when mMaxSteps have been exceeded: the planner will either stop or restart.

Definition at line 92 of file egPlanner.h.

The current state of the planner (ready, running, paused, etc.).

Definition at line 137 of file egPlanner.h.

If used, this is a target state, or an "input" state provided by the user as a guideline.

Definition at line 110 of file egPlanner.h.

bool EGPlanner::mUsesClone [protected]

Definition at line 78 of file egPlanner.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


graspit
Author(s):
autogenerated on Wed Jan 25 11:00:20 2012