Classes | Public Member Functions | Private Member Functions | Private Attributes
haloc::LoopClosure Class Reference

#include <lc.h>

List of all members.

Classes

struct  Params

Public Member Functions

void finalize ()
 Finalizes the loop closure class.
void getCandidates (vector< pair< int, float > > &candidates)
 Get the best n_candidates to close loop with the last image.
void getCandidates (int image_id, vector< pair< int, float > > &candidates)
 Get the best n_candidates to close loop with the image specified by id.
bool getHash (int img_id, vector< float > &hash)
 Returns the hash for a some specific image id.
bool getLoopClosure (int &lc_img_id)
 Try to find a loop closure between last node and all other nodes.
bool getLoopClosure (int &lc_img_id, tf::Transform &trans)
 Try to find a loop closure between last node and all other nodes.
bool getLoopClosure (int img_id_a, int img_id_b, tf::Transform &trans, bool logging=false)
 Compute the loop closure (if any) between A -> B.
bool getLoopClosure (int img_id_a, int img_id_b, tf::Transform &trans, int &matches, int &inliers, bool logging=false)
 Compute the loop closure (if any) between A -> B.
bool hashMatching (int img_id_a, int img_id_b, float &matching)
 Computes the hash matching between 2 images.
void init ()
 Initializes the loop closure class.
 LoopClosure ()
 LoopClosure class constructor.
Params params () const
void setCameraModel (image_geometry::StereoCameraModel stereo_camera_model, cv::Mat camera_matrix)
 Sets the camera model.
int setNode (cv::Mat img)
int setNode (cv::Mat img_l, cv::Mat img_r)
void setParams (const Params &params)
 Sets the class parameters.

Private Member Functions

void buildLikelihoodVector (vector< pair< int, float > > hash_matchings, vector< pair< int, float > > &likelihood)
 Compute the likelihood vectors given a certain hash matching set.
bool compute (Image query, Image candidate, int &matches, int &inliers, tf::Transform &trans)
 Compute the loop closure (if any).
void getBestMatchings (int image_id, int best_n, vector< pair< int, float > > &best_matchings)
 Retrieve the best n matchings give a certain image id.
Image getImage (string img_file)
 Get the image information from file.
void getMatchingsLikelihood (vector< pair< int, float > > matchings, vector< float > &matchings_likelihood, vector< pair< int, float > > cur_likelihood, vector< pair< int, float > > prev_likelihood)
 Given a vector of matches and the current and previous likelihood vectors, returns the likelihood for these matches.
void groupSimilarImages (vector< pair< int, float > > matchings, vector< vector< int > > &groups)
 Group the matchings by images with similar id.

Private Attributes

cv::Mat camera_matrix_
 > Incremental index for the stored images
Hash hash_
 > Query image object
vector< pair< int, vector
< float > > > 
hash_table_
 > Used to save the camera matrix
int img_id_
 > Hash object
vector< int > lc_candidate_positions_
 > Hash table
vector< pair< int, int > > lc_found_
 > Stores the previous likelihood vector
Params params_
vector< pair< int, float > > prev_likelihood_
 > Loop closure candidate positions
Image query_
 > Stores parameters

Detailed Description

Definition at line 16 of file lc.h.


Constructor & Destructor Documentation

LoopClosure class constructor.

Definition at line 45 of file lc.cpp.


Member Function Documentation

void haloc::LoopClosure::buildLikelihoodVector ( vector< pair< int, float > >  hash_matchings,
vector< pair< int, float > > &  likelihood 
) [private]

Compute the likelihood vectors given a certain hash matching set.

Parameters:
Hashmatching vector in the format <image_id, distance>.
Storesthe likelihood in the format <image_id, probability>.

Definition at line 661 of file lc.cpp.

bool haloc::LoopClosure::compute ( Image  query,
Image  candidate,
int &  matches,
int &  inliers,
tf::Transform trans 
) [private]

Compute the loop closure (if any).

Returns:
true if valid loop closure, false otherwise.
Parameters:
Queryimage object.
Candidateimage object.
Returnthe number of matches found.
Returnthe number of inliers found.
Returnthe transform between nodes if loop closure is valid.

Definition at line 498 of file lc.cpp.

Finalizes the loop closure class.

Definition at line 135 of file lc.cpp.

void haloc::LoopClosure::getBestMatchings ( int  image_id,
int  best_n,
vector< pair< int, float > > &  best_matchings 
) [private]

Retrieve the best n matchings give a certain image id.

Parameters:
Queryimage id.
Numberof best matches to retrieve.
Storesbest n matchings in a vector of pairs <image_id, distance>.

Definition at line 612 of file lc.cpp.

void haloc::LoopClosure::getCandidates ( vector< pair< int, float > > &  candidates)

Get the best n_candidates to close loop with the last image.

Returns:
a hash matching vector containing the best image candidates and its likelihood.

Definition at line 264 of file lc.cpp.

void haloc::LoopClosure::getCandidates ( int  image_id,
vector< pair< int, float > > &  candidates 
)

Get the best n_candidates to close loop with the image specified by id.

Returns:
a hash matching vector containing the best image candidates and its likelihood.
Parameters:
imageid.

