Declarations for triangulation and other recovery-of-3D structure functions. More...
#include "general_resources.hpp"#include "opencv_resources.hpp"#include "ros_resources.hpp"#include "camera.hpp"#include "geometry.hpp"#include "tracks.hpp"#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 | CLUSTER_MEAN_MODE 1 |
| #define | DEFAULT_MEAN_MAX_DIST 0.20 |
| #define | DEFAULT_MEAN_MODE 0 |
| #define | DEFAULT_NEAR_RADIUS 0.3 |
| #define | EPSILON 0.00001 |
| #define | MAX_REPROJECTION_DISPARITY 20.0 |
| #define | POSITION_LIMIT 1000 |
Functions | |
| void | addBlankCamera (SysSBA &sys, cameraParameters &cameraData, bool isFixed=false) |
| void | addFixedCamera (SysSBA &sys, cameraParameters &cameraData, const cv::Mat &C) |
| void | addNewCamera (SysSBA &sys, cameraParameters &cameraData, const cv::Mat &C) |
| unsigned int | addNewPoints (vector< featureTrack > &tracks, vector< unsigned int > &indices, cameraParameters &cameraData, cv::Mat *cameras, unsigned int earliest_index, unsigned int latest_index) |
| void | addNewPoints (SysSBA &sys, const vector< cv::Point3d > &pc) |
| int | addToTracks (SysSBA &sys, int im1, vector< cv::Point2f > &pts1, int im2, vector< cv::Point2f > &pts2) |
| void | assignIntrinsicsToP0 (cv::Mat &P0, const cv::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< cv::Point2f > &points1, vector< cv::Point2f > &points2, cv::Mat &mat, cv::Mat &mask, int distMethod=SAMPSON_DISTANCE) |
| double | calcSampsonDistance (cv::Point2f &pt1, cv::Point2f &pt2, cv::Mat &F) |
| double | calcSampsonError (vector< cv::Point2f > &points1, vector< cv::Point2f > &points2, cv::Mat &H, cv::Mat &Hmask) |
| void | combineTransforms (cv::Mat &CN, const cv::Mat &C0, const cv::Mat &C1) |
| void | compileTransform (cv::Mat &c, const cv::Mat &R, const cv::Mat &t) |
| void | constrainDodgyPoints (SysSBA &sys) |
| void | convertPoint3dToMat (const cv::Point3d &src, cv::Mat &dst) |
| void | convertProjectionMatCVToEigen (const cv::Mat &mat, Eigen::Matrix< double, 3, 4 > m) |
| void | convertProjectionMatEigenToCV (const Eigen::Matrix< double, 3, 4 > m, cv::Mat &mat) |
| void | convertVec4dToMat (const Vector4d &vec4, cv::Mat &mat) |
| int | countActiveTriangulatedTracks (vector< unsigned int > &indices, vector< featureTrack > &tracks) |
| int | countTriangulatedTracks (const vector< featureTrack > &tracks) |
| void | decomposeTransform (const cv::Mat &c, cv::Mat &R, cv::Mat &t) |
| Quaterniond | defaultQuaternion () |
| double | dotProduct (const cv::Mat &vec1, const cv::Mat &vec2) |
| double | dotProduct (const Quaterniond &q1, const Quaterniond &q2) |
| void | estimateNewPose (vector< featureTrack > &tracks, cv::Mat &K, int idx, cv::Mat &pose) |
| bool | estimatePoseFromKnownPoints (cv::Mat &dst, cameraParameters camData, vector< featureTrack > &tracks, unsigned int index, const cv::Mat &guide, unsigned minAppearances=1, unsigned int iterCount=100, double maxReprojErr=4.0, double inliersPercentage=0.9, double *reprojError=0, double *pnpInlierProp=0, bool debug=false) |
| void | ExtractPointCloud (vector< cv::Point3d > &cloud, vector< featureTrack > &trackVector) |
| void | filterNearPoints (vector< featureTrack > &featureTrackVector, double x, double y, double z, double limit=DEFAULT_NEAR_RADIUS) |
| void | filterToActivePoints (vector< featureTrack > &tracks, vector< cv::Point2f > &pts1, vector< cv::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 cv::Mat *CX, const cv::Mat &K, const vector< cv::Point2f > &pts1, const vector< cv::Point2f > &pts2, cv::Mat &C) |
| bool | findBestReconstruction (const cv::Mat &P0, cv::Mat &P1, cv::Mat &R, cv::Mat &t, const cv::SVD &svd, const cv::Mat &K, const vector< cv::Point2f > &pts1, const vector< cv::Point2f > &pts2, bool useDefault=false) |
| void | findCentroid (vector< featureTrack > &tracks, cv::Point3d ¢roid, cv::Point3d &stdDeviation) |
| void | findCentroidAndSpread (vector< featureTrack > &tracks, cv::Point3d ¢roid, cv::Point3d &deviations) |
| bool | findClusterMean (const vector< cv::Point3d > &estimatedLocations, cv::Point3d &pt3d, int mode=DEFAULT_MEAN_MODE, int minEstimates=3, double maxStandardDev=0.1) |
| void | findFeaturesForPoints (vector< featureTrack > &tracks, vector< cv::Point2f > &pts1, vector< cv::Point2f > &pts2, vector< cv::Point3d > &pts3d, int idx1, int idx2) |
| void | findFourTransformations (cv::Mat *C, const cv::Mat &E, const cv::Mat &K, const vector< cv::Point2f > &pts1, const vector< cv::Point2f > &pts2) |
| void | findP1Matrix (cv::Mat &P1, const cv::Mat &R, const cv::Mat &t) |
| void | findTriangulatableTracks (vector< featureTrack > &tracks, vector< unsigned int > &indices, vector< unsigned int > &cameras, unsigned int min_length=10) |
| void | findTriangulatableTracks3 (vector< featureTrack > &tracks, vector< unsigned int > &indices, int latest_index=-1, unsigned int min_length=10) |
| void | getActive3dPoints (vector< featureTrack > &tracks, vector< unsigned int > &indices, vector< cv::Point3d > &cloud) |
| void | getActiveTracks (vector< unsigned int > &indices, vector< featureTrack > &tracks, int idx1, int idx2) |
| void | getCorrespondingPoints (vector< featureTrack > &tracks, const vector< cv::Point2f > &pts1, vector< cv::Point2f > &pts2, int idx0, int idx1) |
| double | getDistanceInUnits (const cv::Mat &t) |
| void | getIndicesForTriangulation (vector< unsigned int > &dst, vector< unsigned int > &src, vector< unsigned int > &already_triangulated) |
| void | getPoints3dFromTracks (vector< featureTrack > &tracks, vector< cv::Point3d > &cloud, int idx1=-1, int idx2=-1) |
| void | getPointsFromTracks (vector< featureTrack > &tracks, vector< cv::Point2f > &pts1, vector< cv::Point2f > &pts2, int idx1, int idx2) |
| double | getQuaternionAngle (const Quaterniond &q1, const Quaterniond &q2) |
| double | getRotationInDegrees (const cv::Mat &R) |
| void | getTranslationBetweenCameras (cv::Mat &C1, cv::Mat &C2, double *translations) |
| void | getTriangulatedFullSpanPoints (vector< featureTrack > &tracks, vector< cv::Point2f > &pts1, vector< cv::Point2f > &pts2, int idx1, int idx2, vector< cv::Point3f > &points3) |
| void | getWandZ (cv::Mat &W, cv::Mat &Winv, cv::Mat &Z) |
| void | initializeP0 (cv::Mat &P) |
| int | initialTrackTriangulation (vector< featureTrack > &tracks, vector< unsigned int > &indices, cameraParameters &cameraData, geometry_msgs::PoseStamped *keyframePoses, unsigned int keyframeCount, double minSeparation=0.2, double maxSeparation=1.0, int minEstimates=3, double maxStandardDev=0.1, double maxReprojectionDisparity=MAX_REPROJECTION_DISPARITY) |
| int | initialTrackTriangulationDummy (vector< featureTrack > &tracks, vector< unsigned int > &indices, cameraParameters &cameraData, geometry_msgs::PoseStamped *keyframePoses, unsigned int keyframeCount, double minSeparation=0.2, double maxSeparation=1.0, int minEstimates=3, double maxStandardDev=0.1, bool handedness=false, int xCode=0) |
| void | IterativeLinearLSTriangulation (cv::Mat &dst, const cv::Point3d &u1, const cv::Mat &P1, const cv::Point3d &u2, const cv::Mat &P2) |
| void | LinearLSTriangulation (cv::Mat &dst, const cv::Point3d &u1, const cv::Mat &P1, const cv::Point3d &u2, const cv::Mat &P2) |
| void | obtainAppropriateBaseTransformation (cv::Mat &C0, vector< featureTrack > &tracks) |
| bool | pointIsInFront (const cv::Mat &C, const cv::Point3d &pt) |
| int | pointsInFront (const cv::Mat &C1, const cv::Mat &C2, const vector< cv::Point3d > &pts) |
| int | pointsInFront (const cv::Mat &C1, const cv::Mat &K, const vector< cv::Point2f > &pts1, const vector< cv::Point2f > &pts2) |
| void | printSystemSummary (SysSBA &sys) |
| unsigned int | putativelyTriangulateNewTracks (vector< featureTrack > &tracks, vector< unsigned int > &indices, cameraParameters &cameraData, cv::Mat *cameras, unsigned int earliest_index, unsigned int latest_index) |
| float | ReciprocalSqrt (float x) |
| void | reconstructSubsequence (vector< featureTrack > &tracks, vector< cv::Point3d > &ptCloud, int idx1, int idx2) |
| void | reduceActiveToTriangulated (vector< featureTrack > &tracks, vector< unsigned int > &indices, vector< unsigned int > &untriangulated) |
| void | reduceVectorsToTrackedPoints (const vector< cv::Point2f > &points1, vector< cv::Point2f > &trackedPoints1, const vector< cv::Point2f > &points2, vector< cv::Point2f > &trackedPoints2, vector< uchar > &statusVec) |
| void | removeShortTracks (vector< featureTrack > &tracks, int idx1, int idx2) |
| void | retrieveAllCameras (cv::Mat *allCameraPoses, const SysSBA &sys) |
| void | retrieveAllPoints (vector< cv::Point3d > &pts, const SysSBA &sys) |
| double | retrieveCameraPose (const SysSBA &sys, unsigned int idx, geometry_msgs::Pose &pose) |
| void | retrieveCameraPose (const SysSBA &sys, unsigned int idx, cv::Mat &camera) |
| void | reverseTranslation (cv::Mat &C) |
| void | summarizeTransformation (const cv::Mat &C, char *summary) |
| void | transfer3dPoint (const cv::Point3d &src, cv::Point3d &dst, const cv::Mat &C) |
| void | transfer3DPoints (const vector< cv::Point3d > &src, vector< cv::Point3d > &dst, const cv::Mat &C) |
| void | Triangulate (const cv::Point2f &pt1, const cv::Point2f &pt2, const cv::Mat &K, const cv::Mat &Kinv, const cv::Mat &P1, const cv::Mat &P2, cv::Point3d &xyzPoint, bool debug=false) |
| void | Triangulate_1 (const cv::Point2d &pt1, const cv::Point2d &pt2, const cv::Mat &K, const cv::Mat &Kinv, const cv::Mat &P1, const cv::Mat &P2, cv::Point3d &xyzPoint, bool iterate=true) |
| int | TriangulateNewTracks (vector< featureTrack > &trackVector, const int index1, const int index2, const cv::Mat &K, const cv::Mat &K_inv, const cv::Mat &P0, const cv::Mat &P1, bool initializeOnFocalPlane=false) |
| void | TriangulatePoints (const vector< cv::Point2f > &pt_set1, const vector< cv::Point2f > &pt_set2, const cv::Mat &K, const cv::Mat &Kinv, const cv::Mat &P, const cv::Mat &P1, vector< cv::Point3d > &pointcloud, vector< cv::Point2f > &correspImg1Pt) |
| void | triangulateTracks (vector< featureTrack > &tracks, vector< unsigned int > &indices, cameraParameters &cameraData, cv::Mat *cameras, unsigned int earliest_index, unsigned int latest_index) |
| void | updateCameraNode (SysSBA &sys, cv::Mat R, cv::Mat t, int img1, int img2) |
| void | updateCameraNode_2 (SysSBA &sys, const cv::Mat &R, const cv::Mat &t, int image_index) |
| void | updateCameraNode_2 (SysSBA &sys, const cv::Mat &C, 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< cv::Point3d > &cloud) |
Declarations for triangulation and other recovery-of-3D structure functions.
Definition in file reconstruction.hpp.
| #define _USE_MATH_DEFINES |
Definition at line 22 of file reconstruction.hpp.
| #define CLUSTER_MEAN_MODE 1 |
Definition at line 34 of file reconstruction.hpp.
| #define DEFAULT_MEAN_MAX_DIST 0.20 |
Definition at line 32 of file reconstruction.hpp.
| #define DEFAULT_MEAN_MODE 0 |
Definition at line 33 of file reconstruction.hpp.
| #define DEFAULT_NEAR_RADIUS 0.3 |
Definition at line 25 of file reconstruction.hpp.
| #define EPSILON 0.00001 |
Definition at line 37 of file reconstruction.hpp.
| #define MAX_REPROJECTION_DISPARITY 20.0 |
Definition at line 35 of file reconstruction.hpp.
| #define POSITION_LIMIT 1000 |
Definition at line 31 of file reconstruction.hpp.
| void addBlankCamera | ( | SysSBA & | sys, |
| cameraParameters & | cameraData, | ||
| bool | isFixed = false |
||
| ) |
Definition at line 2873 of file reconstruction.cpp.
| void addFixedCamera | ( | SysSBA & | sys, |
| cameraParameters & | cameraData, | ||
| const cv::Mat & | C | ||
| ) |
Definition at line 2543 of file reconstruction.cpp.
| void addNewCamera | ( | SysSBA & | sys, |
| cameraParameters & | cameraData, | ||
| const cv::Mat & | C | ||
| ) |
Definition at line 2548 of file reconstruction.cpp.
| unsigned int addNewPoints | ( | vector< featureTrack > & | tracks, |
| vector< unsigned int > & | indices, | ||
| cameraParameters & | cameraData, | ||
| cv::Mat * | cameras, | ||
| unsigned int | earliest_index, | ||
| unsigned int | latest_index | ||
| ) |
Definition at line 1608 of file reconstruction.cpp.
| void addNewPoints | ( | SysSBA & | sys, |
| const vector< cv::Point3d > & | pc | ||
| ) |
Definition at line 2733 of file reconstruction.cpp.
| int addToTracks | ( | SysSBA & | sys, |
| int | im1, | ||
| vector< cv::Point2f > & | pts1, | ||
| int | im2, | ||
| vector< cv::Point2f > & | pts2 | ||
| ) |
Definition at line 2749 of file reconstruction.cpp.
| void assignIntrinsicsToP0 | ( | cv::Mat & | P0, |
| const cv::Mat & | K | ||
| ) |
Definition at line 2476 of file reconstruction.cpp.
| void assignTracksToSBA | ( | SysSBA & | sys, |
| vector< featureTrack > & | trackVector, | ||
| int | maxIndex | ||
| ) |
Definition at line 2638 of file reconstruction.cpp.
| double calcFrameScore | ( | double | geomScore, |
| int | numFeatures, | ||
| int | numTracks | ||
| ) |
Definition at line 2404 of file reconstruction.cpp.
| double calcGeometryScore | ( | int | numInliers_H, |
| int | numInliers_F, | ||
| double | sampsonError_H, | ||
| double | sampsonError_F | ||
| ) |
Definition at line 2468 of file reconstruction.cpp.
| double calcInlierGeometryDistance | ( | vector< cv::Point2f > & | points1, |
| vector< cv::Point2f > & | points2, | ||
| cv::Mat & | mat, | ||
| cv::Mat & | mask, | ||
| int | distMethod = SAMPSON_DISTANCE |
||
| ) |
Definition at line 2338 of file reconstruction.cpp.
| double calcSampsonDistance | ( | cv::Point2f & | pt1, |
| cv::Point2f & | pt2, | ||
| cv::Mat & | F | ||
| ) |
Definition at line 2435 of file reconstruction.cpp.
| double calcSampsonError | ( | vector< cv::Point2f > & | points1, |
| vector< cv::Point2f > & | points2, | ||
| cv::Mat & | H, | ||
| cv::Mat & | Hmask | ||
| ) |
Definition at line 2413 of file reconstruction.cpp.
| void combineTransforms | ( | cv::Mat & | CN, |
| const cv::Mat & | C0, | ||
| const cv::Mat & | C1 | ||
| ) |
Definition at line 2505 of file reconstruction.cpp.
| void compileTransform | ( | cv::Mat & | c, |
| const cv::Mat & | R, | ||
| const cv::Mat & | t | ||
| ) |
| void constrainDodgyPoints | ( | SysSBA & | sys | ) |
Definition at line 3183 of file reconstruction.cpp.
| void convertPoint3dToMat | ( | const cv::Point3d & | src, |
| cv::Mat & | dst | ||
| ) |
Definition at line 2273 of file reconstruction.cpp.
| void convertProjectionMatCVToEigen | ( | const cv::Mat & | mat, |
| Eigen::Matrix< double, 3, 4 > | m | ||
| ) |
Definition at line 2992 of file reconstruction.cpp.
| void convertProjectionMatEigenToCV | ( | const Eigen::Matrix< double, 3, 4 > | m, |
| cv::Mat & | mat | ||
| ) |
Definition at line 3011 of file reconstruction.cpp.
| void convertVec4dToMat | ( | const Vector4d & | vec4, |
| cv::Mat & | mat | ||
| ) |
Definition at line 2553 of file reconstruction.cpp.
| int countActiveTriangulatedTracks | ( | vector< unsigned int > & | indices, |
| vector< featureTrack > & | tracks | ||
| ) |
Definition at line 109 of file reconstruction.cpp.
| int countTriangulatedTracks | ( | const vector< featureTrack > & | tracks | ) |
Definition at line 94 of file reconstruction.cpp.
| void decomposeTransform | ( | const cv::Mat & | c, |
| cv::Mat & | R, | ||
| cv::Mat & | t | ||
| ) |
Definition at line 393 of file geometry.cpp.
| Quaterniond defaultQuaternion | ( | ) |
Definition at line 2918 of file reconstruction.cpp.
| double dotProduct | ( | const cv::Mat & | vec1, |
| const cv::Mat & | vec2 | ||
| ) |
Definition at line 2511 of file reconstruction.cpp.
| double dotProduct | ( | const Quaterniond & | q1, |
| const Quaterniond & | q2 | ||
| ) |
Definition at line 2497 of file reconstruction.cpp.
| void estimateNewPose | ( | vector< featureTrack > & | tracks, |
| cv::Mat & | K, | ||
| int | idx, | ||
| cv::Mat & | pose | ||
| ) |
Definition at line 2688 of file reconstruction.cpp.
| bool estimatePoseFromKnownPoints | ( | cv::Mat & | dst, |
| cameraParameters | camData, | ||
| vector< featureTrack > & | tracks, | ||
| unsigned int | index, | ||
| const cv::Mat & | guide, | ||
| unsigned | minAppearances = 1, |
||
| unsigned int | iterCount = 100, |
||
| double | maxReprojErr = 4.0, |
||
| double | inliersPercentage = 0.9, |
||
| double * | reprojError = 0, |
||
| double * | pnpInlierProp = 0, |
||
| bool | debug = false |
||
| ) |
| void ExtractPointCloud | ( | vector< cv::Point3d > & | cloud, |
| vector< featureTrack > & | trackVector | ||
| ) |
Definition at line 3268 of file reconstruction.cpp.
| void filterNearPoints | ( | vector< featureTrack > & | featureTrackVector, |
| double | x, | ||
| double | y, | ||
| double | z, | ||
| double | limit = DEFAULT_NEAR_RADIUS |
||
| ) |
Definition at line 916 of file reconstruction.cpp.
| void filterToActivePoints | ( | vector< featureTrack > & | tracks, |
| vector< cv::Point2f > & | pts1, | ||
| vector< cv::Point2f > & | pts2, | ||
| vector< unsigned int > & | indices, | ||
| int | idx1, | ||
| int | idx2 | ||
| ) |
Definition at line 275 of file reconstruction.cpp.
| void filterToCompleteTracks | ( | vector< unsigned int > & | dst, |
| vector< unsigned int > & | src, | ||
| vector< featureTrack > & | tracks, | ||
| int | idx1, | ||
| int | idx2 | ||
| ) |
Definition at line 320 of file reconstruction.cpp.
| int findBestCandidate | ( | const cv::Mat * | CX, |
| const cv::Mat & | K, | ||
| const vector< cv::Point2f > & | pts1, | ||
| const vector< cv::Point2f > & | pts2, | ||
| cv::Mat & | C | ||
| ) |
Definition at line 22 of file reconstruction.cpp.
| bool findBestReconstruction | ( | const cv::Mat & | P0, |
| cv::Mat & | P1, | ||
| cv::Mat & | R, | ||
| cv::Mat & | t, | ||
| const cv::SVD & | svd, | ||
| const cv::Mat & | K, | ||
| const vector< cv::Point2f > & | pts1, | ||
| const vector< cv::Point2f > & | pts2, | ||
| bool | useDefault = false |
||
| ) |
Definition at line 3299 of file reconstruction.cpp.
| void findCentroid | ( | vector< featureTrack > & | tracks, |
| cv::Point3d & | centroid, | ||
| cv::Point3d & | stdDeviation | ||
| ) |
Definition at line 3903 of file reconstruction.cpp.
| void findCentroidAndSpread | ( | vector< featureTrack > & | tracks, |
| cv::Point3d & | centroid, | ||
| cv::Point3d & | deviations | ||
| ) |
Definition at line 1917 of file reconstruction.cpp.
| bool findClusterMean | ( | const vector< cv::Point3d > & | estimatedLocations, |
| cv::Point3d & | pt3d, | ||
| int | mode = DEFAULT_MEAN_MODE, |
||
| int | minEstimates = 3, |
||
| double | maxStandardDev = 0.1 |
||
| ) |
Definition at line 1198 of file reconstruction.cpp.
| void findFeaturesForPoints | ( | vector< featureTrack > & | tracks, |
| vector< cv::Point2f > & | pts1, | ||
| vector< cv::Point2f > & | pts2, | ||
| vector< cv::Point3d > & | pts3d, | ||
| int | idx1, | ||
| int | idx2 | ||
| ) |
Definition at line 53 of file reconstruction.cpp.
| void findFourTransformations | ( | cv::Mat * | C, |
| const cv::Mat & | E, | ||
| const cv::Mat & | K, | ||
| const vector< cv::Point2f > & | pts1, | ||
| const vector< cv::Point2f > & | pts2 | ||
| ) |
Definition at line 2011 of file reconstruction.cpp.
| void findP1Matrix | ( | cv::Mat & | P1, |
| const cv::Mat & | R, | ||
| const cv::Mat & | t | ||
| ) |
Definition at line 3774 of file reconstruction.cpp.
| void findTriangulatableTracks | ( | vector< featureTrack > & | tracks, |
| vector< unsigned int > & | indices, | ||
| vector< unsigned int > & | cameras, | ||
| unsigned int | min_length = 10 |
||
| ) |
Definition at line 654 of file reconstruction.cpp.
| void findTriangulatableTracks3 | ( | vector< featureTrack > & | tracks, |
| vector< unsigned int > & | indices, | ||
| int | latest_index = -1, |
||
| unsigned int | min_length = 10 |
||
| ) |
Definition at line 692 of file reconstruction.cpp.
| void getActive3dPoints | ( | vector< featureTrack > & | tracks, |
| vector< unsigned int > & | indices, | ||
| vector< cv::Point3d > & | cloud | ||
| ) |
Definition at line 310 of file reconstruction.cpp.
| void getActiveTracks | ( | vector< unsigned int > & | indices, |
| vector< featureTrack > & | tracks, | ||
| int | idx1, | ||
| int | idx2 | ||
| ) |
Definition at line 361 of file reconstruction.cpp.
| void getCorrespondingPoints | ( | vector< featureTrack > & | tracks, |
| const vector< cv::Point2f > & | pts1, | ||
| vector< cv::Point2f > & | pts2, | ||
| int | idx0, | ||
| int | idx1 | ||
| ) |
Definition at line 545 of file reconstruction.cpp.
| double getDistanceInUnits | ( | const cv::Mat & | t | ) |
Definition at line 2530 of file reconstruction.cpp.
| void getIndicesForTriangulation | ( | vector< unsigned int > & | dst, |
| vector< unsigned int > & | src, | ||
| vector< unsigned int > & | already_triangulated | ||
| ) |
Definition at line 125 of file reconstruction.cpp.
| void getPoints3dFromTracks | ( | vector< featureTrack > & | tracks, |
| vector< cv::Point3d > & | cloud, | ||
| int | idx1 = -1, |
||
| int | idx2 = -1 |
||
| ) |
Definition at line 1967 of file reconstruction.cpp.
| void getPointsFromTracks | ( | vector< featureTrack > & | tracks, |
| vector< cv::Point2f > & | pts1, | ||
| vector< cv::Point2f > & | pts2, | ||
| int | idx1, | ||
| int | idx2 | ||
| ) |
Definition at line 1840 of file reconstruction.cpp.
| double getQuaternionAngle | ( | const Quaterniond & | q1, |
| const Quaterniond & | q2 | ||
| ) |
Definition at line 2487 of file reconstruction.cpp.
| double getRotationInDegrees | ( | const cv::Mat & | R | ) |
Definition at line 2520 of file reconstruction.cpp.
| void getTranslationBetweenCameras | ( | cv::Mat & | C1, |
| cv::Mat & | C2, | ||
| double * | translations | ||
| ) |
Definition at line 720 of file reconstruction.cpp.
| void getTriangulatedFullSpanPoints | ( | vector< featureTrack > & | tracks, |
| vector< cv::Point2f > & | pts1, | ||
| vector< cv::Point2f > & | pts2, | ||
| int | idx1, | ||
| int | idx2, | ||
| vector< cv::Point3f > & | points3 | ||
| ) |
Definition at line 616 of file reconstruction.cpp.
| void getWandZ | ( | cv::Mat & | W, |
| cv::Mat & | Winv, | ||
| cv::Mat & | Z | ||
| ) |
Definition at line 3739 of file reconstruction.cpp.
| void initializeP0 | ( | cv::Mat & | P | ) |
Definition at line 3548 of file reconstruction.cpp.
| int initialTrackTriangulation | ( | vector< featureTrack > & | tracks, |
| vector< unsigned int > & | indices, | ||
| cameraParameters & | cameraData, | ||
| geometry_msgs::PoseStamped * | keyframePoses, | ||
| unsigned int | keyframeCount, | ||
| double | minSeparation = 0.2, |
||
| double | maxSeparation = 1.0, |
||
| int | minEstimates = 3, |
||
| double | maxStandardDev = 0.1, |
||
| double | maxReprojectionDisparity = MAX_REPROJECTION_DISPARITY |
||
| ) |
Definition at line 932 of file reconstruction.cpp.
| int initialTrackTriangulationDummy | ( | vector< featureTrack > & | tracks, |
| vector< unsigned int > & | indices, | ||
| cameraParameters & | cameraData, | ||
| geometry_msgs::PoseStamped * | keyframePoses, | ||
| unsigned int | keyframeCount, | ||
| double | minSeparation = 0.2, |
||
| double | maxSeparation = 1.0, |
||
| int | minEstimates = 3, |
||
| double | maxStandardDev = 0.1, |
||
| bool | handedness = false, |
||
| int | xCode = 0 |
||
| ) |
Definition at line 730 of file reconstruction.cpp.
| void IterativeLinearLSTriangulation | ( | cv::Mat & | dst, |
| const cv::Point3d & | u1, | ||
| const cv::Mat & | P1, | ||
| const cv::Point3d & | u2, | ||
| const cv::Mat & | P2 | ||
| ) |
Definition at line 3665 of file reconstruction.cpp.
| void LinearLSTriangulation | ( | cv::Mat & | dst, |
| const cv::Point3d & | u1, | ||
| const cv::Mat & | P1, | ||
| const cv::Point3d & | u2, | ||
| const cv::Mat & | P2 | ||
| ) |
Definition at line 3564 of file reconstruction.cpp.
| void obtainAppropriateBaseTransformation | ( | cv::Mat & | C0, |
| vector< featureTrack > & | tracks | ||
| ) |
Definition at line 1883 of file reconstruction.cpp.
| bool pointIsInFront | ( | const cv::Mat & | C, |
| const cv::Point3d & | pt | ||
| ) |
Definition at line 2136 of file reconstruction.cpp.
| int pointsInFront | ( | const cv::Mat & | C1, |
| const cv::Mat & | C2, | ||
| const vector< cv::Point3d > & | pts | ||
| ) |
Definition at line 2154 of file reconstruction.cpp.
| int pointsInFront | ( | const cv::Mat & | C1, |
| const cv::Mat & | K, | ||
| const vector< cv::Point2f > & | pts1, | ||
| const vector< cv::Point2f > & | pts2 | ||
| ) |
Definition at line 2195 of file reconstruction.cpp.
| void printSystemSummary | ( | SysSBA & | sys | ) |
Definition at line 2913 of file reconstruction.cpp.
| unsigned int putativelyTriangulateNewTracks | ( | vector< featureTrack > & | tracks, |
| vector< unsigned int > & | indices, | ||
| cameraParameters & | cameraData, | ||
| cv::Mat * | cameras, | ||
| unsigned int | earliest_index, | ||
| unsigned int | latest_index | ||
| ) |
Definition at line 1725 of file reconstruction.cpp.
| float ReciprocalSqrt | ( | float | x | ) |
Definition at line 3035 of file reconstruction.cpp.
| void reconstructSubsequence | ( | vector< featureTrack > & | tracks, |
| vector< cv::Point3d > & | ptCloud, | ||
| int | idx1, | ||
| int | idx2 | ||
| ) |
Definition at line 154 of file reconstruction.cpp.
| void reduceActiveToTriangulated | ( | vector< featureTrack > & | tracks, |
| vector< unsigned int > & | indices, | ||
| vector< unsigned int > & | untriangulated | ||
| ) |
Definition at line 261 of file reconstruction.cpp.
| void reduceVectorsToTrackedPoints | ( | const vector< cv::Point2f > & | points1, |
| vector< cv::Point2f > & | trackedPoints1, | ||
| const vector< cv::Point2f > & | points2, | ||
| vector< cv::Point2f > & | trackedPoints2, | ||
| vector< uchar > & | statusVec | ||
| ) |
Definition at line 3281 of file reconstruction.cpp.
| void removeShortTracks | ( | vector< featureTrack > & | tracks, |
| int | idx1, | ||
| int | idx2 | ||
| ) |
Definition at line 158 of file reconstruction.cpp.
| void retrieveAllCameras | ( | cv::Mat * | allCameraPoses, |
| const SysSBA & | sys | ||
| ) |
Definition at line 2619 of file reconstruction.cpp.
| void retrieveAllPoints | ( | vector< cv::Point3d > & | pts, |
| const SysSBA & | sys | ||
| ) |
Definition at line 2575 of file reconstruction.cpp.
| double retrieveCameraPose | ( | const SysSBA & | sys, |
| unsigned int | idx, | ||
| geometry_msgs::Pose & | pose | ||
| ) |
Definition at line 2597 of file reconstruction.cpp.
| void retrieveCameraPose | ( | const SysSBA & | sys, |
| unsigned int | idx, | ||
| cv::Mat & | camera | ||
| ) |
Definition at line 2588 of file reconstruction.cpp.
| void reverseTranslation | ( | cv::Mat & | C | ) |
Definition at line 43 of file reconstruction.cpp.
| void summarizeTransformation | ( | const cv::Mat & | C, |
| char * | summary | ||
| ) |
Definition at line 7 of file reconstruction.cpp.
| void transfer3dPoint | ( | const cv::Point3d & | src, |
| cv::Point3d & | dst, | ||
| const cv::Mat & | C | ||
| ) |
Definition at line 2283 of file reconstruction.cpp.
| void transfer3DPoints | ( | const vector< cv::Point3d > & | src, |
| vector< cv::Point3d > & | dst, | ||
| const cv::Mat & | C | ||
| ) |
Definition at line 2304 of file reconstruction.cpp.
| void Triangulate | ( | const cv::Point2f & | pt1, |
| const cv::Point2f & | pt2, | ||
| const cv::Mat & | K, | ||
| const cv::Mat & | Kinv, | ||
| const cv::Mat & | P1, | ||
| const cv::Mat & | P2, | ||
| cv::Point3d & | xyzPoint, | ||
| bool | debug = false |
||
| ) |
Definition at line 3801 of file reconstruction.cpp.
| void Triangulate_1 | ( | const cv::Point2d & | pt1, |
| const cv::Point2d & | pt2, | ||
| const cv::Mat & | K, | ||
| const cv::Mat & | Kinv, | ||
| const cv::Mat & | P1, | ||
| const cv::Mat & | P2, | ||
| cv::Point3d & | xyzPoint, | ||
| bool | iterate = true |
||
| ) |
Definition at line 3610 of file reconstruction.cpp.
| int TriangulateNewTracks | ( | vector< featureTrack > & | trackVector, |
| const int | index1, | ||
| const int | index2, | ||
| const cv::Mat & | K, | ||
| const cv::Mat & | K_inv, | ||
| const cv::Mat & | P0, | ||
| const cv::Mat & | P1, | ||
| bool | initializeOnFocalPlane = false |
||
| ) |
Definition at line 3202 of file reconstruction.cpp.
| void TriangulatePoints | ( | const vector< cv::Point2f > & | pt_set1, |
| const vector< cv::Point2f > & | pt_set2, | ||
| const cv::Mat & | K, | ||
| const cv::Mat & | Kinv, | ||
| const cv::Mat & | P, | ||
| const cv::Mat & | P1, | ||
| vector< cv::Point3d > & | pointcloud, | ||
| vector< cv::Point2f > & | correspImg1Pt | ||
| ) |
Definition at line 3879 of file reconstruction.cpp.
| void triangulateTracks | ( | vector< featureTrack > & | tracks, |
| vector< unsigned int > & | indices, | ||
| cameraParameters & | cameraData, | ||
| cv::Mat * | cameras, | ||
| unsigned int | earliest_index, | ||
| unsigned int | latest_index | ||
| ) |
Definition at line 1355 of file reconstruction.cpp.
| void updateCameraNode | ( | SysSBA & | sys, |
| cv::Mat | R, | ||
| cv::Mat | t, | ||
| int | img1, | ||
| int | img2 | ||
| ) |
Definition at line 3048 of file reconstruction.cpp.
| void updateCameraNode_2 | ( | SysSBA & | sys, |
| const cv::Mat & | R, | ||
| const cv::Mat & | t, | ||
| int | image_index | ||
| ) |
Definition at line 2959 of file reconstruction.cpp.
| void updateCameraNode_2 | ( | SysSBA & | sys, |
| const cv::Mat & | C, | ||
| int | image_index | ||
| ) |
Definition at line 2924 of file reconstruction.cpp.
| void updateSystemTracks | ( | SysSBA & | sys, |
| vector< featureTrack > & | tracks, | ||
| unsigned int | start_index | ||
| ) |
Definition at line 177 of file reconstruction.cpp.
| void updateTracks | ( | vector< featureTrack > & | trackVector, |
| const SysSBA & | sys | ||
| ) |
Definition at line 2562 of file reconstruction.cpp.
| void updateTriangulatedPoints | ( | vector< featureTrack > & | tracks, |
| vector< unsigned int > & | indices, | ||
| vector< cv::Point3d > & | cloud | ||
| ) |
Definition at line 241 of file reconstruction.cpp.