Interface to the Landmark Manager module. More...
Classes | |
struct | vslam::Point< G > |
Representation of a landmark. More... | |
class | vslam::Points< G > |
Functions | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void | vslam::Points< G >::activateLandmarks (const G &g, typename graph_traits< G >::vertex_descriptor v, int keep_num) |
Marks best landmarks that are visible from given keyframe as optimalizable. | |
void | vslam::Points< G >::deleteLmObs (G &g, const FeatureID< G > &obs) |
Deletes observation of a landmark. | |
template<class G > | |
void | vslam::extendLandmarks (typename graph_traits< G >::vertex_descriptor convd, typename graph_traits< G >::vertex_descriptor newvd, Points< G > &points, G &g) |
Extends existing feature tracks. | |
template<class G > | |
void | vslam::findNewLandmarks (typename graph_traits< G >::vertex_descriptor convd, typename graph_traits< G >::vertex_descriptor newvd, Points< G > &points, G &g) |
Match scale for the new edge with the rest of the graph and find new landmarks. | |
bool | vslam::Points< G >::fixNewLandmark (FeatureID< G > fa, FeatureID< G > fm, FeatureID< G > fb, G &g) |
Attempts to create new landmark from set of three features. | |
bool | vslam::Points< G >::fixNewObservation (FeatureID< G > fa, FeatureID< G > fb, G &g) |
Attempts to add given feature as a new landmark observation. | |
const Point< G > & | vslam::Points< G >::getPoint (int idx) const |
Get landmark data. | |
void | vslam::Points< G >::lmEstimateUpd (int lm_id, Vector3d &new_estimate) |
Update of position estimate of a landmark. | |
void | vslam::Points< G >::lmEstimateUpdChecked (int lm_id, Vector3d &new_estimate) |
Checked update of position estimate of a landmark. | |
int | vslam::Points< G >::size () const |
Returns total number of landmarks. |
Interface to the Landmark Manager module.
void vslam::Points< G >::activateLandmarks | ( | const G & | g, |
typename graph_traits< G >::vertex_descriptor | v, | ||
int | keep_num | ||
) |
Marks best landmarks that are visible from given keyframe as optimalizable.
Makes up to 'keep_num' best landmarks visible from 'v' optimalizable.
Definition at line 401 of file landmark_manager.h.
void vslam::Points< G >::deleteLmObs | ( | G & | g, |
const FeatureID< G > & | obs | ||
) |
Deletes observation of a landmark.
Definition at line 437 of file landmark_manager.h.
void vslam::extendLandmarks | ( | typename graph_traits< G >::vertex_descriptor | convd, |
typename graph_traits< G >::vertex_descriptor | newvd, | ||
Points< G > & | points, | ||
G & | g | ||
) |
Extends existing feature tracks.
Adds a feature to a landmark, iff there exists feature-feature match where one of the features is in the landmark and the other is in the vertex newvd and is geometrically consistent.
Definition at line 616 of file landmark_manager.h.
void vslam::findNewLandmarks | ( | typename graph_traits< G >::vertex_descriptor | convd, |
typename graph_traits< G >::vertex_descriptor | newvd, | ||
Points< G > & | points, | ||
G & | g | ||
) |
Match scale for the new edge with the rest of the graph and find new landmarks.
The function does two things. First, scale of the edge is computed based on an edge connecting one of and to the rest of the graph.
Second, new landmarks are created. New landmark is created if there exist two feature-feature matches sharing convd vertex, which are geometrically consistent and none of the vertices involved in the feature-feature matches is part of any existing landmark.
and are not interchangable. If the edge connects unconnected vertex with the rest * of the graph, the unconnected vertex is passed as newvd and this method is called only once. Othervise it has to be called for both and edges.
Definition at line 566 of file landmark_manager.h.
bool vslam::Points< G >::fixNewLandmark | ( | FeatureID< G > | fa, |
FeatureID< G > | fm, | ||
FeatureID< G > | fb, | ||
G & | g | ||
) |
Attempts to create new landmark from set of three features.
In order for the new landmark to be created, the following must hold:
Definition at line 483 of file landmark_manager.h.
bool vslam::Points< G >::fixNewObservation | ( | FeatureID< G > | fa, |
FeatureID< G > | fb, | ||
G & | g | ||
) |
Attempts to add given feature as a new landmark observation.
In order for it to be done, the following must hold:
Definition at line 518 of file landmark_manager.h.
const Point< G > & vslam::Points< G >::getPoint | ( | int | idx | ) | const |
Get landmark data.
Definition at line 410 of file landmark_manager.h.
void vslam::Points< G >::lmEstimateUpd | ( | int | lm_id, |
Vector3d & | new_estimate | ||
) |
Update of position estimate of a landmark.
Definition at line 416 of file landmark_manager.h.
void vslam::Points< G >::lmEstimateUpdChecked | ( | int | lm_id, |
Vector3d & | new_estimate | ||
) |
Checked update of position estimate of a landmark.
Updates position of landmark 'lm_id' and chceks that the estimate is consistent with all landmark observations. If this is not the cas ROS warning message is issued.
Definition at line 426 of file landmark_manager.h.
int vslam::Points< G >::size | ( | ) | const |
Returns total number of landmarks.
Definition at line 469 of file landmark_manager.h.