$search
Declarations for triangulation and other recovery-of-3D structure functions. More...
#include "general_resources.hpp"#include "opencv_resources.hpp"#include "camera.hpp"#include "geometry.hpp"#include "tools.hpp"#include <pcl/ros/conversions.h>#include <pcl/point_cloud.h>#include <pcl/point_types.h>#include <pcl/io/pcd_io.h>#include <visualization_msgs/MarkerArray.h>#include <sba/sba.h>#include <sba/sba_file_io.h>#include <sba/visualization.h>#include <math.h>

Go to the source code of this file.
Defines | |
| #define | _USE_MATH_DEFINES |
| #define | EPSILON 0.00001 |
| #define | POSITION_LIMIT 1000 |
Functions | |
| void | addBlankCamera (SysSBA &sys, cameraParameters &cameraData, bool isFixed=false) |
| void | addFixedCamera (SysSBA &sys, cameraParameters &cameraData, const Mat &C) |
| void | addNewCamera (SysSBA &sys, cameraParameters &cameraData, const Mat &C) |
| void | addNewPoints (SysSBA &sys, const vector< Point3d > &pc) |
| unsigned int | addNewPoints (vector< featureTrack > &tracks, vector< unsigned int > &indices, cameraParameters &cameraData, Mat *cameras, unsigned int earliest_index, unsigned int latest_index) |
| int | addToTracks (SysSBA &sys, int im1, vector< Point2f > &pts1, int im2, vector< Point2f > &pts2) |
| void | assignIntrinsicsToP0 (Mat &P0, const Mat &K) |
| void | assignTracksToSBA (SysSBA &sys, vector< featureTrack > &trackVector, int maxIndex) |
| double | calcFrameScore (double geomScore, int numFeatures, int numTracks) |
| double | calcGeometryScore (int numInliers_H, int numInliers_F, double sampsonError_H, double sampsonError_F) |
| double | calcInlierGeometryDistance (vector< Point2f > &points1, vector< Point2f > &points2, Mat &mat, Mat &mask, int distMethod=SAMPSON_DISTANCE) |
| double | calcSampsonDistance (Point2f &pt1, Point2f &pt2, Mat &F) |
| double | calcSampsonError (vector< Point2f > &points1, vector< Point2f > &points2, Mat &H, Mat &Hmask) |
| void | combineTransforms (Mat &CN, const Mat &C0, const Mat &C1) |
| void | compileTransform (Mat &c, const Mat &R, const Mat &t) |
| void | constrainDodgyPoints (SysSBA &sys) |
| void | convertPoint3dToMat (const Point3d &src, Mat &dst) |
| void | convertProjectionMatCVToEigen (const Mat &mat, Eigen::Matrix< double, 3, 4 > m) |
| void | convertProjectionMatEigenToCV (const Eigen::Matrix< double, 3, 4 > m, Mat &mat) |
| void | convertVec4dToMat (const Vector4d &vec4, Mat &mat) |
| int | countActiveTriangulatedTracks (vector< unsigned int > &indices, vector< featureTrack > &tracks) |
| void | decomposeTransform (const Mat &c, Mat &R, Mat &t) |
| Quaterniond | defaultQuaternion () |
| double | dotProduct (const Quaterniond &q1, const Quaterniond &q2) |
| double | dotProduct (const Mat &vec1, const Mat &vec2) |
| void | estimateNewPose (vector< featureTrack > &tracks, Mat &K, int idx, Mat &pose) |
| bool | estimatePoseFromKnownPoints (Mat &dst, cameraParameters camData, vector< featureTrack > &tracks, unsigned int index, const Mat &guide) |
| void | ExtractPointCloud (vector< Point3d > &cloud, vector< featureTrack > &trackVector) |
| void | filterToActivePoints (vector< featureTrack > &tracks, vector< Point2f > &pts1, vector< Point2f > &pts2, vector< unsigned int > &indices, int idx1, int idx2) |
| void | filterToCompleteTracks (vector< unsigned int > &dst, vector< unsigned int > &src, vector< featureTrack > &tracks, int idx1, int idx2) |
| int | findBestCandidate (const Mat *CX, const Mat &K, const vector< Point2f > &pts1, const vector< Point2f > &pts2, Mat &C) |
| bool | findBestReconstruction (const Mat &P0, Mat &P1, Mat &R, Mat &t, const SVD &svd, const Mat &K, const vector< Point2f > &pts1, const vector< Point2f > &pts2, bool useDefault=false) |
| void | findCentroid (vector< featureTrack > &tracks, Point3d ¢roid, Point3d &stdDeviation) |
| void | findCentroidAndSpread (vector< featureTrack > &tracks, Point3d ¢roid, Point3d &deviations) |
| void | findFeaturesForPoints (vector< featureTrack > &tracks, vector< Point2f > &pts1, vector< Point2f > &pts2, vector< Point3d > &pts3d, int idx1, int idx2) |
| void | findFourTransformations (Mat *C, const Mat &E, const Mat &K, const vector< Point2f > &pts1, const vector< Point2f > &pts2) |
| void | findP1Matrix (Mat &P1, const Mat &R, const Mat &t) |
| void | findTriangulatableTracks (vector< featureTrack > &tracks, vector< unsigned int > &indices, unsigned int latest_index, unsigned int min_length=10) |
| void | getActive3dPoints (vector< featureTrack > &tracks, vector< unsigned int > &indices, vector< Point3d > &cloud) |
| void | getActiveTracks (vector< unsigned int > &indices, vector< featureTrack > &tracks, int idx1, int idx2) |
| void | getCorrespondingPoints (vector< featureTrack > &tracks, const vector< Point2f > &pts1, vector< Point2f > &pts2, int idx0, int idx1) |
| double | getDistanceInUnits (const Mat &t) |
| void | getIndicesForTriangulation (vector< unsigned int > &dst, vector< unsigned int > &src, vector< unsigned int > &already_triangulated) |
| void | getPoints3dFromTracks (vector< featureTrack > &tracks, vector< Point3d > &cloud, int idx1, int idx2) |
| void | getPointsFromTracks (vector< featureTrack > &tracks, vector< Point2f > &pts1, vector< Point2f > &pts2, int idx1, int idx2) |
| double | getQuaternionAngle (const Quaterniond &q1, const Quaterniond &q2) |
| double | getRotationInDegrees (const Mat &R) |
| void | getTranslationBetweenCameras (Mat &C1, Mat &C2, double *translations) |
| void | getTriangulatedFullSpanPoints (vector< featureTrack > &tracks, vector< Point2f > &pts1, vector< Point2f > &pts2, int idx1, int idx2, vector< Point3f > &points3) |
| void | getWandZ (Mat &W, Mat &Winv, Mat &Z) |
| void | initializeP0 (Mat &P) |
| void | IterativeLinearLSTriangulation (Mat &dst, const Point3d &u, const Mat &P, const Point3d &u1, const Mat &P1) |
| void | LinearLSTriangulation (Mat &dst, const Point3d &u, const Mat &P, const Point3d &u1, const Mat &P1) |
| void | matrixToQuaternion (const Mat &mat, Quaterniond &quat) |
| void | obtainAppropriateBaseTransformation (Mat &C0, vector< featureTrack > &tracks) |
| bool | pointIsInFront (const Mat &C, const Point3d &pt) |
| int | pointsInFront (const Mat &C1, const Mat &K, const vector< Point2f > &pts1, const vector< Point2f > &pts2) |
| int | pointsInFront (const Mat &C1, const Mat &C2, const vector< Point3d > &pts) |
| void | printSystemSummary (SysSBA &sys) |
| void | projectionToRotation (const Mat &src, Mat &dst) |
| void | projectionToTransformation (const Mat &proj, Mat &trans) |
| unsigned int | putativelyTriangulateNewTracks (vector< featureTrack > &tracks, vector< unsigned int > &indices, cameraParameters &cameraData, Mat *cameras, unsigned int earliest_index, unsigned int latest_index) |
| void | quaternionToMatrix (const Quaterniond &quat, Mat &mat) |
| float | ReciprocalSqrt (float x) |
| void | reconstructSubsequence (vector< featureTrack > &tracks, vector< Point3d > &ptCloud, int idx1, int idx2) |
| void | reduceActiveToTriangulated (vector< featureTrack > &tracks, vector< unsigned int > &indices, vector< unsigned int > &untriangulated) |
| void | reduceVectorsToTrackedPoints (const vector< Point2f > &points1, vector< Point2f > &trackedPoints1, const vector< Point2f > &points2, vector< Point2f > &trackedPoints2, vector< uchar > &statusVec) |
| void | removeShortTracks (vector< featureTrack > &tracks, int idx1, int idx2) |
| void | retrieveAllCameras (Mat *allCameraPoses, const SysSBA &sys) |
| void | retrieveAllPoints (vector< Point3d > &pts, const SysSBA &sys) |
| void | retrieveCamera (Mat &camera, const SysSBA &sys, unsigned int idx) |
| void | retrieveCameraPose (SysSBA &sys, Mat &camPose, int idx) |
| void | reverseTranslation (Mat &C) |
| void | rotationToProjection (const Mat &src, Mat &dst) |
| void | summarizeTransformation (const Mat &C, char *summary) |
| void | transfer3dPoint (const Point3d &src, Point3d &dst, const Mat &C) |
| void | transfer3DPoints (const vector< Point3d > &src, vector< Point3d > &dst, const Mat &C) |
| void | transformationToProjection (const Mat &trans, Mat &proj) |
| void | Triangulate (const Point2f &pt1, const Point2f &pt2, const Mat &K, const Mat &Kinv, const Mat &P1, const Mat &P2, Point3d &xyzPoint, bool debug=false) |
| int | TriangulateNewTracks (vector< featureTrack > &trackVector, const int index1, const int index2, const Mat &K, const Mat &K_inv, const Mat &P0, const Mat &P1, bool initializeOnFocalPlane=false) |
| void | TriangulatePoints (const vector< Point2f > &pt_set1, const vector< Point2f > &pt_set2, const Mat &K, const Mat &Kinv, const Mat &P, const Mat &P1, vector< Point3d > &pointcloud, vector< Point2f > &correspImg1Pt) |
| void | triangulateTracks (vector< featureTrack > &tracks, vector< unsigned int > &indices, cameraParameters &cameraData, Mat *cameras, unsigned int earliest_index, unsigned int latest_index) |
| void | updateCameraNode (SysSBA &sys, Mat R, Mat t, int img1, int img2) |
| void | updateCameraNode_2 (SysSBA &sys, const Mat &C, int image_index) |
| void | updateCameraNode_2 (SysSBA &sys, const Mat &R, const Mat &t, int image_index) |
| void | updateSystemTracks (SysSBA &sys, vector< featureTrack > &tracks, unsigned int start_index) |
| void | updateTracks (vector< featureTrack > &trackVector, const SysSBA &sys) |
| void | updateTriangulatedPoints (vector< featureTrack > &tracks, vector< unsigned int > &indices, vector< Point3d > &cloud) |
Declarations for triangulation and other recovery-of-3D structure functions.
Definition in file reconstruction.hpp.
| #define _USE_MATH_DEFINES |
Definition at line 33 of file reconstruction.hpp.
| #define EPSILON 0.00001 |
Definition at line 43 of file reconstruction.hpp.
| #define POSITION_LIMIT 1000 |
Definition at line 40 of file reconstruction.hpp.
| void addBlankCamera | ( | SysSBA & | sys, | |
| cameraParameters & | cameraData, | |||
| bool | isFixed = false | |||
| ) |
Definition at line 2286 of file reconstruction.cpp.
| void addFixedCamera | ( | SysSBA & | sys, | |
| cameraParameters & | cameraData, | |||
| const Mat & | C | |||
| ) |
Definition at line 1966 of file reconstruction.cpp.
| void addNewCamera | ( | SysSBA & | sys, | |
| cameraParameters & | cameraData, | |||
| const Mat & | C | |||
| ) |
Definition at line 1971 of file reconstruction.cpp.
| void addNewPoints | ( | SysSBA & | sys, | |
| const vector< Point3d > & | pc | |||
| ) |
Definition at line 2146 of file reconstruction.cpp.
| unsigned int addNewPoints | ( | vector< featureTrack > & | tracks, | |
| vector< unsigned int > & | indices, | |||
| cameraParameters & | cameraData, | |||
| Mat * | cameras, | |||
| unsigned int | earliest_index, | |||
| unsigned int | latest_index | |||
| ) |
Definition at line 928 of file reconstruction.cpp.
| int addToTracks | ( | SysSBA & | sys, | |
| int | im1, | |||
| vector< Point2f > & | pts1, | |||
| int | im2, | |||
| vector< Point2f > & | pts2 | |||
| ) |
Definition at line 2162 of file reconstruction.cpp.
| void assignIntrinsicsToP0 | ( | Mat & | P0, | |
| const Mat & | K | |||
| ) |
Definition at line 1900 of file reconstruction.cpp.
| void assignTracksToSBA | ( | SysSBA & | sys, | |
| vector< featureTrack > & | trackVector, | |||
| int | maxIndex | |||
| ) |
Definition at line 2051 of file reconstruction.cpp.
| double calcFrameScore | ( | double | geomScore, | |
| int | numFeatures, | |||
| int | numTracks | |||
| ) |
Definition at line 1828 of file reconstruction.cpp.
| double calcGeometryScore | ( | int | numInliers_H, | |
| int | numInliers_F, | |||
| double | sampsonError_H, | |||
| double | sampsonError_F | |||
| ) |
Definition at line 1892 of file reconstruction.cpp.
| double calcInlierGeometryDistance | ( | vector< Point2f > & | points1, | |
| vector< Point2f > & | points2, | |||
| Mat & | mat, | |||
| Mat & | mask, | |||
| int | distMethod = SAMPSON_DISTANCE | |||
| ) |
Definition at line 1762 of file reconstruction.cpp.
| double calcSampsonDistance | ( | Point2f & | pt1, | |
| Point2f & | pt2, | |||
| Mat & | F | |||
| ) |
Definition at line 1859 of file reconstruction.cpp.
| double calcSampsonError | ( | vector< Point2f > & | points1, | |
| vector< Point2f > & | points2, | |||
| Mat & | H, | |||
| Mat & | Hmask | |||
| ) |
Definition at line 1837 of file reconstruction.cpp.
| void combineTransforms | ( | Mat & | CN, | |
| const Mat & | C0, | |||
| const Mat & | C1 | |||
| ) |
Definition at line 1929 of file reconstruction.cpp.
| void compileTransform | ( | Mat & | c, | |
| const Mat & | R, | |||
| const Mat & | t | |||
| ) |
Definition at line 1740 of file reconstruction.cpp.
| void constrainDodgyPoints | ( | SysSBA & | sys | ) |
Definition at line 2806 of file reconstruction.cpp.
| void convertPoint3dToMat | ( | const Point3d & | src, | |
| Mat & | dst | |||
| ) |
Definition at line 1613 of file reconstruction.cpp.
| void convertProjectionMatCVToEigen | ( | const Mat & | mat, | |
| Eigen::Matrix< double, 3, 4 > | m | |||
| ) |
Definition at line 2399 of file reconstruction.cpp.
| void convertProjectionMatEigenToCV | ( | const Eigen::Matrix< double, 3, 4 > | m, | |
| Mat & | mat | |||
| ) |
Definition at line 2418 of file reconstruction.cpp.
| void convertVec4dToMat | ( | const Vector4d & | vec4, | |
| Mat & | mat | |||
| ) |
Definition at line 1976 of file reconstruction.cpp.
| int countActiveTriangulatedTracks | ( | vector< unsigned int > & | indices, | |
| vector< featureTrack > & | tracks | |||
| ) |
Definition at line 94 of file reconstruction.cpp.
| void decomposeTransform | ( | const Mat & | c, | |
| Mat & | R, | |||
| Mat & | t | |||
| ) |
Definition at line 1719 of file reconstruction.cpp.
| Quaterniond defaultQuaternion | ( | ) |
Definition at line 2325 of file reconstruction.cpp.
| double dotProduct | ( | const Quaterniond & | q1, | |
| const Quaterniond & | q2 | |||
| ) |
Definition at line 1921 of file reconstruction.cpp.
| double dotProduct | ( | const Mat & | vec1, | |
| const Mat & | vec2 | |||
| ) |
Definition at line 1935 of file reconstruction.cpp.
| void estimateNewPose | ( | vector< featureTrack > & | tracks, | |
| Mat & | K, | |||
| int | idx, | |||
| Mat & | pose | |||
| ) |
Definition at line 2101 of file reconstruction.cpp.
| bool estimatePoseFromKnownPoints | ( | Mat & | dst, | |
| cameraParameters | camData, | |||
| vector< featureTrack > & | tracks, | |||
| unsigned int | index, | |||
| const Mat & | guide | |||
| ) |
Definition at line 393 of file reconstruction.cpp.
| void ExtractPointCloud | ( | vector< Point3d > & | cloud, | |
| vector< featureTrack > & | trackVector | |||
| ) |
Definition at line 2891 of file reconstruction.cpp.
| void filterToActivePoints | ( | vector< featureTrack > & | tracks, | |
| vector< Point2f > & | pts1, | |||
| vector< Point2f > & | pts2, | |||
| vector< unsigned int > & | indices, | |||
| int | idx1, | |||
| int | idx2 | |||
| ) |
Definition at line 260 of file reconstruction.cpp.
| void filterToCompleteTracks | ( | vector< unsigned int > & | dst, | |
| vector< unsigned int > & | src, | |||
| vector< featureTrack > & | tracks, | |||
| int | idx1, | |||
| int | idx2 | |||
| ) |
Definition at line 305 of file reconstruction.cpp.
| int findBestCandidate | ( | const Mat * | CX, | |
| const Mat & | K, | |||
| const vector< Point2f > & | pts1, | |||
| const vector< Point2f > & | pts2, | |||
| Mat & | C | |||
| ) |
Definition at line 22 of file reconstruction.cpp.
| bool findBestReconstruction | ( | const Mat & | P0, | |
| Mat & | P1, | |||
| Mat & | R, | |||
| Mat & | t, | |||
| const SVD & | svd, | |||
| const Mat & | K, | |||
| const vector< Point2f > & | pts1, | |||
| const vector< Point2f > & | pts2, | |||
| bool | useDefault = false | |||
| ) |
Definition at line 2922 of file reconstruction.cpp.
| void findCentroid | ( | vector< featureTrack > & | tracks, | |
| Point3d & | centroid, | |||
| Point3d & | stdDeviation | |||
| ) |
Definition at line 3465 of file reconstruction.cpp.
| void findCentroidAndSpread | ( | vector< featureTrack > & | tracks, | |
| Point3d & | centroid, | |||
| Point3d & | deviations | |||
| ) |
Definition at line 1237 of file reconstruction.cpp.
| void findFeaturesForPoints | ( | vector< featureTrack > & | tracks, | |
| vector< Point2f > & | pts1, | |||
| vector< Point2f > & | pts2, | |||
| vector< Point3d > & | pts3d, | |||
| int | idx1, | |||
| int | idx2 | |||
| ) |
Definition at line 53 of file reconstruction.cpp.
| void findFourTransformations | ( | Mat * | C, | |
| const Mat & | E, | |||
| const Mat & | K, | |||
| const vector< Point2f > & | pts1, | |||
| const vector< Point2f > & | pts2 | |||
| ) |
Definition at line 1315 of file reconstruction.cpp.
| void findP1Matrix | ( | Mat & | P1, | |
| const Mat & | R, | |||
| const Mat & | t | |||
| ) |
Definition at line 3340 of file reconstruction.cpp.
| void findTriangulatableTracks | ( | vector< featureTrack > & | tracks, | |
| vector< unsigned int > & | indices, | |||
| unsigned int | latest_index, | |||
| unsigned int | min_length = 10 | |||
| ) |
Definition at line 592 of file reconstruction.cpp.
| void getActive3dPoints | ( | vector< featureTrack > & | tracks, | |
| vector< unsigned int > & | indices, | |||
| vector< Point3d > & | cloud | |||
| ) |
Definition at line 295 of file reconstruction.cpp.
| void getActiveTracks | ( | vector< unsigned int > & | indices, | |
| vector< featureTrack > & | tracks, | |||
| int | idx1, | |||
| int | idx2 | |||
| ) |
Definition at line 346 of file reconstruction.cpp.
| void getCorrespondingPoints | ( | vector< featureTrack > & | tracks, | |
| const vector< Point2f > & | pts1, | |||
| vector< Point2f > & | pts2, | |||
| int | idx0, | |||
| int | idx1 | |||
| ) |
Definition at line 483 of file reconstruction.cpp.
| double getDistanceInUnits | ( | const Mat & | t | ) |
Definition at line 1954 of file reconstruction.cpp.
| void getIndicesForTriangulation | ( | vector< unsigned int > & | dst, | |
| vector< unsigned int > & | src, | |||
| vector< unsigned int > & | already_triangulated | |||
| ) |
Definition at line 110 of file reconstruction.cpp.
| void getPoints3dFromTracks | ( | vector< featureTrack > & | tracks, | |
| vector< Point3d > & | cloud, | |||
| int | idx1, | |||
| int | idx2 | |||
| ) |
Definition at line 1287 of file reconstruction.cpp.
| void getPointsFromTracks | ( | vector< featureTrack > & | tracks, | |
| vector< Point2f > & | pts1, | |||
| vector< Point2f > & | pts2, | |||
| int | idx1, | |||
| int | idx2 | |||
| ) |
Definition at line 1160 of file reconstruction.cpp.
| double getQuaternionAngle | ( | const Quaterniond & | q1, | |
| const Quaterniond & | q2 | |||
| ) |
Definition at line 1911 of file reconstruction.cpp.
| double getRotationInDegrees | ( | const Mat & | R | ) |
Definition at line 1944 of file reconstruction.cpp.
| void getTranslationBetweenCameras | ( | Mat & | C1, | |
| Mat & | C2, | |||
| double * | translations | |||
| ) |
Definition at line 663 of file reconstruction.cpp.
| void getTriangulatedFullSpanPoints | ( | vector< featureTrack > & | tracks, | |
| vector< Point2f > & | pts1, | |||
| vector< Point2f > & | pts2, | |||
| int | idx1, | |||
| int | idx2, | |||
| vector< Point3f > & | points3 | |||
| ) |
Definition at line 554 of file reconstruction.cpp.
| void getWandZ | ( | Mat & | W, | |
| Mat & | Winv, | |||
| Mat & | Z | |||
| ) |
Definition at line 3305 of file reconstruction.cpp.
| void initializeP0 | ( | Mat & | P | ) |
Definition at line 3171 of file reconstruction.cpp.
| void IterativeLinearLSTriangulation | ( | Mat & | dst, | |
| const Point3d & | u, | |||
| const Mat & | P, | |||
| const Point3d & | u1, | |||
| const Mat & | P1 | |||
| ) |
Definition at line 3227 of file reconstruction.cpp.
| void LinearLSTriangulation | ( | Mat & | dst, | |
| const Point3d & | u, | |||
| const Mat & | P, | |||
| const Point3d & | u1, | |||
| const Mat & | P1 | |||
| ) |
Definition at line 3187 of file reconstruction.cpp.
| void matrixToQuaternion | ( | const Mat & | mat, | |
| Quaterniond & | quat | |||
| ) |
Definition at line 2490 of file reconstruction.cpp.
| void obtainAppropriateBaseTransformation | ( | Mat & | C0, | |
| vector< featureTrack > & | tracks | |||
| ) |
Definition at line 1203 of file reconstruction.cpp.
| bool pointIsInFront | ( | const Mat & | C, | |
| const Point3d & | pt | |||
| ) |
Definition at line 1476 of file reconstruction.cpp.
| int pointsInFront | ( | const Mat & | C1, | |
| const Mat & | K, | |||
| const vector< Point2f > & | pts1, | |||
| const vector< Point2f > & | pts2 | |||
| ) |
Definition at line 1535 of file reconstruction.cpp.
| int pointsInFront | ( | const Mat & | C1, | |
| const Mat & | C2, | |||
| const vector< Point3d > & | pts | |||
| ) |
Definition at line 1494 of file reconstruction.cpp.
| void printSystemSummary | ( | SysSBA & | sys | ) |
Definition at line 2320 of file reconstruction.cpp.
| void projectionToRotation | ( | const Mat & | src, | |
| Mat & | dst | |||
| ) |
Definition at line 2439 of file reconstruction.cpp.
| void projectionToTransformation | ( | const Mat & | proj, | |
| Mat & | trans | |||
| ) |
Definition at line 1437 of file reconstruction.cpp.
| unsigned int putativelyTriangulateNewTracks | ( | vector< featureTrack > & | tracks, | |
| vector< unsigned int > & | indices, | |||
| cameraParameters & | cameraData, | |||
| Mat * | cameras, | |||
| unsigned int | earliest_index, | |||
| unsigned int | latest_index | |||
| ) |
Definition at line 1045 of file reconstruction.cpp.
| void quaternionToMatrix | ( | const Quaterniond & | quat, | |
| Mat & | mat | |||
| ) |
Definition at line 1676 of file reconstruction.cpp.
| float ReciprocalSqrt | ( | float | x | ) |
Definition at line 2477 of file reconstruction.cpp.
| void reconstructSubsequence | ( | vector< featureTrack > & | tracks, | |
| vector< Point3d > & | ptCloud, | |||
| int | idx1, | |||
| int | idx2 | |||
| ) |
Definition at line 139 of file reconstruction.cpp.
| void reduceActiveToTriangulated | ( | vector< featureTrack > & | tracks, | |
| vector< unsigned int > & | indices, | |||
| vector< unsigned int > & | untriangulated | |||
| ) |
Definition at line 246 of file reconstruction.cpp.
| void reduceVectorsToTrackedPoints | ( | const vector< Point2f > & | points1, | |
| vector< Point2f > & | trackedPoints1, | |||
| const vector< Point2f > & | points2, | |||
| vector< Point2f > & | trackedPoints2, | |||
| vector< uchar > & | statusVec | |||
| ) |
Definition at line 2904 of file reconstruction.cpp.
| void removeShortTracks | ( | vector< featureTrack > & | tracks, | |
| int | idx1, | |||
| int | idx2 | |||
| ) |
Definition at line 143 of file reconstruction.cpp.
| void retrieveAllCameras | ( | Mat * | allCameraPoses, | |
| const SysSBA & | sys | |||
| ) |
Definition at line 2032 of file reconstruction.cpp.
| void retrieveAllPoints | ( | vector< Point3d > & | pts, | |
| const SysSBA & | sys | |||
| ) |
Definition at line 1998 of file reconstruction.cpp.
| void retrieveCamera | ( | Mat & | camera, | |
| const SysSBA & | sys, | |||
| unsigned int | idx | |||
| ) |
Definition at line 2022 of file reconstruction.cpp.
| void retrieveCameraPose | ( | SysSBA & | sys, | |
| Mat & | camPose, | |||
| int | idx | |||
| ) |
Definition at line 2011 of file reconstruction.cpp.
| void reverseTranslation | ( | Mat & | C | ) |
Definition at line 43 of file reconstruction.cpp.
| void rotationToProjection | ( | const Mat & | src, | |
| Mat & | dst | |||
| ) |
Definition at line 2456 of file reconstruction.cpp.
| void summarizeTransformation | ( | const Mat & | C, | |
| char * | summary | |||
| ) |
Definition at line 7 of file reconstruction.cpp.
| void transfer3dPoint | ( | const Point3d & | src, | |
| Point3d & | dst, | |||
| const Mat & | C | |||
| ) |
Definition at line 1623 of file reconstruction.cpp.
| void transfer3DPoints | ( | const vector< Point3d > & | src, | |
| vector< Point3d > & | dst, | |||
| const Mat & | C | |||
| ) |
Definition at line 1644 of file reconstruction.cpp.
| void transformationToProjection | ( | const Mat & | trans, | |
| Mat & | proj | |||
| ) |
Definition at line 1456 of file reconstruction.cpp.
| void Triangulate | ( | const Point2f & | pt1, | |
| const Point2f & | pt2, | |||
| const Mat & | K, | |||
| const Mat & | Kinv, | |||
| const Mat & | P1, | |||
| const Mat & | P2, | |||
| Point3d & | xyzPoint, | |||
| bool | debug = false | |||
| ) |
Definition at line 3367 of file reconstruction.cpp.
| int TriangulateNewTracks | ( | vector< featureTrack > & | trackVector, | |
| const int | index1, | |||
| const int | index2, | |||
| const Mat & | K, | |||
| const Mat & | K_inv, | |||
| const Mat & | P0, | |||
| const Mat & | P1, | |||
| bool | initializeOnFocalPlane = false | |||
| ) |
Definition at line 2825 of file reconstruction.cpp.
| void TriangulatePoints | ( | const vector< Point2f > & | pt_set1, | |
| const vector< Point2f > & | pt_set2, | |||
| const Mat & | K, | |||
| const Mat & | Kinv, | |||
| const Mat & | P, | |||
| const Mat & | P1, | |||
| vector< Point3d > & | pointcloud, | |||
| vector< Point2f > & | correspImg1Pt | |||
| ) |
Definition at line 3441 of file reconstruction.cpp.
| void triangulateTracks | ( | vector< featureTrack > & | tracks, | |
| vector< unsigned int > & | indices, | |||
| cameraParameters & | cameraData, | |||
| Mat * | cameras, | |||
| unsigned int | earliest_index, | |||
| unsigned int | latest_index | |||
| ) |
Definition at line 673 of file reconstruction.cpp.
| void updateCameraNode | ( | SysSBA & | sys, | |
| Mat | R, | |||
| Mat | t, | |||
| int | img1, | |||
| int | img2 | |||
| ) |
Definition at line 2671 of file reconstruction.cpp.
| void updateCameraNode_2 | ( | SysSBA & | sys, | |
| const Mat & | C, | |||
| int | image_index | |||
| ) |
Definition at line 2331 of file reconstruction.cpp.
| void updateCameraNode_2 | ( | SysSBA & | sys, | |
| const Mat & | R, | |||
| const Mat & | t, | |||
| int | image_index | |||
| ) |
Definition at line 2366 of file reconstruction.cpp.
| void updateSystemTracks | ( | SysSBA & | sys, | |
| vector< featureTrack > & | tracks, | |||
| unsigned int | start_index | |||
| ) |
Definition at line 162 of file reconstruction.cpp.
| void updateTracks | ( | vector< featureTrack > & | trackVector, | |
| const SysSBA & | sys | |||
| ) |
Definition at line 1985 of file reconstruction.cpp.
| void updateTriangulatedPoints | ( | vector< featureTrack > & | tracks, | |
| vector< unsigned int > & | indices, | |||
| vector< Point3d > & | cloud | |||
| ) |
Definition at line 226 of file reconstruction.cpp.