Classes | Functions
Edge Builder
Pose-Graph
Collaboration diagram for Edge Builder:

Classes

class  vslam::EdgeBuilder< G >
 Interface for adding edges to the pose-graph. More...
class  vslam::MonoFtrClassEdgeBuilder< G >
 Implementation of EdgeBuilder, where there is only one kind of feature detector-descriptor pair. More...

Functions

static void vslam::MonoFtrClassEdgeBuilder< G >::computeScale (VertexD contactvd, VertexD newvd, G &g, Points< G > &points, SE3 &scaled_T_vbd_vcd)
 Compute scale.
std::tr1::shared_ptr
< RobustFeatureMatcher
vslam::constructRMatcher (std::tr1::shared_ptr< cv::DescriptorMatcher > _dmatcher, std::tr1::shared_ptr< EMatrixModelBuilder > _minbuilder, std::tr1::shared_ptr< EMatrixModelBuilder > _builder)
static void vslam::EdgeBuilder< G >::featureSelection (G &g, VertexD vd, int target_num, vector< int > &keep_idxs, vector< cv::KeyPoint > &sel_keypoints, cv::Mat &sel_descriptors)
 Feature Selection step for Edge Builder.
void vslam::MonoFtrClassEdgeBuilder< G >::guidedMatching (G &g, VertexD c1vd, VertexD c2vd)
 Perform guided matching.
template<class ErrorAccumT >
ErrorAccumT::ErrorT vslam::outlierRemoval (const Matrix3d &E, const ErrorAccumT &ea, const ImageMatchVec &matches_c1c2, const vector< cv::DMatch > &dmatches_c1c2, vector< cv::DMatch > &filtered_matches_c1c2)
 Outlier Removal for image correspondences in 2-view geometry given by an essential matrix.
template<class G >
void vslam::setRelTranslationError (double r_min, double r_max, typename graph_traits< G >::vertex_descriptor vs, typename graph_traits< G >::vertex_descriptor vt, G &g)
bool vslam::MonoFtrClassEdgeBuilder< G >::unguidedMatching (const vector< cv::KeyPoint > &sel_tvd_keypoints, const vector< cv::KeyPoint > &sel_qvd_keypoints, const cv::Mat &sel_tvd_descriptors, const cv::Mat &sel_qvd_descriptors, SE3 &T_tvd_qvd, std::vector< cv::DMatch > &global_dmatches_c1c2)
 Unguided Matching and Robust Model Estimations steps for Edge Builder.

Deprecated functions.

Deprecated:
Old version of computing scale and finding new landmarks. Use MonoFtrClassEdgeBuilder::computeScale and findNewLandmarks instead.
static void vslam::MonoFtrClassEdgeBuilder< G >::compute3viewStructure (VertexD vad, VertexD vbd, VertexD vcd, G &g, IdxPoint3dVec &, SE3 &)
 Compute scale and common points for two edges.
static void vslam::MonoFtrClassEdgeBuilder< G >::matchScaleFindNewLandmarks (VertexD vsrc, VertexD vdest, Points< G > &points, G &g)
 Match scale for the new edge with the rest of the graph and find new landmarks.

Function Documentation

template<class G >
void vslam::MonoFtrClassEdgeBuilder< G >::compute3viewStructure ( VertexD  vad,
VertexD  vbd,
VertexD  vcd,
G &  g,
IdxPoint3dVec common_pts_3d,
SE3 &  scaled_T_vbd_vcd 
) [static, protected]

Compute scale and common points for two edges.

For two edges sharing a vertex, compute feature track spanning both two edges. The tracks are represented as triangulated points and their indexes w.r.t. the c1 coordinate farme (i.e. vbd vertex).

Todo:
to be removed.

scaled_T_vbd_vcd SE3 transform with corrected scale as determined by common points with edge (vad, vbd).

Definition at line 280 of file graph_builder.h.

template<class G >
void vslam::MonoFtrClassEdgeBuilder< G >::computeScale ( VertexD  convd,
VertexD  newvd,
G &  g,
Points< G > &  points,
SE3 &  scaled_T_vbd_vcd 
) [static, protected]

Compute scale.

Todo:
document.
Parameters:
in/out]scaled_T_vbd_vcd SE3 transform with corrected scale as determined by feature tracks that are common with edge $(vad, vbd)$.
Todo:
force positive depth

Definition at line 409 of file graph_builder.h.

std::tr1::shared_ptr< RobustFeatureMatcher > vslam::constructRMatcher ( std::tr1::shared_ptr< cv::DescriptorMatcher >  _dmatcher,
std::tr1::shared_ptr< EMatrixModelBuilder _minbuilder,
std::tr1::shared_ptr< EMatrixModelBuilder _builder 
) [inline]

