libmove3d-planners
|
Public Member Functions | |
Graph (Robot *R, graph *ptGraph) | |
Graph (Robot *R) | |
Graph (graph *G) | |
Graph (const Graph &G) | |
Graph copy constructor : be sure that the connected componants are updated. More... | |
bool | isGraphChanged () |
return the value of the Change flag More... | |
graph * | getGraphStruct () const |
Creates a p3d_graph from Boost Graph. More... | |
void | setGraph (graph *G) |
stocke la structure p3d_graph More... | |
Robot * | getRobot () const |
obtient le Robot pour lequel le Graph est créé More... | |
void | setRobot (Robot *R) |
sets the Robot of the Graph | |
std::map< node *, Node * > | getNodesTable () |
obtient la table des noeuds du Graph More... | |
unsigned int | getNumberOfNodes () |
obtient le nombre de Node dans le Graph More... | |
std::vector< Node * > | getNodes () const |
obtient le vecteur des Node du Graph More... | |
std::vector< Node * > | getSortedNodes () const |
std::vector< Node * > | getNotTrajNodes () const |
Node * | getNode (unsigned int i) const |
Get Node ith node in Graph. | |
unsigned int | getNumberOfEdges () const |
obtient le nombre de Node dans le Graph More... | |
std::vector< Edge * > | getEdges () const |
obtient le vecteur des Edge du Graph More... | |
std::vector< Edge * > | getEdges (std::tr1::shared_ptr< Configuration > q, bool from=false) |
std::vector< Edge * > | getEdges (Node *nq, bool from=false) |
Edge * | getEdge (unsigned int i) const |
Returns the ith edge. | |
unsigned int | getNumberOfCompco () const |
ConnectedComponent * | getConnectedComponent (int ith) const |
Get Compco. More... | |
std::vector< ConnectedComponent * > | getConnectedComponents () const |
Get Compcos. | |
Node * | getNode (node *N) |
obtient le Node correspondant au p3d_node More... | |
Node * | getLastNode () |
obtient le dernier Node ajouté au Graph More... | |
std::string | getName () |
obtient le nom du Graph More... | |
void | setName () |
modifie le nom du Graph; un nom standard est alors mis | |
void | setName (std::string Name) |
modifie le nom du Graph More... | |
bool | equal (Graph *G) |
teste si deux Graph sont égaux en comparant leur listNode More... | |
bool | equalName (Graph *G) |
teste si deux Graph ont le même nom More... | |
bool | isInGraph (Node *N) |
vérifie si un node est dans le Graph More... | |
Edge * | isEdgeInGraph (Node *N1, Node *N2) |
Looks if two Node make an edge in the Graph. More... | |
Node * | searchConf (Configuration &q) |
Gets the node that corresponds to a configuration. More... | |
void | createCompco (Node *node) |
New Compco. More... | |
Node * | insertNode (Node *node) |
insert un Node dans le Graph More... | |
Node * | insertExtremalNode (Node *node) |
insert un Node de type ISOLATE More... | |
void | addNode (Node *node) |
Add the given node to the storing structure of the graph (without creating any link). | |
Node * | insertNode (Node *expansionNode, LocalPath &path) |
Link a Configuration to a Node for the RRT Planner. More... | |
Node * | insertConfigurationAsNode (std::tr1::shared_ptr< Configuration > q, Node *from, double step) |
Link a Configuration to a Node for the RRT Planner. More... | |
void | sortEdges () |
trie les Edges en fonction de leur longueur More... | |
void | updateSortedNodes (Node *node) |
trie les Nodes en fonction de leur distance à la position du robot via la trajectoire courante | |
Node * | getRandomNodeNearTraj () |
void | updateSepareNodes (Node *n) |
void | separateNodes () |
std::map< double, Node * > | getNodesOnTraj (Node *near, bool neighbour=false) |
std::vector< Node * > | getKNodesOnTraj (Node *near, uint k) |
void | sortNodes (double init=-1) |
Edge * | addEdge (Node *source, Node *target, bool compute_length=true, double length=0., bool compute_cost=true, double cost=0.) |
ajoute un Edge au Graph More... | |
Edge * | addEdge (Node *source, Node *target, localPathPtr_t path) |
Add an edge to the graph, going from the given source to the given target. More... | |
void | addEdges (Node *N1, Node *N2, bool computeLength=true, double length=0., bool computeCost=true, double cost=0.) |
ajoute deux Edge au Graph More... | |
void | addEdges (Node *N1, Node *N2, localPathPtr_t path) |
Add two opposite edges between the nodes N1 and N2. More... | |
void | addOrientedEdge (Node *N1, Node *N2, localPathPtr_t path) |
Add the oriented edge N1->N2. More... | |
void | removeEdge (Edge *E) |
Remove edge. More... | |
void | removeEdges (Node *N1, Node *N2) |
Remove the edges between the nodes N1 and N2. More... | |
void | sortNodesByDist (Node *N) |
Sort nodes against one given node. More... | |
void | sortNodesByDist (confPtr_t q) |
Sort nodes against one given configuration. More... | |
void | addNode (Node *N, double maxDist) |
ajoute un Node s'il est à moins d'une distance max du Graph More... | |
void | addNodes (std::vector< Node * > N, double maxDist) |
ajoute des Node s'ils sont à moins d'une distance max du Graph More... | |
void | removeNode (Node *node) |
Remove the given node from the graph. | |
bool | linkNode (Node *N) |
lie un Node au Graph More... | |
bool | linkNodeCompMultisol (Node *N, ConnectedComponent *compPt) |
Links a node to a compco with multisol. More... | |
bool | linkNodeWithoutDist (Node *N) |
Lie un node au Graph sans prendre en compte la distance max. More... | |
bool | linkNodeAtDist (Node *N) |
Lie un Node au Graph en prenant en compte la distance max. More... | |
bool | linkToAllNodes (Node *N) |
lie un Node à tous les autres Nodes visibles More... | |
bool | areNodesLinked (Node *node1, Node *node2, double &dist) |
Function that computes if a node is linked to another node. More... | |
bool | linkNodeAndMerge (Node *node1, Node *node2) |
Link 2 nodes and merge them. More... | |
void | createRandConfs (int NMAX) |
crée des Node à des Configurations aléatoires More... | |
Node * | randomNodeFromComp (Node *comp) |
Gets Random node in the connected component. More... | |
bool | connectNodeToCompco (Node *node, Node *compco) |
Function that trys to connect a node to a given connected component. More... | |
std::vector< Node * > | KNearestWeightNeighbour (confPtr_t q, int K, double radius, bool weighted, int distConfigChoice) |
K Nearest Weighted Neighbors in graph. More... | |
std::vector< Node * > | kNearestNeighbours (unsigned k, confPtr_t conf) |
std::vector< Node * > | neighborsInBall (confPtr_t conf, double radius) |
Return the nodes whose configurations are within a ball (in the C-space) having the given radius and centered on the given configuration. | |
Node * | nearestWeightNeighbour (Node *compco, confPtr_t C, bool weighted, int distConfigChoice) |
obtient le plus proche voisin d'une composante connexe More... | |
Node * | getCompco (unsigned int ith) |
Get Ith Compco. More... | |
std::vector< Node * > | getNodesInTheCompCo (Node *node) |
Vector of nodes in the same compco. More... | |
void | addCycles (Node *node, double step) |
ajoute des Edges formant des cycles dans le Graph More... | |
void | mergeComponents (Node *N1, Node *N2) |
Merge the connected components to which N1 and N2 belong. | |
int | mergeComp (Node *CompCo1, Node *CompCo2, double DistNodes, bool compute_edge_cost) |
merge deux composantes connexes More... | |
int | rebuildCompcoFromBoostGraph () |
Rebuild the connected component using the strongly connected component algo from the BGL. | |
void | mergeCheck () |
teste si des composantes connexes doivent être merger et le fait le cas échéant More... | |
void | removeCompco (ConnectedComponent *CompCo) |
Delete the compco. More... | |
bool | checkConnectedComponents () |
Check C and C++ Connected Components. | |
void | recomputeCost () |
Recompute the Graph cost (Edges and Nodes) More... | |
bool | checkAllEdgesValid () |
Recompute All Edges Valid. More... | |
API::Trajectory * | extractBestTrajSoFar (confPtr_t qi, confPtr_t qf) |
Extract best traj from qi that is closest to q_f. | |
std::pair< bool, std::vector < Node * > > | extractBestNodePathSoFar (confPtr_t qi, confPtr_t qf) |
Extract best vector of nodes from qi that is closest to q_f. More... | |
API::Trajectory * | extractTreeShortestPath (Node *initN, Node *endN) |
Return a trajectory (i.e. the shortest path) from initN to endN, using parenthood in a tree. More... | |
std::vector< double > | computeDijkstraShortestPaths (Node *n) |
Compute the lengths of all the shortest paths having for source the node n, using Dijkstra. | |
std::vector< double > | computeDijkstraShortestPaths (Node *n, std::map< double, Node * > to) |
std::vector< Node * > | extractAStarShortestNodePaths (Node *initN, Node *endN) |
Return the shortest path (as a list of nodes) from initN to endN, using A*. | |
std::vector< Node * > | extractAStarShortestNodePaths (std::vector< Node * > passingBy) |
std::vector< Node * > | extractAStarShortestNodePaths (confPtr_t initC, confPtr_t endC) |
Return the shortest path (as a list of nodes) from initC to endC, using A*. | |
API::Trajectory * | extractAStarShortestPath (Node *initN, Node *endN) |
Return a trajectory (i.e. the shortest path) from initN to endN, using A*. More... | |
API::Trajectory * | extractAStarShortestPath (confPtr_t initC, confPtr_t endC) |
Return a trajectory (i.e. the shortest path) from initC to endC, using A*. More... | |
double | getAStarShortestPathLength (confPtr_t initC, confPtr_t endC) |
Return the lenght of the shortest path (using A*) in the graph between initC and endC Return P3D_HUDGE if no such path exists. | |
API::Trajectory * | extractBestTraj (confPtr_t qi, confPtr_t qf) |
Extract best traj. | |
void | initMotionPlanning (node *start, node *goal) |
Init Motion planning problem. More... | |
BGL_Vertex | findVertexDescriptor (Node *N) |
BGL_Edge | findEdgeDescriptor (Edge *E) |
void | saveBGLGraphToDotFile (const std::string &filename) |
BGL_Graph & | get_BGL_Graph () |
void | draw () |
void | resetConnections () |
void | unflagAll () |
unsigned int | getNbScc () |
std::vector< std::vector< Node * > > | getStronglyConnectedComponents () |
std::vector< double > | sortSCC (unsigned int id, Node *N1, bool forward) |
void | addScc (Node *node) |
Adds the singleton {node} to the list of the strongly connected components. More... | |
bool | areSccConnected (unsigned int i, unsigned int j) |
Returns true if in the transitive closure of the graph of the strongly connected components, the strongly connected component (scc) of index i is connected to the scc j. | |
void | connectScc (unsigned int i, unsigned int j) |
Adds an edge in the transitive closure of the graph of the strongly connected components from strongly connected component (scc) of index i to connected to the scc j. More... | |
bool | mergeScc (unsigned int i, unsigned int j) |
Merges strongly connected component (scc) of index i with scc of idex j. More... | |
Static Public Member Functions | |
static void | sortNodesByDist (std::vector< Node * > &nodes, confPtr_t config) |
Compute the K nearest nodes. More... | |
Graph::Graph | ( | const Graph & | G | ) |
Graph copy constructor : be sure that the connected componants are updated.
G | the graph |
void Graph::addCycles | ( | Node * | node, |
double | step | ||
) |
Add an edge to the graph, going from the given source to the given target.
path | local path between the source and the target |
Add two opposite edges between the nodes N1 and N2.
N1 | node already present in the graph and belonging to a connected component |
N2 | new node that has to be linked to an existing node, or existing node that has to be moved to another connected component |
path | local path between N1 and N2 |
void Graph::addNode | ( | Node * | N, |
double | maxDist | ||
) |
void Graph::addNodes | ( | std::vector< Node * > | N, |
double | maxDist | ||
) |
Add the oriented edge N1->N2.
N1 | node |
N2 | node |
path | local path from N1 to N2 |
void Graph::addScc | ( | Node * | node | ) |
Adds the singleton {node} to the list of the strongly connected components.
Updates the the transitive closure of the graph of the strongly connected components.
Function that computes if a node is linked to another node.
Check if two nodes are linked using the collision checking method.
bool Graph::checkAllEdgesValid | ( | ) |
Recompute All Edges Valid.
Check if all edges are valid.
Function that trys to connect a node to a given connected component.
Intempts to connect a node to a compco.
void Graph::connectScc | ( | unsigned int | i, |
unsigned int | j | ||
) |
Adds an edge in the transitive closure of the graph of the strongly connected components from strongly connected component (scc) of index i to connected to the scc j.
Merges components if need be.
void Graph::createCompco | ( | Node * | node | ) |
New Compco.
Create a Compco.
node | to create a compco for |
void Graph::createRandConfs | ( | int | NMAX | ) |
bool Graph::equal | ( | Graph * | G | ) |
bool Graph::equalName | ( | Graph * | G | ) |
Trajectory * Graph::extractAStarShortestPath | ( | Node * | initN, |
Node * | endN | ||
) |
Return a trajectory (i.e. the shortest path) from initN to endN, using A*.
Return a trajectory (i.e.
the shortest path) from initN to endN, using A*.
Trajectory * Graph::extractAStarShortestPath | ( | confPtr_t | initC, |
confPtr_t | endC | ||
) |
Return a trajectory (i.e. the shortest path) from initC to endC, using A*.
Return a trajectory (i.e.
the shortest path) from initC to endC, using A*.
pair< bool, vector< Node * > > Graph::extractBestNodePathSoFar | ( | confPtr_t | qi, |
confPtr_t | qf | ||
) |
Extract best vector of nodes from qi that is closest to q_f.
This function works for tree type of graphs.
Trajectory * Graph::extractTreeShortestPath | ( | Node * | initN, |
Node * | endN | ||
) |
Return a trajectory (i.e. the shortest path) from initN to endN, using parenthood in a tree.
Return a trajectory (i.e.
the shortest path) from initN to endN, using parenthood in a tree.
Node * Graph::getCompco | ( | unsigned int | ith | ) |
Get Ith Compco.
Returns the ith compco.
ConnectedComponent * Graph::getConnectedComponent | ( | int | ith | ) | const |
Get Compco.
Returns a connected component.
vector< Edge * > Graph::getEdges | ( | ) | const |
p3d_graph * Graph::getGraphStruct | ( | ) | const |
Creates a p3d_graph from Boost Graph.
obtient la structure p3d_graph stockée
Node * Graph::getLastNode | ( | ) |
Node* Graph::getNode | ( | node * | N | ) |
vector< Node * > Graph::getNodes | ( | ) | const |
Vector of nodes in the same compco.
Get Nodes in the same compco.
map< p3d_node *, Node * > Graph::getNodesTable | ( | ) |
unsigned int Graph::getNumberOfEdges | ( | ) | const |
unsigned int Graph::getNumberOfNodes | ( | ) |
Robot * Graph::getRobot | ( | ) | const |
void Graph::initMotionPlanning | ( | node * | start, |
node * | goal | ||
) |
Init Motion planning problem.
Replaces p3d_InitRun.
Node * Graph::insertConfigurationAsNode | ( | std::tr1::shared_ptr< Configuration > | q, |
Node * | from, | ||
double | step | ||
) |
Link a Configuration to a Node for the RRT Planner.
q | the Configuration to link |
from | the Node |
Link a Configuration to a Node for the RRT Planner.
Insert node for RRT.
q | the Configuration to link |
expansionNode | the Node |
currentCost | the current cost to reach the Node |
step | the max distance for one step of RRT expansion |
|
inline |
return the value of the Change flag
bool Graph::isInGraph | ( | Node * | N | ) |
vector< Node * > Graph::KNearestWeightNeighbour | ( | confPtr_t | q, |
int | K, | ||
double | radius, | ||
bool | weighted, | ||
int | distConfigChoice | ||
) |
K Nearest Weighted Neighbors in graph.
Return the K Nearest Neighbors of the configuration q in the entire graph within a minimum radius.
bool Graph::linkNode | ( | Node * | N | ) |
Link 2 nodes and merge them.
Link Node and Merge.
bool Graph::linkNodeAtDist | ( | Node * | N | ) |
bool Graph::linkNodeCompMultisol | ( | Node * | N, |
ConnectedComponent * | compPt | ||
) |
Links a node to a compco with multisol.
Copy of p3d_link_node_comp_multisol.
bool Graph::linkNodeWithoutDist | ( | Node * | N | ) |
bool Graph::linkToAllNodes | ( | Node * | newN | ) |
void Graph::mergeCheck | ( | ) |
teste si des composantes connexes doivent être merger et le fait le cas échéant
Detect the need of merging comp.
merge deux composantes connexes
Merge Component.
CompCo1 | la première composante connexe |
CompCo2 | la seconde composante connexe |
DistNodes | la distance entre les deux composantes connexes |
bool Graph::mergeScc | ( | unsigned int | i, |
unsigned int | j | ||
) |
Merges strongly connected component (scc) of index i with scc of idex j.
Updates the the transitive closure of the graph of the strongly connected components.
Node * Graph::nearestWeightNeighbour | ( | Node * | compco, |
confPtr_t | C, | ||
bool | weighted, | ||
int | distConfigChoice | ||
) |
obtient le plus proche voisin d'une composante connexe
Nearest Weighted Neighbour in graph.
compco | la composante connexe dans laquelle on cherche le Node |
C | la Configuration dont on veut determier le plus proche voisin |
weighted | |
distConfigChoice | le type de calcul de distance |
finds the closest node from configuration in the connected component of node compco
Gets Random node in the connected component.
Random Nodes From Component.
void Graph::recomputeCost | ( | ) |
Recompute the Graph cost (Edges and Nodes)
Recompute all node and edge cost.
void Graph::removeCompco | ( | ConnectedComponent * | CompCo | ) |
Delete the compco.
Deletes a connected component.
void Graph::removeEdge | ( | Edge * | E | ) |
Remove edge.
Remove edge from graph.
Remove the edges between the nodes N1 and N2.
Remove the edges between nodes N1 and N2.
Node * Graph::searchConf | ( | Configuration & | q | ) |
Gets the node that corresponds to a configuration.
Search configuration in graph.
q | la Configuration recherchée |
void Graph::setGraph | ( | graph * | G | ) |
stocke la structure p3d_graph
G | la structure à stocker |
void Graph::setName | ( | std::string | Name | ) |
modifie le nom du Graph
Name | le nouveau nom |
void Graph::sortEdges | ( | ) |
trie les Edges en fonction de leur longueur
Sort Edges.
void Graph::sortNodesByDist | ( | Node * | N | ) |
void Graph::sortNodesByDist | ( | confPtr_t | q | ) |
|
static |
Compute the K nearest nodes.
Sort Nodes.
K | the maximal number of neighbors |