Set of utilities useful across multiple modules that operate on pose-graph. More...
Functions | |
template<class G > | |
Vector2d | vslam::getFeaturePixel (const G &g, const FeatureID< G > f) |
Returns pixel coordinates of a feature. | |
template<class G > | |
void | vslam::landmarkObservationsBySize (const G &g, Points< G > &points, typename graph_traits< G >::vertex_descriptor vd, vector< vector< int > > &all_result, vector< vector< int > > &kf_result) |
template<class G > | |
double | vslam::maxFeatureDistance (const G &g, const Points< G > &points, typename Point< G >::VertexD v) |
template<class G > | |
std::string | vslam::printVertexId (const G &g, typename graph_traits< G >::vertex_descriptor vd) |
returns human-readable vertex-id as string. | |
Feature manipulation utils | |
| |
template<class G > | |
int | vslam::getFeatureIdx (const G &g, int source_idx, typename graph_traits< G >::vertex_descriptor source_vd, typename graph_traits< G >::vertex_descriptor target_vd) |
template<class G > | |
int | vslam::getFeatureIdx (const G &g, FeatureID< G > srcf, typename graph_traits< G >::vertex_descriptor target_vd) |
get feature index in the target pose... | |
template<typename G > | |
void | vslam::remove_idx_pair (int sidx, typename graph_traits< G >::vertex_descriptor src, typename graph_traits< G >::vertex_descriptor dest, G &g) |
delete feature-feature match. | |
template<typename G > | |
void | vslam::add_idx_pair (int src_idx, int dest_idx, typename graph_traits< G >::vertex_descriptor src, typename graph_traits< G >::vertex_descriptor dest, G &g) |
insert feature-feature match. | |
template<typename G > | |
void | vslam::add_idx_pair_from_dmatch (const cv::DMatch &dmatch, typename graph_traits< G >::vertex_descriptor tvd, typename graph_traits< G >::vertex_descriptor qvd, G &g) |
insert feature-feature match. | |
template<typename G > | |
bool | vslam::filter_index_pair_duplicates (const cv::DMatch &dmatch, typename graph_traits< G >::vertex_descriptor src, typename graph_traits< G >::vertex_descriptor dest, G &g) |
returns false if feature-feature match from dmatch is present in the pose-graph. | |
vector< cv::DMatch > | vslam::remapDMatchIdxs (const vector< cv::DMatch > &dmatches, const vector< int > &tidx, const vector< int > &qidx) |
Remap feature indexes. | |
cv::DMatch | vslam::dmatchFromPair (const pair< int, int > &p) |
pair< int, int > | vslam::pairFromDMatch (const cv::DMatch &dmatch) |
template<template< class, class > class CT, class G > | |
CT< int, std::allocator< int > > | vslam::common_feature_tracks (G &g, typename graph_traits< G >::vertex_descriptor vad, typename graph_traits< G >::vertex_descriptor vbd, typename graph_traits< G >::vertex_descriptor vcd) |
Find feature-tracks common to given 3 vertices. | |
Creation of ImageMatch and ImageMatchVec | |
template<class G > | |
ImageMatch | vslam::computeMatch (const G &g, FeatureID< G > source, FeatureID< G > target) |
template<class G > | |
ImageMatch | vslam::computeMatch (const G &g, int source_idx, typename graph_traits< G >::vertex_descriptor source_vd, typename graph_traits< G >::vertex_descriptor target_vd) |
template<typename G > | |
ImageMatchVec | vslam::computeMatches (typename graph_traits< G >::vertex_descriptor src, typename graph_traits< G >::vertex_descriptor dest, const G &g) |
Edge Transform | |
template<class PoseGraphT > | |
SE3 | vslam::getEdgeTransform (const PoseGraphT &g, typename graph_traits< PoseGraphT >::vertex_descriptor vd1, typename graph_traits< PoseGraphT >::vertex_descriptor vd2) |
Get RBT from 'vd1' CF to 'vd2' CF. | |
template<class G > | |
void | vslam::setEdgeTransform (const SE3 &T_tvd_qvd, typename graph_traits< G >::vertex_descriptor tvd, typename graph_traits< G >::vertex_descriptor qvd, G &g) |
Sets edge rigid body transform constraint and updates transform for qvd vertex accordingly. | |
Disparity | |
double | vslam::vectorAngle (const Vector3d &vec1, const Vector3d &vec2) |
template<class PoseGraphT > | |
double | vslam::disparityAngle (const PoseGraphT &g, FeatureID< PoseGraphT > f1, FeatureID< PoseGraphT > f2) |
template<class PoseGraphT > | |
double | vslam::minEdgeDisparityAngle (PoseGraphT &g, typename graph_traits< PoseGraphT >::vertex_descriptor srcv, typename graph_traits< PoseGraphT >::vertex_descriptor destv) |
SFM | |
template<class G > | |
Vector3d | vslam::triangulatePointWrtWorld (const G &g, FeatureID< G > f1, FeatureID< G > f2) |
Triangulates landmark determined by two features in the pose-graph wrt. to world CF. | |
template<class G > | |
Vector3d | vslam::triangulatePointWrtWorldPos (const G &g, FeatureID< G > f1, FeatureID< G > f2) |
bool | vslam::isEstimateInFrontOfCamera (const LandmarkObservation &obs, const Vector3d &estimate) |
Set of utilities useful across multiple modules that operate on pose-graph.
void vslam::add_idx_pair | ( | int | src_idx, |
int | dest_idx, | ||
typename graph_traits< G >::vertex_descriptor | src, | ||
typename graph_traits< G >::vertex_descriptor | dest, | ||
G & | g | ||
) |
insert feature-feature match.
Definition at line 65 of file graph_utils.h.
void vslam::add_idx_pair_from_dmatch | ( | const cv::DMatch & | dmatch, |
typename graph_traits< G >::vertex_descriptor | tvd, | ||
typename graph_traits< G >::vertex_descriptor | qvd, | ||
G & | g | ||
) |
insert feature-feature match.
Definition at line 78 of file graph_utils.h.
CT<int, std::allocator<int> > vslam::common_feature_tracks | ( | G & | g, |
typename graph_traits< G >::vertex_descriptor | vad, | ||
typename graph_traits< G >::vertex_descriptor | vbd, | ||
typename graph_traits< G >::vertex_descriptor | vcd | ||
) |
Find feature-tracks common to given 3 vertices.
Compute feature indexes in vertex 'vbd' that are part of some feature track that is common to 'vad', vbd' and 'vcd'. The computation is based solely on information given in edge_kp_idx_map property of edges , .
Definition at line 128 of file graph_utils.h.
ImageMatch vslam::computeMatch | ( | const G & | g, |
FeatureID< G > | source, | ||
FeatureID< G > | target | ||
) |
Definition at line 151 of file graph_utils.h.
ImageMatch vslam::computeMatch | ( | const G & | g, |
int | source_idx, | ||
typename graph_traits< G >::vertex_descriptor | source_vd, | ||
typename graph_traits< G >::vertex_descriptor | target_vd | ||
) |
Definition at line 162 of file graph_utils.h.
ImageMatchVec vslam::computeMatches | ( | typename graph_traits< G >::vertex_descriptor | src, |
typename graph_traits< G >::vertex_descriptor | dest, | ||
const G & | g | ||
) |
Definition at line 172 of file graph_utils.h.
double vslam::disparityAngle | ( | const PoseGraphT & | g, |
FeatureID< PoseGraphT > | f1, | ||
FeatureID< PoseGraphT > | f2 | ||
) |
Definition at line 229 of file graph_utils.h.
cv::DMatch vslam::dmatchFromPair | ( | const pair< int, int > & | p | ) | [inline] |
Definition at line 113 of file graph_utils.h.
bool vslam::filter_index_pair_duplicates | ( | const cv::DMatch & | dmatch, |
typename graph_traits< G >::vertex_descriptor | src, | ||
typename graph_traits< G >::vertex_descriptor | dest, | ||
G & | g | ||
) |
returns false if feature-feature match from dmatch is present in the pose-graph.
Definition at line 87 of file graph_utils.h.
SE3 vslam::getEdgeTransform | ( | const PoseGraphT & | g, |
typename graph_traits< PoseGraphT >::vertex_descriptor | vd1, | ||
typename graph_traits< PoseGraphT >::vertex_descriptor | vd2 | ||
) |
Get RBT from 'vd1' CF to 'vd2' CF.
Definition at line 196 of file graph_utils.h.
int vslam::getFeatureIdx | ( | const G & | g, |
int | source_idx, | ||
typename graph_traits< G >::vertex_descriptor | source_vd, | ||
typename graph_traits< G >::vertex_descriptor | target_vd | ||
) |
get feature index in the target pose (i.e. retrive the the feature-feature match)
Definition at line 30 of file graph_utils.h.
int vslam::getFeatureIdx | ( | const G & | g, |
FeatureID< G > | srcf, | ||
typename graph_traits< G >::vertex_descriptor | target_vd | ||
) |
get feature index in the target pose...
Definition at line 46 of file graph_utils.h.
Vector2d vslam::getFeaturePixel | ( | const G & | g, |
const FeatureID< G > | f | ||
) |
Returns pixel coordinates of a feature.
Definition at line 333 of file graph_utils.h.
bool vslam::isEstimateInFrontOfCamera | ( | const LandmarkObservation & | obs, |
const Vector3d & | estimate | ||
) | [inline] |
Definition at line 287 of file graph_utils.h.
void vslam::landmarkObservationsBySize | ( | const G & | g, |
Points< G > & | points, | ||
typename graph_traits< G >::vertex_descriptor | vd, | ||
vector< vector< int > > & | all_result, | ||
vector< vector< int > > & | kf_result | ||
) |
Definition at line 298 of file graph_utils.h.
double vslam::maxFeatureDistance | ( | const G & | g, |
const Points< G > & | points, | ||
typename Point< G >::VertexD | v | ||
) |
Definition at line 339 of file graph_utils.h.
double vslam::minEdgeDisparityAngle | ( | PoseGraphT & | g, |
typename graph_traits< PoseGraphT >::vertex_descriptor | srcv, | ||
typename graph_traits< PoseGraphT >::vertex_descriptor | destv | ||
) |
Definition at line 241 of file graph_utils.h.
pair<int, int> vslam::pairFromDMatch | ( | const cv::DMatch & | dmatch | ) | [inline] |
Definition at line 117 of file graph_utils.h.
std::string vslam::printVertexId | ( | const G & | g, |
typename graph_traits< G >::vertex_descriptor | vd | ||
) |
returns human-readable vertex-id as string.
Definition at line 359 of file graph_utils.h.
vector<cv::DMatch> vslam::remapDMatchIdxs | ( | const vector< cv::DMatch > & | dmatches, |
const vector< int > & | tidx, | ||
const vector< int > & | qidx | ||
) | [inline] |
Remap feature indexes.
Definition at line 100 of file graph_utils.h.
void vslam::remove_idx_pair | ( | int | sidx, |
typename graph_traits< G >::vertex_descriptor | src, | ||
typename graph_traits< G >::vertex_descriptor | dest, | ||
G & | g | ||
) |
delete feature-feature match.
Definition at line 52 of file graph_utils.h.
void vslam::setEdgeTransform | ( | const SE3 & | T_tvd_qvd, |
typename graph_traits< G >::vertex_descriptor | tvd, | ||
typename graph_traits< G >::vertex_descriptor | qvd, | ||
G & | g | ||
) |
Sets edge rigid body transform constraint and updates transform for qvd vertex accordingly.
Definition at line 204 of file graph_utils.h.
Vector3d vslam::triangulatePointWrtWorld | ( | const G & | g, |
FeatureID< G > | f1, | ||
FeatureID< G > | f2 | ||
) |
Triangulates landmark determined by two features in the pose-graph wrt. to world CF.
Definition at line 269 of file graph_utils.h.
Vector3d vslam::triangulatePointWrtWorldPos | ( | const G & | g, |
FeatureID< G > | f1, | ||
FeatureID< G > | f2 | ||
) |
Definition at line 278 of file graph_utils.h.
double vslam::vectorAngle | ( | const Vector3d & | vec1, |
const Vector3d & | vec2 | ||
) | [inline] |
brief computes angle between two vectors.
Definition at line 223 of file graph_utils.h.