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

#include <graph.h>

List of all members.

Public Member Functions

void addEdge (int i, int j, tf::Transform edge, int sigma)
 Add an edge to the graph.
void addFrameToQueue (Frame frame)
 Add a frame to the queue of frames to be inserted into the graph as vertices.
void findClosestVertices (int vertex_id, int window_center, int window, int best_n, vector< int > &neighbors)
 Get the closest neighbors by distance.
cv::Mat getCameraMatrix () const
 Get camera matrix.
image_geometry::PinholeCameraModel getCameraModel () const
 Get camera model.
int getFrameNum () const
 Get camera matrix.
bool getFramePose (int frame_id, tf::Transform &frame_pose)
 Get frame pose.
void getFrameVertices (int frame_id, vector< int > &vertices)
 Retrieve the list of the vertices of a corresponding frame.
int getLastVertexFrameId ()
 Get the last vertex frame id.
tf::Transform getVertexCameraPose (int id, bool lock=true)
 Get the camera pose of some specific vertex.
int getVertexFrameId (int id)
 Get the frame id of some specific vertex.
tf::Transform getVertexPose (int vertex_id, bool lock=true)
 Get the graph vertex pose.
tf::Transform getVertexPoseRelativeToCamera (int id)
 Get the graph vertex pose relative to camera.
 Graph (LoopClosing *loop_closing)
 Class constructor.
void init ()
 Initialize the graph.
void run ()
 Starts graph.
void saveGraph ()
 Save the graph to file.
void setCamera2Odom (const tf::Transform &camera2odom)
 Set the transformation between camera and robot odometry frame.
void setCameraMatrix (const cv::Mat &camera_matrix)
 Set camera matrix.
void setCameraModel (const image_geometry::PinholeCameraModel &camera_model)
 Set camera model.
void update ()
 Optimize the graph.

Protected Member Functions

int addVertex (tf::Transform pose)
 Add a vertex to the graph.
bool checkNewFrameInQueue ()
 Check if there are frames in the queue to be inserted into the graph.
tf::Transform correctClusterPose (tf::Transform initial_pose)
 Correct a cluster pose with the information of the updated graph.
vector< vector< int > > createComb (vector< int > cluster_ids)
 Return all possible combinations of 2 elements of the input vector.
void processNewFrame ()
 Converts the frame to a graph vertex and adds it to the graph.
void publishCameraPose (tf::Transform camera_pose)
 Publishes the graph camera pose.
void publishGraph ()
 Publishes all the graph.
void saveFrame (Frame frame, bool draw_clusters=false)
 Save the frame to the default location.

Private Attributes

tf::Transform camera2odom_
 > Mutex for the insertion of new frames into the graph
cv::Mat camera_matrix_
 > Loop closing
image_geometry::PinholeCameraModel camera_model_
 > The camera matrix
vector< pair< int, int > > cluster_frame_relation_
 > Processed frames counter
int frame_id_
 > Frames queue to be inserted into the graph
list< Frameframe_queue_
 > G2O graph optimizer
vector< double > frame_stamps_
 > Stores the initial cluster poses, before graph update.
g2o::SparseOptimizer graph_optimizer_
ros::Publisher graph_pub_
 > Camera pose publisher
vector< tf::Transforminitial_cluster_pose_history_
 > Stores the cluster poses relative to camera frame
vector< tf::Transformlocal_cluster_poses_
 > Stores the cluster/frame relation (cluster_id, frame_id)
LoopClosingloop_closing_
 > Transformation between camera and robot odometry frame
mutex mutex_frame_queue_
 > Mutex for the graph manipulation
mutex mutex_graph_
ros::Publisher pose_pub_
 > Pinhole left camera model

Detailed Description

Definition at line 40 of file graph.h.


Constructor & Destructor Documentation

slam::Graph::Graph ( LoopClosing loop_closing)

Class constructor.

Parameters:
Loopclosing object pointer

Definition at line 11 of file graph.cpp.


Member Function Documentation

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

Add an edge to the graph.

Parameters:
Indexof vertex 1
Indexof vertex 2
Transformationbetween vertices
Sigmainformation

Definition at line 273 of file graph.cpp.

Add a frame to the queue of frames to be inserted into the graph as vertices.

Parameters:
Theframe to be inserted

Definition at line 50 of file graph.cpp.

int slam::Graph::addVertex ( tf::Transform  pose) [protected]

Add a vertex to the graph.

Returns:
the vertex id
Parameters:
Vertexpose

Definition at line 250 of file graph.cpp.

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

Check if there are frames in the queue to be inserted into the graph.

Returns:
true if frames queue is not empty.

Definition at line 56 of file graph.cpp.

Correct a cluster pose with the information of the updated graph.

Returns:
the corrected pose
Parameters:
Thepose to be corrected

Definition at line 209 of file graph.cpp.

vector< vector< int > > slam::Graph::createComb ( vector< int >  cluster_ids) [protected]

Return all possible combinations of 2 elements of the input vector.

Returns:
the list of combinations
Parameters:
Inputvector with all values

Definition at line 231 of file graph.cpp.

void slam::Graph::findClosestVertices ( int  vertex_id,
int  window_center,
int  window,
int  best_n,
vector< int > &  neighbors 
)