Definition at line 273 of file lc.cpp.

bool haloc::LoopClosure::getHash ( int  img_id,
vector< float > &  hash 
)

Returns the hash for a some specific image id.

Returns:
true if hash found
Parameters:
theimage id.
thereturning hash.

Definition at line 231 of file lc.cpp.

haloc::Image haloc::LoopClosure::getImage ( string  img_file) [private]

Get the image information from file.

Returns:
the image object.
Parameters:
imagefilename

Definition at line 833 of file lc.cpp.

bool haloc::LoopClosure::getLoopClosure ( int &  lc_img_id)

Try to find a loop closure between last node and all other nodes.

Returns:
true if valid loop closure, false otherwise.
Parameters:
Returnthe index of the image that closes loop (-1 if no loop).

Definition at line 340 of file lc.cpp.

bool haloc::LoopClosure::getLoopClosure ( int &  lc_img_id,
tf::Transform trans 
)

Try to find a loop closure between last node and all other nodes.

Returns:
true if valid loop closure, false otherwise.
Parameters:
Returnthe index of the image that closes loop (-1 if no loop).
Returnthe transform between nodes if loop closure is valid.

Definition at line 351 of file lc.cpp.

bool haloc::LoopClosure::getLoopClosure ( int  img_id_a,
int  img_id_b,
tf::Transform trans,
bool  logging = false 
)

Compute the loop closure (if any) between A -> B.

Returns:
true if valid loop closure, false otherwise.
Parameters:
referenceimage id.
currentimage id.
Returnthe transform between nodes if loop closure is valid.
Showoutput log or not.

Definition at line 481 of file lc.cpp.

bool haloc::LoopClosure::getLoopClosure ( int  img_id_a,
int  img_id_b,
tf::Transform trans,
int &  matches,
int &  inliers,
bool  logging = false 
)

Compute the loop closure (if any) between A -> B.

Returns:
true if valid loop closure, false otherwise.
Parameters:
referenceimage id.
currentimage id.
Returnthe transform between nodes if loop closure is valid.
Showoutput log or not.
Thenumber of matches
Thenumber of inliers

Definition at line 430 of file lc.cpp.

void haloc::LoopClosure::getMatchingsLikelihood ( vector< pair< int, float > >  matchings,
vector< float > &  matchings_likelihood,
vector< pair< int, float > >  cur_likelihood,
vector< pair< int, float > >  prev_likelihood 
) [private]

Given a vector of matches and the current and previous likelihood vectors, returns the likelihood for these matches.

Parameters:
Hashmatching vector in the format <image_id, distance>.
Storesthe likelihood for the given matching vectors
Currentvector of likelihood in the format <image_id, probability>.
Previousvector of likelihood in the format <image_id, probability>.

Definition at line 716 of file lc.cpp.

void haloc::LoopClosure::groupSimilarImages ( vector< pair< int, float > >  matchings,
vector< vector< int > > &  groups 
) [private]

Group the matchings by images with similar id.

Parameters:
Hashmatching vector in the format <image_id, distance>.
Storesgroups of images

Definition at line 770 of file lc.cpp.

bool haloc::LoopClosure::hashMatching ( int  img_id_a,
int  img_id_b,
float &  matching 
)

Computes the hash matching between 2 images.

Returns:
true if hashes found
Parameters:
theimage id a.
theimage id b.
thereturning hash matching.

Definition at line 251 of file lc.cpp.

Initializes the loop closure class.

Definition at line 88 of file lc.cpp.

Params haloc::LoopClosure::params ( ) const [inline]

Definition at line 64 of file lc.h.

void haloc::LoopClosure::setCameraModel ( image_geometry::StereoCameraModel  stereo_camera_model,
cv::Mat  camera_matrix 
)

Sets the camera model.

Parameters:
Stereocamera model.

Definition at line 79 of file lc.cpp.

int haloc::LoopClosure::setNode ( cv::Mat  img)
int haloc::LoopClosure::setNode ( cv::Mat  img_l,
cv::Mat  img_r 
)
void haloc::LoopClosure::setParams ( const Params params)

Sets the class parameters.

Parameters:
stuctof parameters.

Definition at line 50 of file lc.cpp.


Member Data Documentation

> Incremental index for the stored images

Definition at line 151 of file lc.h.

> Query image object

Definition at line 149 of file lc.h.

vector< pair<int, vector<float> > > haloc::LoopClosure::hash_table_ [private]

> Used to save the camera matrix

Definition at line 152 of file lc.h.

> Hash object

Definition at line 150 of file lc.h.

> Hash table

Definition at line 153 of file lc.h.

vector< pair<int, int > > haloc::LoopClosure::lc_found_ [private]

> Stores the previous likelihood vector

Definition at line 155 of file lc.h.

Definition at line 147 of file lc.h.

vector< pair<int,float> > haloc::LoopClosure::prev_likelihood_ [private]

> Loop closure candidate positions

Definition at line 154 of file lc.h.

> Stores parameters

Definition at line 148 of file lc.h.


The documentation for this class was generated from the following files:


libhaloc
Author(s): Pep Lluis Negre
autogenerated on Thu Feb 11 2016 23:22:48