triangulation utilities More...
#include <CppUnitLite/TestHarness.h>#include <gtsam/geometry/Cal3Bundler.h>#include <gtsam/geometry/Cal3DS2.h>#include <gtsam/geometry/CameraSet.h>#include <gtsam/geometry/PinholeCamera.h>#include <gtsam/geometry/SphericalCamera.h>#include <gtsam/geometry/StereoCamera.h>#include <gtsam/geometry/triangulation.h>#include <gtsam/nonlinear/ExpressionFactor.h>#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>#include <gtsam/slam/StereoFactor.h>
Go to the source code of this file.
Functions | |
| static const PinholeCamera< Cal3_S2 > | kCamera1 (kPose1, *kSharedCal) |
| static const PinholeCamera< Cal3_S2 > | kCamera2 (kPose2, *kSharedCal) |
| static const Point3 | kLandmark (5, 0.5, 1.2) |
| int | main () |
| TEST (triangulation, fourPoses) | |
| TEST (triangulation, fourPoses_distinct_Ks) | |
| TEST (triangulation, fourPoses_distinct_Ks_distortion) | |
| TEST (triangulation, fourPoses_robustNoiseModel) | |
| TEST (triangulation, onePose) | |
| TEST (triangulation, outliersAndFarLandmarks) | |
| TEST (triangulation, reprojectionError_cameraComparison) | |
| TEST (triangulation, StereoTriangulateNonlinear) | |
| TEST (triangulation, threePoses_robustNoiseModel) | |
| TEST (triangulation, twoCamerasLOSTvsDLT) | |
| TEST (triangulation, twoCamerasUsingLOST) | |
| TEST (triangulation, twoIdenticalPoses) | |
| TEST (triangulation, twoPoses) | |
| TEST (triangulation, twoPoses_sphericalCamera) | |
| TEST (triangulation, twoPoses_sphericalCamera_extremeFOV) | |
| TEST (triangulation, twoPosesBundler) | |
| TEST (triangulation, twoPosesCal3DS2) | |
| TEST (triangulation, twoPosesFisheye) | |
Variables | |
| static const Point2Vector | kMeasurements {kZ1, kZ2} |
| static const Pose3 | kPose1 = Pose3(upright, gtsam::Point3(0, 0, 1)) |
| static const Pose3 | kPose2 = kPose1 * Pose3(Rot3(), Point3(1, 0, 0)) |
| static const std::vector< Pose3 > | kPoses = {kPose1, kPose2} |
| static const std::shared_ptr< Cal3_S2 > | kSharedCal |
| static const Point2 | kZ1 = kCamera1.project(kLandmark) |
| static const Point2 | kZ2 = kCamera2.project(kLandmark) |
| static const Rot3 | upright = Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2) |
|
static |
|
static |
|
static |
| int main | ( | ) |
Definition at line 857 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| fourPoses | |||
| ) |
Definition at line 296 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| fourPoses_distinct_Ks | |||
| ) |
Definition at line 430 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| fourPoses_distinct_Ks_distortion | |||
| ) |
Definition at line 493 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| fourPoses_robustNoiseModel | |||
| ) |
Definition at line 385 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| onePose | |||
| ) |
Definition at line 587 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| outliersAndFarLandmarks | |||
| ) |
Definition at line 515 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| reprojectionError_cameraComparison | |||
| ) |
Definition at line 821 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| StereoTriangulateNonlinear | |||
| ) |
Definition at line 599 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| threePoses_robustNoiseModel | |||
| ) |
Definition at line 345 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| twoCamerasLOSTvsDLT | |||
| ) |
Definition at line 125 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| twoCamerasUsingLOST | |||
| ) |
Definition at line 96 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| twoIdenticalPoses | |||
| ) |
Definition at line 572 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| twoPoses | |||
| ) |
Definition at line 63 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| twoPoses_sphericalCamera | |||
| ) |
Definition at line 703 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| twoPoses_sphericalCamera_extremeFOV | |||
| ) |
Definition at line 762 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| twoPosesBundler | |||
| ) |
Definition at line 265 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| twoPosesCal3DS2 | |||
| ) |
Definition at line 161 of file testTriangulation.cpp.
| TEST | ( | triangulation | , |
| twoPosesFisheye | |||
| ) |
Definition at line 213 of file testTriangulation.cpp.
|
static |
Definition at line 59 of file testTriangulation.cpp.
|
static |
Definition at line 43 of file testTriangulation.cpp.
Definition at line 47 of file testTriangulation.cpp.
Definition at line 50 of file testTriangulation.cpp.
|
static |
Definition at line 38 of file testTriangulation.cpp.
|
static |
Definition at line 57 of file testTriangulation.cpp.
|
static |
Definition at line 58 of file testTriangulation.cpp.
Definition at line 42 of file testTriangulation.cpp.