#include <EpipolarGeometry.h>
Public Member Functions | |
bool | check (const Signature *ssA, const Signature *ssB) |
EpipolarGeometry (const ParametersMap ¶meters=ParametersMap()) | |
int | getMatchCountMinAccepted () const |
double | getRansacParam1 () const |
double | getRansacParam2 () const |
void | parseParameters (const ParametersMap ¶meters) |
void | setMatchCountMinAccepted (int matchCountMinAccepted) |
void | setRansacParam1 (double ransacParam1) |
void | setRansacParam2 (double ransacParam2) |
virtual | ~EpipolarGeometry () |
Static Public Member Functions | |
static void | findEpipolesFromF (const cv::Mat &fundamentalMatrix, cv::Vec3d &e1, cv::Vec3d &e2) |
static cv::Mat | findFFromCalibratedStereoCameras (double fx, double fy, double cx, double cy, double Tx, double Ty) |
static cv::Mat | findFFromWords (const std::list< std::pair< int, std::pair< cv::KeyPoint, cv::KeyPoint > > > &pairs, std::vector< uchar > &status, double ransacParam1=3.0, double ransacParam2=0.99) |
static int | findPairs (const std::multimap< int, cv::KeyPoint > &wordsA, const std::multimap< int, cv::KeyPoint > &wordsB, std::list< std::pair< int, std::pair< cv::KeyPoint, cv::KeyPoint > > > &pairs) |
static int | findPairsAll (const std::multimap< int, cv::KeyPoint > &wordsA, const std::multimap< int, cv::KeyPoint > &wordsB, std::list< std::pair< int, std::pair< cv::KeyPoint, cv::KeyPoint > > > &pairs) |
static int | findPairsUnique (const std::multimap< int, cv::KeyPoint > &wordsA, const std::multimap< int, cv::KeyPoint > &wordsB, std::list< std::pair< int, std::pair< cv::KeyPoint, cv::KeyPoint > > > &pairs) |
static cv::Mat | findPFromE (const cv::Mat &E, const cv::Mat &x, const cv::Mat &xp) |
static void | findRTFromP (const cv::Mat &p, cv::Mat &r, cv::Mat &t) |
static cv::Mat | iterativeLinearLSTriangulation (cv::Point3d u, const cv::Matx34d &P, cv::Point3d u1, const cv::Matx34d &P1) |
static cv::Mat | linearLSTriangulation (cv::Point3d u, cv::Matx34d P, cv::Point3d u1, cv::Matx34d P1) |
static double | triangulatePoints (const cv::Mat &pt_set1, const cv::Mat &pt_set2, const cv::Mat &P, const cv::Mat &P1, pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud, std::vector< double > &reproj_errors) |
Private Attributes | |
int | _matchCountMinAccepted |
double | _ransacParam1 |
double | _ransacParam2 |
Definition at line 44 of file EpipolarGeometry.h.
rtabmap::EpipolarGeometry::EpipolarGeometry | ( | const ParametersMap & | parameters = ParametersMap() | ) |
Definition at line 46 of file EpipolarGeometry.cpp.
rtabmap::EpipolarGeometry::~EpipolarGeometry | ( | ) | [virtual] |
Definition at line 54 of file EpipolarGeometry.cpp.
bool rtabmap::EpipolarGeometry::check | ( | const Signature * | ssA, |
const Signature * | ssB | ||
) |
Definition at line 65 of file EpipolarGeometry.cpp.
void rtabmap::EpipolarGeometry::findEpipolesFromF | ( | const cv::Mat & | fundamentalMatrix, |
cv::Vec3d & | e1, | ||
cv::Vec3d & | e2 | ||
) | [static] |
Definition at line 100 of file EpipolarGeometry.cpp.
cv::Mat rtabmap::EpipolarGeometry::findFFromCalibratedStereoCameras | ( | double | fx, |
double | fy, | ||
double | cx, | ||
double | cy, | ||
double | Tx, | ||
double | Ty | ||
) | [static] |
Definition at line 387 of file EpipolarGeometry.cpp.
cv::Mat rtabmap::EpipolarGeometry::findFFromWords | ( | const std::list< std::pair< int, std::pair< cv::KeyPoint, cv::KeyPoint > > > & | pairs, |
std::vector< uchar > & | status, | ||
double | ransacParam1 = 3.0 , |
||
double | ransacParam2 = 0.99 |
||
) | [static] |
Definition at line 292 of file EpipolarGeometry.cpp.
int rtabmap::EpipolarGeometry::findPairs | ( | const std::multimap< int, cv::KeyPoint > & | wordsA, |
const std::multimap< int, cv::KeyPoint > & | wordsB, | ||
std::list< std::pair< int, std::pair< cv::KeyPoint, cv::KeyPoint > > > & | pairs | ||
) | [static] |
if a=[1 2 3 4 6 6], b=[1 1 2 4 5 6 6], results= [(1,1a) (2,2) (4,4) (6a,6a) (6b,6b)] realPairsCount = 5
Definition at line 413 of file EpipolarGeometry.cpp.
int rtabmap::EpipolarGeometry::findPairsAll | ( | const std::multimap< int, cv::KeyPoint > & | wordsA, |
const std::multimap< int, cv::KeyPoint > & | wordsB, | ||
std::list< std::pair< int, std::pair< cv::KeyPoint, cv::KeyPoint > > > & | pairs | ||
) | [static] |
if a=[1 2 3 4 6 6], b=[1 1 2 4 5 6 6], results= [(1,1a) (1,1b) (2,2) (4,4) (6a,6a) (6a,6b) (6b,6a) (6b,6b)] realPairsCount = 5
Definition at line 471 of file EpipolarGeometry.cpp.
int rtabmap::EpipolarGeometry::findPairsUnique | ( | const std::multimap< int, cv::KeyPoint > & | wordsA, |
const std::multimap< int, cv::KeyPoint > & | wordsB, | ||
std::list< std::pair< int, std::pair< cv::KeyPoint, cv::KeyPoint > > > & | pairs | ||
) | [static] |
if a=[1 2 3 4 6 6], b=[1 1 2 4 5 6 6], results= [(2,2) (4,4)] realPairsCount = 5
Definition at line 441 of file EpipolarGeometry.cpp.
cv::Mat rtabmap::EpipolarGeometry::findPFromE | ( | const cv::Mat & | E, |
const cv::Mat & | x, | ||
const cv::Mat & | xp | ||
) | [static] |
Definition at line 179 of file EpipolarGeometry.cpp.
void rtabmap::EpipolarGeometry::findRTFromP | ( | const cv::Mat & | p, |
cv::Mat & | r, | ||
cv::Mat & | t | ||
) | [static] |
Definition at line 375 of file EpipolarGeometry.cpp.
int rtabmap::EpipolarGeometry::getMatchCountMinAccepted | ( | ) | const [inline] |
Definition at line 52 of file EpipolarGeometry.h.
double rtabmap::EpipolarGeometry::getRansacParam1 | ( | ) | const [inline] |
Definition at line 53 of file EpipolarGeometry.h.
double rtabmap::EpipolarGeometry::getRansacParam2 | ( | ) | const [inline] |
Definition at line 54 of file EpipolarGeometry.h.
cv::Mat rtabmap::EpipolarGeometry::iterativeLinearLSTriangulation | ( | cv::Point3d | u, |
const cv::Matx34d & | P, | ||
cv::Point3d | u1, | ||
const cv::Matx34d & | P1 | ||
) | [static] |
source = SfM toy library: https://github.com/royshil/SfM-Toy-Library From "Triangulation", Hartley, R.I. and Sturm, P., Computer vision and image understanding, 1997 return 4x1 double
Definition at line 539 of file EpipolarGeometry.cpp.
cv::Mat rtabmap::EpipolarGeometry::linearLSTriangulation | ( | cv::Point3d | u, |
cv::Matx34d | P, | ||
cv::Point3d | u1, | ||
cv::Matx34d | P1 | ||
) | [static] |
source = SfM toy library: https://github.com/royshil/SfM-Toy-Library From "Triangulation", Hartley, R.I. and Sturm, P., Computer vision and image understanding, 1997 return 1x3 double
Definition at line 506 of file EpipolarGeometry.cpp.
void rtabmap::EpipolarGeometry::parseParameters | ( | const ParametersMap & | parameters | ) |
Definition at line 58 of file EpipolarGeometry.cpp.
void rtabmap::EpipolarGeometry::setMatchCountMinAccepted | ( | int | matchCountMinAccepted | ) | [inline] |
Definition at line 56 of file EpipolarGeometry.h.
void rtabmap::EpipolarGeometry::setRansacParam1 | ( | double | ransacParam1 | ) | [inline] |
Definition at line 57 of file EpipolarGeometry.h.
void rtabmap::EpipolarGeometry::setRansacParam2 | ( | double | ransacParam2 | ) | [inline] |
Definition at line 58 of file EpipolarGeometry.h.
double rtabmap::EpipolarGeometry::triangulatePoints | ( | const cv::Mat & | pt_set, |
const cv::Mat & | pt_set1, | ||
const cv::Mat & | P, | ||
const cv::Mat & | P1, | ||
pcl::PointCloud< pcl::PointXYZ >::Ptr & | pointcloud, | ||
std::vector< double > & | reproj_errors | ||
) | [static] |
source = SfM toy library: https://github.com/royshil/SfM-Toy-Library
Definition at line 591 of file EpipolarGeometry.cpp.
int rtabmap::EpipolarGeometry::_matchCountMinAccepted [private] |
Definition at line 137 of file EpipolarGeometry.h.
double rtabmap::EpipolarGeometry::_ransacParam1 [private] |
Definition at line 138 of file EpipolarGeometry.h.
double rtabmap::EpipolarGeometry::_ransacParam2 [private] |
Definition at line 139 of file EpipolarGeometry.h.