Get the closest neighbors by distance.

Parameters:
Thevertex id to retrieve its neighbors
Thevertex where discard window will be centered.
Windowsize of discarded vertices.
Numberof neighbors to be retrieved.
Willcontain the list of best neighbors by distance.

Definition at line 308 of file graph.cpp.

cv::Mat slam::Graph::getCameraMatrix ( ) const [inline]

Get camera matrix.

Definition at line 144 of file graph.h.

Get camera model.

Definition at line 153 of file graph.h.

int slam::Graph::getFrameNum ( ) const [inline]

Get camera matrix.

Definition at line 157 of file graph.h.

bool slam::Graph::getFramePose ( int  frame_id,
tf::Transform frame_pose 
)

Get frame pose.

Returns:
true if frame pose can be extracted, false otherwise
Parameters:
frameid
outputgraph frame pose

Definition at line 412 of file graph.cpp.

void slam::Graph::getFrameVertices ( int  frame_id,
vector< int > &  vertices 
)

Retrieve the list of the vertices of a corresponding frame.

Parameters:
Theframe id
Willcontain the list of vertices for this frame.

Definition at line 341 of file graph.cpp.

Get the last vertex frame id.

Returns:
the frame id

Definition at line 365 of file graph.cpp.

tf::Transform slam::Graph::getVertexCameraPose ( int  id,
bool  lock = true 
)

Get the camera pose of some specific vertex.

Returns:
graph vertex camera pose
Parameters:
vertexid
trueto lock the graph

Definition at line 434 of file graph.cpp.

Get the frame id of some specific vertex.

Returns:
the frame id
Parameters:
vertexid

Definition at line 351 of file graph.cpp.

tf::Transform slam::Graph::getVertexPose ( int  vertex_id,
bool  lock = true 
)

Get the graph vertex pose.

Returns:
graph vertex pose
Parameters:
vertexid
setto true to lock the graph

Definition at line 378 of file graph.cpp.

Get the graph vertex pose relative to camera.

Returns:
graph vertex pose relative to camera
Parameters:
vertexid

Definition at line 429 of file graph.cpp.

Initialize the graph.

Definition at line 16 of file graph.cpp.

void slam::Graph::processNewFrame ( ) [protected]

Converts the frame to a graph vertex and adds it to the graph.

Definition at line 62 of file graph.cpp.

void slam::Graph::publishCameraPose ( tf::Transform  camera_pose) [protected]

Publishes the graph camera pose.

Parameters:
Camerapose

Definition at line 575 of file graph.cpp.

void slam::Graph::publishGraph ( ) [protected]

Publishes all the graph.

Definition at line 586 of file graph.cpp.

void slam::Graph::run ( )

Starts graph.

Definition at line 37 of file graph.cpp.

void slam::Graph::saveFrame ( Frame  frame,
bool  draw_clusters = false 
) [protected]

Save the frame to the default location.

Parameters:
theframe to be drawn
trueto draw the clusters over the frame

Definition at line 440 of file graph.cpp.

Save the graph to file.

Definition at line 467 of file graph.cpp.

void slam::Graph::setCamera2Odom ( const tf::Transform camera2odom) [inline]

Set the transformation between camera and robot odometry frame.

Parameters:
thetransform

Definition at line 135 of file graph.h.

void slam::Graph::setCameraMatrix ( const cv::Mat &  camera_matrix) [inline]

Set camera matrix.

Parameters:
cameramatrix

Definition at line 140 of file graph.h.

void slam::Graph::setCameraModel ( const image_geometry::PinholeCameraModel camera_model) [inline]

Set camera model.

Parameters:
cameramatrix

Definition at line 149 of file graph.h.

Optimize the graph.

Definition at line 297 of file graph.cpp.


Member Data Documentation

> Mutex for the insertion of new frames into the graph

Definition at line 223 of file graph.h.

cv::Mat slam::Graph::camera_matrix_ [private]

> Loop closing

Definition at line 227 of file graph.h.

> The camera matrix

Definition at line 229 of file graph.h.

vector< pair< int,int > > slam::Graph::cluster_frame_relation_ [private]

> Processed frames counter

Definition at line 211 of file graph.h.

int slam::Graph::frame_id_ [private]

> Frames queue to be inserted into the graph

Definition at line 209 of file graph.h.

> G2O graph optimizer

Definition at line 207 of file graph.h.

vector<double> slam::Graph::frame_stamps_ [private]

> Stores the initial cluster poses, before graph update.

Definition at line 217 of file graph.h.

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

Definition at line 205 of file graph.h.

> Camera pose publisher

Definition at line 233 of file graph.h.

> Stores the cluster poses relative to camera frame

Definition at line 215 of file graph.h.

> Stores the cluster/frame relation (cluster_id, frame_id)

Definition at line 213 of file graph.h.

> Transformation between camera and robot odometry frame

Definition at line 225 of file graph.h.

> Mutex for the graph manipulation

Definition at line 221 of file graph.h.

mutex slam::Graph::mutex_graph_ [private]

Definition at line 219 of file graph.h.

> Pinhole left camera model

Definition at line 231 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 Jul 14 2016 04:09:13