Classes | Public Member Functions | Protected Member Functions | Private Attributes
slam::Graph Class Reference

#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 &params)
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

void slam::Graph::addEdge ( int  i,
int  j,
tf::Transform  edge 
)

Add new edge to the graph.

Returns:
Parameters:
Idvertice 1.
Idvertice 2.
Edgetransform that joins both vertices.

Definition at line 197 of file graph.cpp.

Add new vertice into the graph.

Returns:
Parameters:
Lastcorrected odometry pose.
Currentread odometry.
Timestampfor the current odometry.

Definition at line 134 of file graph.cpp.

int slam::Graph::addVertice ( tf::Transform  pose,
tf::Transform  pose_corrected,
double  timestamp 
)

Add new vertice into the graph.

Returns:
Parameters:
Lastestimated pose.
lastcorrected pose.
Timestampfor the current odometry.

Definition at line 180 of file graph.cpp.

void slam::Graph::findClosestNodes ( int  discart_first_n,
int  best_n,
vector< int > &  neighbors 
)

Get the best neighbors by distance.

Returns:
Parameters:
Numberof previous candidates to be discarted
Numberof neighbors to be retrieved.
Willcontain the list of best neighbors by distance.

Definition at line 81 of file graph.cpp.

void slam::Graph::getLastPoses ( tf::Transform  current_odom,
tf::Transform last_graph_pose,
tf::Transform last_graph_odom 
)

Get last poses of the graph.

Returns:
Parameters:
Currentodometry pose used in the case of graph is empty.
Containsthe last graph pose.
Containsthe last odometry pose.

Definition at line 51 of file graph.cpp.

bool slam::Graph::init ( ) [protected]

Init the graph.

Returns:

Definition at line 15 of file graph.cpp.

Params slam::Graph::params ( ) const [inline]
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.

void slam::Graph::setParams ( const Params params) [inline]
Parameters:
paramsnew parameters

Definition at line 58 of file graph.h.

void slam::Graph::setVerticeEstimate ( int  vertice_id,
tf::Transform  pose 
)

Updates som vertice estimate.

Returns:
Parameters:
Idvertice.
Newestimate

Definition at line 219 of file graph.cpp.

Update the graph.

Definition at line 226 of file graph.cpp.


Member Data Documentation

g2o::SparseOptimizer slam::Graph::graph_optimizer_ [private]

> Vector to save the odometry history

Definition at line 109 of file graph.h.

vector< pair<tf::Transform,double> > slam::Graph::odom_history_ [private]

Definition at line 105 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:


stereo_slam
Author(s): Pep Lluis Negre
autogenerated on Thu Aug 27 2015 15:24:22