libmove3d-planners
 All Classes Namespaces Files Functions Variables Enumerations Enumerator Friends Macros Groups Pages
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
RRT Class Reference

The Rapidly-exploring Random Tree (RRT) algorithm. More...

#include <RRT.hpp>

Inheritance diagram for RRT:
TreePlanner Planner DirectedRRT HRICS_RRT HRICS_RRTPlan ManhattanLikeRRT MultiRRT StarRRT ThresholdRRT TransitionEdgeRRT TransitionRRT

Public Member Functions

 RRT (Robot *robot, Graph *graph)
 Constructor.
 
virtual ~RRT ()
 Destructor.
 
virtual unsigned init ()
 Initialize RRT. More...
 
virtual unsigned run ()
 Main function of RRT. More...
 
virtual bool trajFound ()
 Check whether RRT has found a trajectory in the graph it is building. More...
 
void addConnectibleNode ()
 
unsigned int getNbConnectibleNodes ()
 
- Public Member Functions inherited from TreePlanner
 TreePlanner (Robot *R, Graph *G)
 Constructor.
 
 ~TreePlanner ()
 Destructor.
 
virtual bool preConditions ()
 Checks out the Pre-conditions. More...
 
virtual bool connectNodeToComp (Node *N, Node *CompNode)
 Tries to connect a node to the other connected component of the graph. More...
 
virtual bool connectionToTheOtherCompco (Node *toNode)
 Main function to connect to the other Connected Component. More...
 
virtual unsigned int expandOneStep (Node *fromComp)
 Expands tree from component fromComp. More...
 
bool goalBias () const
 Decide whether the goal bias should be applied, based on a random trial. More...
 
double getTime ()
 Return time in algorithm: this function must be called after ChronoTimeOfDayOn() More...
 
int getRunId ()
 Get the run Id.
 
void setRunId (int id)
 Set the run Id.
 
unsigned int getNumberOfConsecutiveFail ()
 Return the number of consecutive failures observed during planification.
 
unsigned int getNumberOfExpansion ()
 Return the number of expansions performed during planification.
 
unsigned int getNumberOfFailedExpansion ()
 Return the number of expansion that failed during planification.
 
unsigned int getNumberOfInitialNodes ()
 Return the initial number of nodes.
 
NodegetLastNode ()
 Return the last node added to the graph.
 
double getDistanceGap ()
 
- Public Member Functions inherited from Planner
 Planner ()
 Plain Constructor of the class.
 
 Planner (Robot *rob, Graph *graph)
 Constructor of the class. More...
 
virtual ~Planner ()
 Destructeur de la classe.
 
RobotgetActivRobot ()
 retourne le Robot activ More...
 
void setRobot (Robot *R)
 place le Robot utilisé pour la planification More...
 
GraphgetActivGraph ()
 obtient le Graph actif pour la planification More...
 
void setGraph (Graph *G)
 modifie le Graph actif pour la planification More...
 
bool setInit (confPtr_t Cs)
 place le Node initial de la planification More...
 
bool setGoal (confPtr_t Cg)
 place le Node final de la planification More...
 
NodegetInit ()
 obtient le Node intial de la planification More...
 
NodegetGoal ()
 obtient le Node final de la planification More...
 
confPtr_t getInitConf ()
 Get init configuration.
 
confPtr_t getGoalConf ()
 Get goal configuration.
 
bool getInitialized ()
 test si le Planner est initialisé pour la planification More...
 
void setInitialized (bool b)
 modifie la valeur du Booleen de test d'initialisation More...
 
int getRunId ()
 Get the run Id.
 
void setRunId (int id)
 Set the run Id.
 
double getTime ()
 return time in algorithm this function must be called after ChronoTimeOfDayOn() More...
 
void chronoStart ()
 
void chronoStop ()
 
void chronoUpdate ()
 

Protected Member Functions

virtual unsigned expandOneStep (ConnectedComponent *fromComp)
 Perform a single expansion step of RRT, growing the given connected component. More...
 
bool checkStopConditions ()
 Check the stopping conditions of RRT. More...
 
virtual API::TrajectoryextractTrajectory ()
 Extract a trajectory from Start to Goal.
 

Protected Attributes

RRTExpansionexpansion
 access point to the expansion procedure of RRT
 
std::vector< double > trajCosts
 
- Protected Attributes inherited from TreePlanner
int m_runId
 
unsigned int m_nbConscutiveFailures
 
unsigned int m_nbExpansion
 
unsigned int m_nbFailedExpansion
 
unsigned int m_nbInitNodes
 
double m_DistanceGap
 
Nodem_last_node
 
- Protected Attributes inherited from Planner
int(* _stop_func )()
 
void(* _draw_func )()
 
confPtr_t _q_start
 
confPtr_t _q_goal
 
Node_Start
 Le Node initial de la planification.
 
Node_Goal
 Le Node final de la planification.
 
Robot_Robot
 Le Robot pour lequel la recherche va se faire.
 
Graph_Graph
 Le Graph qui va être utilisé
 
bool _Init
 Le Planner a été initialisé
 
bool m_fail
 
int m_runId
 
double m_time
 

Detailed Description

The Rapidly-exploring Random Tree (RRT) algorithm.

Member Function Documentation

bool RRT::checkStopConditions ( )
protectedvirtual

Check the stopping conditions of RRT.

Returns
TRUE if one of the conditions is satisfied, and FALSE otherwise

Reimplemented from TreePlanner.

Reimplemented in StarRRT, and DirectedRRT.

unsigned RRT::expandOneStep ( ConnectedComponent fromComp)
protectedvirtual

Perform a single expansion step of RRT, growing the given connected component.

Returns
the number of created nodes

Reimplemented in DirectedRRT, and ManhattanLikeRRT.

virtual unsigned RRT::init ( void  )
inlinevirtual

Initialize RRT.

Returns
the number of nodes added to the graph

Reimplemented from TreePlanner.

Reimplemented in TransitionEdgeRRT, TransitionRRT, ThresholdRRT, StarRRT, DirectedRRT, MultiTRRT, MultiThresholdRRT, MultiRRT, HRICS_RRT, and HRICS_RRTPlan.

unsigned RRT::run ( )
virtual

Main function of RRT.


RRT


Returns
the number of nodes added to the graph

Main function of RRT.

Returns
the number of nodes added to the graph

Reimplemented from TreePlanner.

Reimplemented in DirectedRRT, and MultiRRT.

bool RRT::trajFound ( )
virtual

Check whether RRT has found a trajectory in the graph it is building.

Returns
TRUE if the criteria required for a trajectory to be found are met, and FALSE otherwise

Reimplemented from Planner.

Reimplemented in MultiRRT, and DirectedRRT.


The documentation for this class was generated from the following files: