Defines | Typedefs | Functions
Landmark Position Estimate Consistency Checkers
Implementation
Collaboration diagram for Landmark Position Estimate Consistency Checkers:

Defines

#define VSLAM_REPROJ_ERROR_TOLERANCE   5.0
 max. acceptable reprojection error in consistency checks

Typedefs

typedef ALIGNED
< LandmarkObservation >
::vector 
vslam::lmdetails::LandmarkObservationVec
typedef Model< Vector3d,
LandmarkObservation
vslam::lmdetails::PointFromLandmarkObservationsModel

Functions

template<class G >
bool vslam::lmdetails::consistencyCheck (const G &g, FeatureID< G > f1, FeatureID< G > f2, FeatureID< G > f3, Vector3d &estimate)
 Tests if given three features can be used to create new landmark with these observations.
template<class G >
bool vslam::lmdetails::consistencyCheck (const G &g, const Points< G > &points, FeatureID< G > lmfid, FeatureID< G > nonlmfid, Vector3d &estimate)
 Cheks if a new feature can be used to extend existing landmark.
bool vslam::lmdetails::landmarkObservationSetConsistency (const LandmarkObservationVec &observations1, const LandmarkObservationVec &observations2, const LandmarkObservationVec &all_observations, Vector3d &global_est)
 Tests if given set of features is consistent set of landmark observations (i.e. feature-landmark associations).

Define Documentation

#define VSLAM_REPROJ_ERROR_TOLERANCE   5.0

max. acceptable reprojection error in consistency checks

Definition at line 252 of file landmark_manager.h.


Typedef Documentation

Definition at line 256 of file landmark_manager.h.

Definition at line 258 of file landmark_manager.h.


Function Documentation

template<class G >
bool vslam::lmdetails::consistencyCheck ( const G &  g,
FeatureID< G >  f1,
FeatureID< G >  f2,
FeatureID< G >  f3,
Vector3d &  estimate 
)

Tests if given three features can be used to create new landmark with these observations.

See also:
consistencyCheck(const G&, const Points<G>&, FeatureID<G>, FeatureID<G>, Vector3d&)

Definition at line 328 of file landmark_manager.h.

template<class G >
bool vslam::lmdetails::consistencyCheck ( const G &  g,
const Points< G > &  points,
FeatureID< G >  lmfid,
FeatureID< G >  nonlmfid,
Vector3d &  estimate 
)

Cheks if a new feature can be used to extend existing landmark.

If lmfid is landmark observation and nonlmfid is not, then it is attempted to find an estimate that would make observations of landmark observed form lmfid with added observation nonlmfid consistent.

Note:
lmfid and nonlmfid do not have to be connected by an edge.
Parameters:
[in,out]estimateHint for consistent landmark position estimate, which is updated to consistent estimate computed (as proof of consistency).

Definition at line 352 of file landmark_manager.h.

bool vslam::lmdetails::landmarkObservationSetConsistency ( const LandmarkObservationVec &  observations1,
const LandmarkObservationVec &  observations2,
const LandmarkObservationVec &  all_observations,
Vector3d &  global_est 
) [inline]

Tests if given set of features is consistent set of landmark observations (i.e. feature-landmark associations).

Pairs (a, b) constructed so that a is from `observations1` and b from `observations2` are used for estimation of position of would-be landmark that is used to test if the observations of the would-be landmark are consistent with its position.

Parameters:
in/out]global_est hint for landmark position estimate, which is updated to consistent estimate computed (this is both input and output parameter).
See also:
Model
ModelBuilder
Returns:
sucess status.

Definition at line 276 of file landmark_manager.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


pose_estimation
Author(s): Jiri Divis/jiridivis@gmail.com
autogenerated on Wed Mar 27 2013 21:00:14