#include <graph.h>
List of all members.
Classes |
struct | Params |
Public Member Functions |
void | addEdge (int i, int j, tf::Transform edge) |
| Add new edge to the graph.
|
int | addVertice (tf::Transform pose_corrected) |
| Add new vertice into the graph.
|
int | addVertice (tf::Transform pose, tf::Transform pose_corrected, double timestamp) |
| Add new vertice into the graph.
|
void | findClosestNodes (int discart_first_n, int best_n, vector< int > &neighbors) |
| Get the best neighbors by distance.
|
void | getLastPoses (tf::Transform current_odom, tf::Transform &last_graph_pose, tf::Transform &last_graph_odom) |
| Get last poses of the graph.
|
| Graph () |
| Class constructor. Reads node parameters and initialize some properties.
|
Params | params () const |
bool | saveGraphToFile () |
| Save the optimized graph into a file with the same format than odometry_msgs.
|
void | setParams (const Params ¶ms) |
void | setVerticeEstimate (int vertice_id, tf::Transform pose) |
| Updates som vertice estimate.
|
void | update () |
| Update the graph.
|
Protected Member Functions |
bool | init () |
| Init the graph.
|
Private Attributes |
g2o::SparseOptimizer | graph_optimizer_ |
| > Vector to save the odometry history
|
vector< pair< tf::Transform,
double > > | odom_history_ |
Params | params_ |
| > G2O graph optimizer
|
Detailed Description
Definition at line 29 of file graph.h.
Constructor & Destructor Documentation
Class constructor. Reads node parameters and initialize some properties.
- Returns:
Definition at line 7 of file graph.cpp.
Member Function Documentation
Add new edge to the graph.
- Returns:
- Parameters:
-
Id | vertice 1. |
Id | vertice 2. |
Edge | transform that joins both vertices. |
Definition at line 197 of file graph.cpp.
Add new vertice into the graph.
- Returns:
- Parameters:
-
Last | corrected odometry pose. |
Current | read odometry. |
Timestamp | for the current odometry. |
Definition at line 134 of file graph.cpp.
Add new vertice into the graph.
- Returns:
- Parameters:
-
Last | estimated pose. |
last | corrected pose. |
Timestamp | for the current odometry. |
Definition at line 180 of file graph.cpp.
Get the best neighbors by distance.
- Returns:
- Parameters:
-
Number | of previous candidates to be discarted |
Number | of neighbors to be retrieved. |
Will | contain the list of best neighbors by distance. |
Definition at line 81 of file graph.cpp.
Get last poses of the graph.
- Returns:
- Parameters:
-
Current | odometry pose used in the case of graph is empty. |
Contains | the last graph pose. |
Contains | the last odometry pose. |
Definition at line 51 of file graph.cpp.
Init the graph.
- Returns:
Definition at line 15 of file graph.cpp.
- Returns:
- current parameters
Definition at line 67 of file graph.h.
Save the optimized graph into a file with the same format than odometry_msgs.
- Returns:
Definition at line 236 of file graph.cpp.
- Parameters:
-
Definition at line 58 of file graph.h.
Updates som vertice estimate.
- Returns:
- Parameters:
-
Definition at line 219 of file graph.cpp.
Member Data Documentation
> Vector to save the odometry history
Definition at line 109 of file graph.h.
> G2O graph optimizer
Definition at line 112 of file graph.h.
The documentation for this class was generated from the following files: