Classes | |
struct | _RadiusPoint |
struct | AtomPair |
struct | AtomPairDist |
struct | AtomPairLess |
struct | AtomPairMin |
class | Blender |
class | BlenderAlpha |
class | BlenderMultiband |
class | BlenderNoBlend |
class | BlenderSimple |
class | BlurDetector |
struct | Callback |
class | CallbackEngine |
class | Camera |
class | CaptureEngine |
class | Copier |
struct | DCallback |
class | drawable |
class | Extrinsics |
class | Features |
struct | FitPair |
class | FitterResult |
struct | GCallback |
class | GenericModelFitter |
struct | Globber |
class | GriddedDynamicDetectorAdaptor |
class | HugeImage |
class | ImageAtom |
class | ImageMolecule |
class | Images |
class | ModelFitter |
class | ModelFitterParams |
class | MoleculeGlob |
struct | MoleculePeeler |
class | MoleculeProcessor |
struct | PairGlobber |
struct | PairNode |
struct | PairNodeData |
struct | PairPointsCSV |
class | PriorTracker |
class | Projector |
class | SCopier |
class | serializable |
class | SparseProjector |
struct | SVDFitR |
struct | SVDRSolverParams |
Typedefs | |
typedef std::set< AtomPair, AtomPairLess > | AtomPairSet |
typedef std::vector< cv::KeyPoint > | KeypointVector |
typedef std::vector< cv::DMatch > | MatchesVector |
typedef void(* | MDoperator )(cv::InputArray, cv::InputArray, cv::OutputArray, double, int) |
typedef float(* | PairBlendConfFPT )(float err_new, float err_prv) |
a typedef for easily swapping out the blending confidence function for PairNode. Want to allow low-confidence things to get drawn, but only if they don't overlap something else that has high confidence. | |
typedef float(* | PairMatchErrFPT )(const AtomPair &pair, const PairNodeData &node_data) |
a typedef for easily swapping out the error function for PairNode. | |
typedef GenericModelFitter < SVDFitR, SVDRSolverParams > | SVDFitter |
Functions | |
void | alphaCompose (Mat &rgb1, const Mat &alpha, const Mat &one_minus_alpha, Mat &rgb_dest) |
float | angularDist (const Extrinsics &ext1, const Extrinsics &ext2) |
float | calcError (const Point3f &p1, const Point3f &p2, const Mat &R, const Mat &K) |
float | calcError (const std::vector< Point3f > &pts1, const std::vector< Point3f > &pts2, const std::vector< uchar > &mask, const cv::Mat &R, const cv::Mat &K, int norm_type) |
float | calcError (const cv::Point3f &p1, const cv::Point3f &p2, const cv::Mat &R, const cv::Mat &K) |
float | calcError (const std::vector< cv::Point3f > &pts1, const std::vector< cv::Point3f > &pts2, const std::vector< uchar > &mask, const cv::Mat &R, const cv::Mat &K, int norm_type=cv::NORM_L1) |
float | calcReprojectonError (const vector< Point2f > &pts1, const vector< Point2f > &pts2, const std::vector< uchar > &mask, const cv::Mat &R, const cv::Mat &_K, int norm_type) |
float | calcReprojectonError (const std::vector< cv::Point2f > &pts1, const std::vector< cv::Point2f > &pts2, const std::vector< uchar > &mask, const cv::Mat &R, const cv::Mat &K, int norm_type=cv::NORM_L1) |
bool | compareRealToIndexPair (const std::pair< double, int > &lhs, const std::pair< double, int > &rhs) |
helper to sort a vector of distance index pairs | |
void | convertRTtoG (const cv::Mat &R, const cv::Mat &T, cv::Mat &G) |
concatenate 3x3 R and 3x1 T into a 4x4 G matrix | |
cv::Mat | createHomogSphrCoords (const cv::Size &sphere_size, float theta_range=2 *CV_PI, float phi_range=CV_PI) |
void | DijkstraWay (ImageMolecule &mol) |
void | divideImageByDoubleWeights (const cv::Mat &img, const cv::Mat &weights, cv::Mat &output, std::vector< cv::Mat > *cache_channels=0) |
void | divideImageByFloatWeights (const cv::Mat &img, const cv::Mat &weights, cv::Mat &output, std::vector< cv::Mat > *cache_channels=0) |
void | drawMatchesRelative (const Features &train, const Features &query, const std::vector< cv::DMatch > &matches, Mat &img, const vector< unsigned char > &mask) |
void | drawMatchesRelative (const Features &train, const Features &query, const std::vector< cv::DMatch > &matches, cv::Mat &img, const std::vector< unsigned char > &mask=std::vector< unsigned char >()) |
cv::Mat | getRv (const cv::Mat &R) |
int | getUID () |
void | initAlphaMat (const Size &sz, Mat &alpha, int feather_width) |
void | initAlphaMat (const cv::Size &sz, cv::Mat &alpha, int feather_width) |
void | KeyPointsToPoints (const KeypointVector &keypts, std::vector< cv::Point2f > &pts) |
void | matches2points (const KeypointVector &train, const KeypointVector &query, const MatchesVector &matches, std::vector< cv::Point2f > &pts_train, std::vector< cv::Point2f > &pts_query) |
void | matches2points (const KeypointVector &train, const KeypointVector &query, const MatchesVector &matches, std::vector< cv::Point2f > &pts_train, std::vector< Point2f > &pts_query) |
void | mdImageByDoubleWeights (const cv::Mat &img, const cv::Mat &weights, cv::Mat &output, MDoperator md, std::vector< cv::Mat > *cache_channels) |
void | mdImageByFloatWeights (const cv::Mat &img, const cv::Mat &weights, cv::Mat &output, MDoperator md, std::vector< cv::Mat > *cache_channels) |
void | multiplyImageByDoubleWeights (const cv::Mat &img, const cv::Mat &weights, cv::Mat &output, std::vector< cv::Mat > *cache_channels=0) |
void | multiplyImageByFloatWeights (const cv::Mat &img, const cv::Mat &weights, cv::Mat &output, std::vector< cv::Mat > *cache_channels=0) |
std::ostream & | operator<< (std::ostream &out, const PairNode &node) |
std::ostream & | operator<< (std::ostream &out, const AtomPair &pair) |
bool | operator== (const cv::Point2f &pt1, _RadiusPoint< cv::Point2f > pt2) |
bool | operator== (const cv::Point3f &pt1, _RadiusPoint< cv::Point3f > pt2) |
float | PairConfExpLaw (float err_new, float err_prv) |
float | PairConfInvLaw (float err_new, float err_prv) |
float | PairErrorAvoidCompassChain (const AtomPair &pair, const PairNodeData &node_data) |
float | PairErrorInliers (const AtomPair &pair, const PairNodeData &node_data) |
float | PairErrorSimple (const AtomPair &pair, const PairNodeData &node_data) |
void | point2fto3dMat (const cv::Point2f &p1, const cv::Mat &Kinv, cv::Mat &p13d) |
cv::Mat | point2fto3dMat (const cv::Point2f &p1, const cv::Mat &Kinv) |
cv::Point3f | point2fTo3f (const cv::Point2f &p1, const cv::Mat &Kinverse) |
cv::Point2f | point3fTo2f (const cv::Point3f &p1, const cv::Mat &K) |
template<typename Inserter , typename Begin , typename End > | |
void | points2fto3f (Begin begin, End end, Inserter it, const cv::Mat &Kinverse) |
template<typename Inserter , typename Begin , typename End > | |
void | points3fto2f (Begin begin, End end, Inserter it, const cv::Mat &K) |
void | PointsToKeyPoints (const std::vector< cv::Point2f > &keypts, KeypointVector &pts) |
cv::Mat | pt2f_to_3d (const cv::Point2f &p1, const cv::Mat &K) |
template<typename T > | |
_RadiusPoint< T > | RadiusPoint (float r, const T &pt2) |
void | rescaleFloatImage1 (cv::Mat &img) |
void | rescaleFloatImage1_clip (cv::Mat &img) |
void | rescaleFloatImage1_shiftMin_divideMax (cv::Mat &img) |
void | rescaleFloatImage256 (cv::Mat &img) |
void | rescaleFloatImage256_clip (cv::Mat &img) |
template<typename CSVSavable > | |
void | saveMatCsv (const CSVSavable &mat, const std::string &name, bool append) |
allows each output of cv::Mat in cv::Matlab forcv::Mat to std::cout use like | |
float | scorematch (const std::vector< cv::DMatch > &matches) |
void | sharpen_backwards_heat_equation (const cv::Mat &src, cv::Mat &dst, float alpha=.02) |
cv::Mat | skewsym (const cv::Mat &x) |
void | sparsifyMatches (const ImageAtom &atom1, const ImageAtom &atom2, std::vector< cv::Point2f > &pts1, std::vector< cv::Point2f > &pts2, int iKeep=50) |
void | sparsifyMatches (AtomPair &pair, int iKeep=50) |
std::string | strip (const std::string &str, const std::string &what) |
Variables | |
static const float | PI = 3.14159265f |
static int | uid_gen = 0 |
typedef std::set<AtomPair, AtomPairLess> pano::AtomPairSet |
Definition at line 261 of file ModelFitter.h.
typedef std::vector<cv::KeyPoint> pano::KeypointVector |
store list of key points from 'feature detection'
Definition at line 48 of file feature_utils.h.
typedef std::vector<cv::DMatch> pano::MatchesVector |
store list of 'match points' and 'match scores' between two sets of keypoints
Definition at line 52 of file feature_utils.h.
typedef void(* pano::MDoperator)(cv::InputArray, cv::InputArray, cv::OutputArray, double, int) |
Definition at line 80 of file panoutils.h.
typedef float(* pano::PairBlendConfFPT)(float err_new, float err_prv) |
a typedef for easily swapping out the blending confidence function for PairNode. Want to allow low-confidence things to get drawn, but only if they don't overlap something else that has high confidence.
Definition at line 41 of file PairNode.h.
typedef float(* pano::PairMatchErrFPT)(const AtomPair &pair, const PairNodeData &node_data) |
a typedef for easily swapping out the error function for PairNode.
Definition at line 35 of file PairNode.h.
Definition at line 467 of file ModelFitter.h.
void pano::alphaCompose | ( | Mat & | rgb1, |
const Mat & | alpha, | ||
const Mat & | one_minus_alpha, | ||
Mat & | rgb_dest | ||
) |
Definition at line 105 of file Blender.cpp.
float pano::angularDist | ( | const Extrinsics & | ext1, |
const Extrinsics & | ext2 | ||
) | [inline] |
Definition at line 91 of file Extrinsics.h.
float pano::calcError | ( | const Point3f & | p1, |
const Point3f & | p2, | ||
const Mat & | R, | ||
const Mat & | K | ||
) |
Definition at line 228 of file ModelFitter.cpp.
float pano::calcError | ( | const std::vector< Point3f > & | pts1, |
const std::vector< Point3f > & | pts2, | ||
const std::vector< uchar > & | mask, | ||
const cv::Mat & | R, | ||
const cv::Mat & | K, | ||
int | norm_type | ||
) |
Definition at line 240 of file ModelFitter.cpp.
float pano::calcError | ( | const cv::Point3f & | p1, |
const cv::Point3f & | p2, | ||
const cv::Mat & | R, | ||
const cv::Mat & | K | ||
) |
gets the L2 norm between the p1 and p2 given an R takes {p2} = R * p1 return norm(p2 , {p2})
float pano::calcError | ( | const std::vector< cv::Point3f > & | pts1, |
const std::vector< cv::Point3f > & | pts2, | ||
const std::vector< uchar > & | mask, | ||
const cv::Mat & | R, | ||
const cv::Mat & | K, | ||
int | norm_type = cv::NORM_L1 |
||
) |
float pano::calcReprojectonError | ( | const vector< Point2f > & | pts1, |
const vector< Point2f > & | pts2, | ||
const std::vector< uchar > & | mask, | ||
const cv::Mat & | R, | ||
const cv::Mat & | _K, | ||
int | norm_type | ||
) |
Definition at line 262 of file ModelFitter.cpp.
float pano::calcReprojectonError | ( | const std::vector< cv::Point2f > & | pts1, |
const std::vector< cv::Point2f > & | pts2, | ||
const std::vector< uchar > & | mask, | ||
const cv::Mat & | R, | ||
const cv::Mat & | K, | ||
int | norm_type = cv::NORM_L1 |
||
) |
lift p1 to 3d, rotate points by R, reproject by K, compare to p2. also takes the mask for doing this for only a subset.
bool pano::compareRealToIndexPair | ( | const std::pair< double, int > & | lhs, |
const std::pair< double, int > & | rhs | ||
) | [inline] |
helper to sort a vector of distance index pairs
Definition at line 38 of file panoutils.h.
void pano::convertRTtoG | ( | const cv::Mat & | R, |
const cv::Mat & | T, | ||
cv::Mat & | G | ||
) |
concatenate 3x3 R and 3x1 T into a 4x4 G matrix
Definition at line 296 of file ModelFitter.cpp.
cv::Mat pano::createHomogSphrCoords | ( | const cv::Size & | sphere_size, |
float | theta_range = 2 * CV_PI , |
||
float | phi_range = CV_PI |
||
) |
Definition at line 188 of file Projector.cpp.
void pano::DijkstraWay | ( | ImageMolecule & | mol | ) |
Definition at line 108 of file MoleculeProcessor.cpp.
void pano::divideImageByDoubleWeights | ( | const cv::Mat & | img, |
const cv::Mat & | weights, | ||
cv::Mat & | output, | ||
std::vector< cv::Mat > * | cache_channels = 0 |
||
) | [inline] |
Definition at line 100 of file panoutils.h.
void pano::divideImageByFloatWeights | ( | const cv::Mat & | img, |
const cv::Mat & | weights, | ||
cv::Mat & | output, | ||
std::vector< cv::Mat > * | cache_channels = 0 |
||
) | [inline] |
Definition at line 92 of file panoutils.h.
void pano::drawMatchesRelative | ( | const Features & | train, |
const Features & | query, | ||
const std::vector< cv::DMatch > & | matches, | ||
Mat & | img, | ||
const vector< unsigned char > & | mask | ||
) |
Definition at line 49 of file Features.cpp.
void pano::drawMatchesRelative | ( | const Features & | train, |
const Features & | query, | ||
const std::vector< cv::DMatch > & | matches, | ||
cv::Mat & | img, | ||
const std::vector< unsigned char > & | mask = std::vector< unsigned char >() |
||
) |
cv::Mat pano::getRv | ( | const cv::Mat & | R | ) | [inline] |
return the effect of R on a unit vector on z axis
Definition at line 29 of file panoutils.h.
int pano::getUID | ( | ) |
Definition at line 16 of file ImageAtom.cpp.
void pano::initAlphaMat | ( | const Size & | sz, |
Mat & | alpha, | ||
int | feather_width | ||
) |
Definition at line 31 of file Blender.cpp.
void pano::initAlphaMat | ( | const cv::Size & | sz, |
cv::Mat & | alpha, | ||
int | feather_width | ||
) |
void pano::KeyPointsToPoints | ( | const KeypointVector & | keypts, |
std::vector< cv::Point2f > & | pts | ||
) |
convert from a vector of 'keypoints' with N-d data to 2d xy points
Definition at line 46 of file feature_utils.cpp.
void pano::matches2points | ( | const KeypointVector & | train, |
const KeypointVector & | query, | ||
const MatchesVector & | matches, | ||
std::vector< cv::Point2f > & | pts_train, | ||
std::vector< cv::Point2f > & | pts_query | ||
) |
convert from a vector of 'match points' with N-d data to 2d xy points
void pano::matches2points | ( | const KeypointVector & | train, |
const KeypointVector & | query, | ||
const MatchesVector & | matches, | ||
std::vector< cv::Point2f > & | pts_train, | ||
std::vector< Point2f > & | pts_query | ||
) |
Definition at line 66 of file feature_utils.cpp.
void pano::mdImageByDoubleWeights | ( | const cv::Mat & | img, |
const cv::Mat & | weights, | ||
cv::Mat & | output, | ||
MDoperator | md, | ||
std::vector< cv::Mat > * | cache_channels | ||
) |
Definition at line 30 of file panoutils.cpp.
void pano::mdImageByFloatWeights | ( | const cv::Mat & | img, |
const cv::Mat & | weights, | ||
cv::Mat & | output, | ||
MDoperator | md, | ||
std::vector< cv::Mat > * | cache_channels | ||
) |
Definition at line 6 of file panoutils.cpp.
void pano::multiplyImageByDoubleWeights | ( | const cv::Mat & | img, |
const cv::Mat & | weights, | ||
cv::Mat & | output, | ||
std::vector< cv::Mat > * | cache_channels = 0 |
||
) | [inline] |
Definition at line 96 of file panoutils.h.
void pano::multiplyImageByFloatWeights | ( | const cv::Mat & | img, |
const cv::Mat & | weights, | ||
cv::Mat & | output, | ||
std::vector< cv::Mat > * | cache_channels = 0 |
||
) | [inline] |
Definition at line 88 of file panoutils.h.
std::ostream & pano::operator<< | ( | std::ostream & | out, |
const PairNode & | node | ||
) |
encapsulate dumping node meta-data along with the pair of atoms it contains
Definition at line 725 of file MoleculeProcessor.cpp.
std::ostream & pano::operator<< | ( | std::ostream & | out, |
const AtomPair & | pair | ||
) |
encapsulate dumping pair-only, less meta-data than a PairNode
Definition at line 756 of file MoleculeProcessor.cpp.
bool pano::operator== | ( | const cv::Point2f & | pt1, |
_RadiusPoint< cv::Point2f > | pt2 | ||
) | [inline] |
Definition at line 39 of file feature_utils.h.
bool pano::operator== | ( | const cv::Point3f & | pt1, |
_RadiusPoint< cv::Point3f > | pt2 | ||
) | [inline] |
Definition at line 42 of file feature_utils.h.
float pano::PairConfExpLaw | ( | float | err_new, |
float | err_prv | ||
) | [inline] |
exponential decrease of blender confidence with match error
Definition at line 45 of file PairNode.h.
float pano::PairConfInvLaw | ( | float | err_new, |
float | err_prv | ||
) | [inline] |
1/x decrease of blender confidence with match error m-code: E = logspace(-1,3,500); gam0 = beta0 * C0; CofE = gam0 ./ (E+eps0) + alpha; loglog(E,CofE)
Definition at line 61 of file PairNode.h.
float pano::PairErrorAvoidCompassChain | ( | const AtomPair & | pair, |
const PairNodeData & | node_data | ||
) | [inline] |
example of error function that is use something regarding the entire graph, which would not be available to the modelfitter + fitter_result
Definition at line 86 of file PairNode.h.
float pano::PairErrorInliers | ( | const AtomPair & | pair, |
const PairNodeData & | node_data | ||
) | [inline] |
Return inliers-weighted error. Assumes things about how Modelfitter Error relates to inliers, when ModelFitter is a generic class. Makes sense for SVD as it stands.
Definition at line 74 of file PairNode.h.
float pano::PairErrorSimple | ( | const AtomPair & | pair, |
const PairNodeData & | node_data | ||
) | [inline] |
Definition at line 78 of file PairNode.h.
void pano::point2fto3dMat | ( | const cv::Point2f & | p1, |
const cv::Mat & | Kinv, | ||
cv::Mat & | p13d | ||
) | [inline] |
Definition at line 380 of file ModelFitter.h.
cv::Mat pano::point2fto3dMat | ( | const cv::Point2f & | p1, |
const cv::Mat & | Kinv | ||
) | [inline] |
Definition at line 386 of file ModelFitter.h.
cv::Point3f pano::point2fTo3f | ( | const cv::Point2f & | p1, |
const cv::Mat & | Kinverse | ||
) | [inline] |
Definition at line 399 of file ModelFitter.h.
cv::Point2f pano::point3fTo2f | ( | const cv::Point3f & | p1, |
const cv::Mat & | K | ||
) | [inline] |
Definition at line 407 of file ModelFitter.h.
void pano::points2fto3f | ( | Begin | begin, |
End | end, | ||
Inserter | it, | ||
const cv::Mat & | Kinverse | ||
) |
Definition at line 416 of file ModelFitter.h.
void pano::points3fto2f | ( | Begin | begin, |
End | end, | ||
Inserter | it, | ||
const cv::Mat & | K | ||
) |
Definition at line 427 of file ModelFitter.h.
void pano::PointsToKeyPoints | ( | const std::vector< cv::Point2f > & | keypts, |
KeypointVector & | pts | ||
) |
Definition at line 56 of file feature_utils.cpp.
cv::Mat pano::pt2f_to_3d | ( | const cv::Point2f & | p1, |
const cv::Mat & | K | ||
) | [inline] |
'lift' 2d to 3d points via K and assumption of being on unit sphere
Definition at line 394 of file ModelFitter.h.
_RadiusPoint<T> pano::RadiusPoint | ( | float | r, |
const T & | pt2 | ||
) |
Definition at line 35 of file feature_utils.h.
void pano::rescaleFloatImage1 | ( | cv::Mat & | img | ) | [inline] |
Definition at line 143 of file panoutils.h.
void pano::rescaleFloatImage1_clip | ( | cv::Mat & | img | ) | [inline] |
Definition at line 164 of file panoutils.h.
void pano::rescaleFloatImage1_shiftMin_divideMax | ( | cv::Mat & | img | ) | [inline] |
Definition at line 126 of file panoutils.h.
void pano::rescaleFloatImage256 | ( | cv::Mat & | img | ) | [inline] |
Definition at line 105 of file panoutils.h.
void pano::rescaleFloatImage256_clip | ( | cv::Mat & | img | ) | [inline] |
Definition at line 195 of file panoutils.h.
void pano::saveMatCsv | ( | const CSVSavable & | mat, |
const std::string & | name, | ||
bool | append | ||
) |
allows each output of cv::Mat in cv::Matlab forcv::Mat to std::cout use like
// std::cout << mycv::Mat; //
write a cv::Matrix in csv forcv::Mat for cv::Matlab. This means that the rows are seperated by newlines and the columns by commas .... 331.413896619595,0,122.365880226491 0,249.320451610369,122.146722131871 0,0,1
out | output stream to write to |
cv::Mat | write a cv::Mat to a csvSaves a cv::Mat csv file for using in Matlab |
Mat | The Mat. |
name | The name. |
append | true to append. |
Definition at line 73 of file panoutils.h.
float pano::scorematch | ( | const std::vector< cv::DMatch > & | matches | ) | [inline] |
Definition at line 67 of file feature_utils.h.
void pano::sharpen_backwards_heat_equation | ( | const cv::Mat & | src, |
cv::Mat & | dst, | ||
float | alpha = .02 |
||
) |
apply 'unknown blur' deblurring. for efficiency, write to the source back in it's format.
Definition at line 63 of file BlurDetector.cpp.
cv::Mat pano::skewsym | ( | const cv::Mat & | x | ) | [inline] |
Definition at line 100 of file Extrinsics.h.
void pano::sparsifyMatches | ( | const ImageAtom & | atom1, |
const ImageAtom & | atom2, | ||
std::vector< cv::Point2f > & | pts1, | ||
std::vector< cv::Point2f > & | pts2, | ||
int | iKeep = 50 |
||
) |
keep only a subset of points, with lower reproject error via this fitter
void pano::sparsifyMatches | ( | AtomPair & | pair, |
int | iKeep = 50 |
||
) |
keep only a subset of points, with lower reproject error via this fitter
Definition at line 310 of file ModelFitter.cpp.
std::string pano::strip | ( | const std::string & | str, |
const std::string & | what | ||
) |
Definition at line 814 of file MoleculeProcessor.cpp.
const float pano::PI = 3.14159265f [static] |
Definition at line 13 of file Projector.cpp.
int pano::uid_gen = 0 [static] |
Definition at line 15 of file ImageAtom.cpp.