#include <posest/pe.h>
#include <opencv2/core/core.hpp>
#include <opencv2/features2d/features2d.hpp>
Go to the source code of this file.
Namespaces | |
namespace | pe |
Functions | |
double | pe::avgSampsonusError (const cv::Mat &essential, const std::vector< cv::Point2f > &points1, const std::vector< cv::Point2f > &points2, double max_error=1.0, bool verbose=false) |
cv::Mat | pe::calcEssentialMatrix (const cv::Mat &intrinsics_inv, const cv::Mat &R, const cv::Mat &T) |
void | pe::calcRelativeRT (const cv::Mat &R1, const cv::Mat &T1, const cv::Mat &R2, const cv::Mat &T2, cv::Mat &dR, cv::Mat &dT) |
float | pe::calcScaledPointCloudDistance (const std::vector< cv::Point3f > &points1, const std::vector< cv::Point3f > &points2) |
void | pe::computeEpipolarInliers (const cv::Mat &essential, const std::vector< cv::Point2f > &points1, const std::vector< cv::Point2f > &points2, std::vector< bool > &inliers, double maxError=3.0) |
cv::Point3f | pe::crossProduct (cv::Point3f &p1, cv::Point3f &p2) |
void | pe::dumpFltMat (const char *name, const cv::Mat &mat) |
void | pe::filterInliers (const std::vector< cv::Point3f > &obj_pts, const std::vector< cv::Point2f > &img1_pts, const std::vector< cv::Point2f > &img2_pts, const cv::Mat &R, const cv::Mat &T, const cv::Mat &intrinsics, double reprojectionError, std::vector< bool > &valid) |
template<class T > | |
void | pe::filterVector (const std::vector< T > &src, const std::vector< bool > &valid, std::vector< T > &dst) |
template<class T > | |
void | pe::filterVector (const std::vector< T > &src, const std::vector< int > &valid, std::vector< T > &dst) |
template<class T > | |
void | pe::filterVector (std::vector< T > &v, const std::vector< bool > &valid) |
void | pe::findNaNPoints (const std::vector< cv::Point3f > &points, std::vector< bool > &valid) |
void | pe::keyPoints2Point2f (const cv::vector< cv::KeyPoint > &src, std::vector< cv::Point2f > &dst) |
void | pe::keyPoints2Point2f (const std::vector< cv::KeyPoint > &src, std::vector< cv::Point2f > &dst) |
void | pe::matchesFromIndices (const std::vector< cv::KeyPoint > &_set1, const std::vector< cv::KeyPoint > &_set2, const std::vector< int > &indices, std::vector< cv::Point2f > &points1, std::vector< cv::Point2f > &points2) |
void | pe::matchesFromIndices (const std::vector< cv::KeyPoint > &src1, const std::vector< cv::KeyPoint > &src2, const std::vector< cv::DMatch > &indices, std::vector< cv::Point2f > &dst1, std::vector< cv::Point2f > &dst2) |
cv::Point3f | pe::mult (const cv::Mat &M, const cv::Point3f &p) |
void | pe::planarSFM (const cv::Mat &intrinsics, const std::vector< cv::KeyPoint > &set1, const std::vector< cv::KeyPoint > &set2, const std::vector< int > &indices, cv::Mat &H, cv::Mat &R, cv::Mat &T, double reprojectionError=6.0) |
void | pe::reprojectPoints (const cv::Mat &intrinsics, const cv::Mat &R, const cv::Mat &T, const std::vector< cv::Point2f > &p1, const std::vector< cv::Point2f > &p2, std::vector< cv::Point3f > &p, std::vector< bool > &valid) |
void | pe::sample (int max_index, int count, std::vector< int > &sample_indices) |
void | pe::sba (const cv::Mat &intrinsics, cv::Mat &rvec, cv::Mat &tvec, std::vector< cv::Point3f > &points, const std::vector< cv::Point2f > &points1, const std::vector< cv::Point2f > &points2) |
double | pe::SFM (const cv::Mat &intrinsics, const std::vector< cv::KeyPoint > &set1, const std::vector< cv::KeyPoint > &set2, const std::vector< int > &indices, cv::Mat &R, cv::Mat &T, double reprojectionError=6.0) |
double | pe::SFM (const cv::Mat &intrinsics, const std::vector< cv::Point2f > &points1, const std::vector< cv::Point2f > &points2, cv::Mat &R, cv::Mat &T, double reprojectionError=6.0) |
double | pe::SFMwithSBA (const cv::Mat &intrinsics, const std::vector< cv::KeyPoint > &points1, const std::vector< cv::KeyPoint > &points2, const std::vector< int > &indices, cv::Mat &rvec, cv::Mat &T, double reprojectionError) |
double | pe::SFMwithSBA (const cv::Mat &intrinsics, std::vector< cv::Point2f > &points1, std::vector< cv::Point2f > &points2, cv::Mat &rvec, cv::Mat &T, double reprojectionError) |
template<class T > | |
void | pe::vectorSubset (const std::vector< T > &src, const std::vector< int > &indices, std::vector< T > &dst) |