Definition at line 741 of file graph_builder.h.

template<class G >
void vslam::EdgeBuilder< G >::featureSelection ( G &  g,
VertexD  vd,
int  target_num,
vector< int > &  keep_idxs,
vector< cv::KeyPoint > &  sel_keypoints,
cv::Mat &  sel_descriptors 
) [static, protected]

Feature Selection step for Edge Builder.

Selects approximately target_num features eavenly spread across the imaging surface.

Precondition:
vertex_kp and vertex_desc properties of the graph g are initialized correctly with detected keypoints. KeyPoint data structures in sel_keypoints have to have response parameter set.
Parameters:
[out]keep_idxsindexes of selected features in node vd.
[out]sel_keypointsarray of cv::KeyPoint coresponding to the selected features in order given by keep_idxs.
[out]sel_descriptorssame as sel_keypoints for cv::Mat feature descriptors.

Definition at line 517 of file graph_builder.h.

template<class G >
void vslam::MonoFtrClassEdgeBuilder< G >::guidedMatching ( G &  g,
VertexD  qvd,
VertexD  tvd 
) [protected]

Perform guided matching.

Performs guided matching by using vslam::findLocalMatches. The matches are then searched for outliers. Non-outlier matches that are not already in the feature-feature matches of edge '(qvd, tvd)', are then added.

Precondition:
see vslam::findLocalMatches
Todo:
unify errors under one variable as was done in rmatcher.

Definition at line 616 of file graph_builder.h.

template<class G >
void vslam::MonoFtrClassEdgeBuilder< G >::matchScaleFindNewLandmarks ( VertexD  vsrc,
VertexD  vdest,
Points< G > &  points,
G &  g 
) [static, protected]

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 $(vsrc, vdest)$ is computed based on an edge connecting one of $vsrc$ and $vdest$ to the rest of the graph.

Second, new landmarks are created. New landmark is created if there exist two feature-feature matches sharing vsrc vertex, which are geometrically consistent and none of the vertices involved in the feature-feature matches is part of any existing landmark.

$vsrc$ and $vdest$ are not interchangable. If the edge connects unconnected vertex with the rest * of the graph, the unconnected vertex is passed as vdest and this method is called only once. Othervise it has to be called for both $(vsrc, vdest)$ and $(vdest, vsrc)$ edges.

Definition at line 342 of file graph_builder.h.

template<class ErrorAccumT >
ErrorAccumT::ErrorT vslam::outlierRemoval ( const Matrix3d &  E,
const ErrorAccumT &  ea,
const ImageMatchVec matches_c1c2,
const vector< cv::DMatch > &  dmatches_c1c2,
vector< cv::DMatch > &  filtered_matches_c1c2 
)

Outlier Removal for image correspondences in 2-view geometry given by an essential matrix.

Parameters:
Eessential matrix (c1 to c2).
eaErrorAccumulator implementation (determines which data are outliers).
matches_c1c2image coordinates of matches from c1 to c2.
dmatches_c1c2feature index pairs corresponding to 'matches_c1c2'.
[out]filtered_matches_c1c2inlier feature index pairs from 'dmatches_c1c2'
Returns:
model error as determined by 'ea'.

Definition at line 585 of file graph_builder.h.

template<class G >
void vslam::setRelTranslationError ( double  r_min,
double  r_max,
typename graph_traits< G >::vertex_descriptor  vs,
typename graph_traits< G >::vertex_descriptor  vt,
G &  g 
)

Definition at line 249 of file graph_builder.h.

template<class G >
bool vslam::MonoFtrClassEdgeBuilder< G >::unguidedMatching ( const vector< cv::KeyPoint > &  sel_tvd_keypoints,
const vector< cv::KeyPoint > &  sel_qvd_keypoints,
const cv::Mat &  sel_tvd_descriptors,
const cv::Mat &  sel_qvd_descriptors,
SE3 &  T_tvd_qvd,
std::vector< cv::DMatch > &  global_dmatches_c1c2 
) [protected]

Unguided Matching and Robust Model Estimations steps for Edge Builder.

Parameters:
sel_tvd_keypointstarget vertex keypoints array.
sel_qvd_keypointsquery vertex keypoints array.
sel_tvd_descriptorstarget vertex feature descriptors array.
sel_qvd_descriptorsquery vertex feature descriptors array.
[out]T_tvd_qvdRBT from target vertex CF to query vertex CF with undefined scale.
[out]global_dmatches_c1c2computed matches.
Returns:
true if T_tvd_qvd contains valid value and false othervise.

Definition at line 547 of file graph_builder.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