4 #include "API/ConfigSpace/configuration.hpp"
130 virtual unsigned init();
135 virtual unsigned int run() = 0;
164 void (*_draw_func)();
186 extern Planner* global_Move3DPlanner;
Robot * _Robot
Le Robot pour lequel la recherche va se faire.
Definition: planner.hpp:174
confPtr_t getInitConf()
Get init configuration.
Definition: planner.hpp:108
Planner()
Plain Constructor of the class.
Definition: planner.cpp:27
int getRunId()
Get the run Id.
Definition: planner.hpp:140
Classe représentant un Node d'un Graph.
Definition: node.hpp:39
Graph * _Graph
Le Graph qui va être utilisé
Definition: planner.hpp:175
Node * getInit()
obtient le Node intial de la planification
Definition: planner.cpp:92
bool setGoal(confPtr_t Cg)
place le Node final de la planification
Definition: planner.cpp:159
Robot * getActivRobot()
retourne le Robot activ
Definition: planner.cpp:72
confPtr_t getGoalConf()
Get goal configuration.
Definition: planner.hpp:113
virtual bool trajFound()
test de trajectoire
Definition: planner.cpp:60
void setGraph(Graph *G)
modifie le Graph actif pour la planification
Definition: planner.cpp:87
bool setInit(confPtr_t Cs)
place le Node initial de la planification
Definition: planner.cpp:125
double getTime()
return time in algorithm this function must be called after ChronoTimeOfDayOn()
Definition: planner.cpp:117
void setRunId(int id)
Set the run Id.
Definition: planner.hpp:145
This class holds a the robot represented by a kinematic chain.
Definition: robot.hpp:42
virtual unsigned int run()=0
Run function.
virtual unsigned init()
Méthode d'initialisation du Planner.
Definition: planner.cpp:102
void setInitialized(bool b)
modifie la valeur du Booleen de test d'initialisation
Definition: planner.cpp:206
Node * _Start
Le Node initial de la planification.
Definition: planner.hpp:171
Definition: trajectory.hpp:40
bool getInitialized()
test si le Planner est initialisé pour la planification
Definition: planner.cpp:201
Node * getGoal()
obtient le Node final de la planification
Definition: planner.cpp:97
void setRobot(Robot *R)
place le Robot utilisé pour la planification
Definition: planner.cpp:77
Base class for planning algorithms.
Definition: planner.hpp:28
Node * _Goal
Le Node final de la planification.
Definition: planner.hpp:172
bool _Init
Le Planner a été initialisé
Definition: planner.hpp:177
virtual ~Planner()
Destructeur de la classe.
Definition: planner.cpp:56
Graph * getActivGraph()
obtient le Graph actif pour la planification
Definition: planner.cpp:82