Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix triangulatePoint3 for calibrations with distortion #1128

Merged
merged 3 commits into from
Mar 15, 2022
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Next Next commit
fix triangulatePoint3 for calibrations with distortion
Prior implementation only used the K() portion of all Cal3 calibrations
for the linear triangulation of points with triangulatePoint3.
- Added tests for triangulation with non-Cal3_S2 calibrations.
- Added skew to the test Cal3_S2 calibration.
- Added an undistortMeasurements step to triangulatePoint3 so that
linear triangulation works for calibrations with distortion
coefficients.
  • Loading branch information
thomassm committed Mar 8, 2022
commit ba32a0de85c94eebae4d27116cec3885db9f66bc
109 changes: 106 additions & 3 deletions gtsam/geometry/tests/testTriangulation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

#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>
Expand All @@ -38,7 +39,7 @@ using namespace boost::assign;
// Some common constants

static const boost::shared_ptr<Cal3_S2> sharedCal = //
boost::make_shared<Cal3_S2>(1500, 1200, 0, 640, 480);
boost::make_shared<Cal3_S2>(1500, 1200, 0.1, 640, 480);

// Looking along X-axis, 1 meter above ground plane (x-y)
static const Rot3 upright = Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2);
Expand Down Expand Up @@ -95,11 +96,113 @@ TEST(triangulation, twoPoses) {
EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-4));
}

//******************************************************************************
// Simple test with a well-behaved two camera situation with Cal3S2 calibration.
TEST(triangulation, twoPosesCal3S2) {
static const boost::shared_ptr<Cal3DS2> sharedDistortedCal = //
boost::make_shared<Cal3DS2>(1500, 1200, 0, 640, 480, -.3, 0.1, 0.0001, -0.0003);

PinholeCamera<Cal3DS2> camera1Distorted(pose1, *sharedDistortedCal);

PinholeCamera<Cal3DS2> camera2Distorted(pose2, *sharedDistortedCal);

// 1. Project two landmarks into two cameras and triangulate
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

  1. ? Also, please format with Google style...

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

good catch, fixed the numbering. I ran clang-format --style=Google for the new code, do you have a different formatter though? It made a lot of changes to the original code that I didn't include.

Point2 z1Distorted = camera1Distorted.project(landmark);
Point2 z2Distorted = camera2Distorted.project(landmark);

vector<Pose3> poses;
Point2Vector measurements;

poses += pose1, pose2;
measurements += z1Distorted, z2Distorted;

double rank_tol = 1e-9;

// 1. Test simple DLT, perfect in no noise situation
bool optimize = false;
boost::optional<Point3> actual1 = //
triangulatePoint3<Cal3DS2>(poses, sharedDistortedCal, measurements, rank_tol, optimize);
EXPECT(assert_equal(landmark, *actual1, 1e-7));

// 2. test with optimization on, same answer
optimize = true;
boost::optional<Point3> actual2 = //
triangulatePoint3<Cal3DS2>(poses, sharedDistortedCal, measurements, rank_tol, optimize);
EXPECT(assert_equal(landmark, *actual2, 1e-7));

// 3. Add some noise and try again: result should be ~ (4.995,
// 0.499167, 1.19814)
measurements.at(0) += Point2(0.1, 0.5);
measurements.at(1) += Point2(-0.2, 0.3);
optimize = false;
boost::optional<Point3> actual3 = //
triangulatePoint3<Cal3DS2>(poses, sharedDistortedCal, measurements, rank_tol, optimize);
EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual3, 1e-3));

// 4. Now with optimization on
optimize = true;
boost::optional<Point3> actual4 = //
triangulatePoint3<Cal3DS2>(poses, sharedDistortedCal, measurements, rank_tol, optimize);
EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-3));
}

//******************************************************************************
// Simple test with a well-behaved two camera situation with Fisheye calibration.
TEST(triangulation, twoPosesFisheye) {
using Calibration = Cal3Fisheye;
static const boost::shared_ptr<Calibration> sharedDistortedCal = //
boost::make_shared<Calibration>(1500, 1200, .1, 640, 480, -.3, 0.1, 0.0001, -0.0003);

PinholeCamera<Calibration> camera1Distorted(pose1, *sharedDistortedCal);

PinholeCamera<Calibration> camera2Distorted(pose2, *sharedDistortedCal);

// 1. Project two landmarks into two cameras and triangulate
Point2 z1Distorted = camera1Distorted.project(landmark);
Point2 z2Distorted = camera2Distorted.project(landmark);

vector<Pose3> poses;
Point2Vector measurements;

poses += pose1, pose2;
measurements += z1Distorted, z2Distorted;

double rank_tol = 1e-9;

// 1. Test simple DLT, perfect in no noise situation
bool optimize = false;
boost::optional<Point3> actual1 = //
triangulatePoint3<Calibration>(poses, sharedDistortedCal, measurements, rank_tol, optimize);
EXPECT(assert_equal(landmark, *actual1, 1e-7));

// 2. test with optimization on, same answer
optimize = true;
boost::optional<Point3> actual2 = //
triangulatePoint3<Calibration>(poses, sharedDistortedCal, measurements, rank_tol, optimize);
EXPECT(assert_equal(landmark, *actual2, 1e-7));

// 3. Add some noise and try again: result should be ~ (4.995,
// 0.499167, 1.19814)
measurements.at(0) += Point2(0.1, 0.5);
measurements.at(1) += Point2(-0.2, 0.3);
optimize = false;
boost::optional<Point3> actual3 = //
triangulatePoint3<Calibration>(poses, sharedDistortedCal, measurements, rank_tol, optimize);
EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual3, 1e-3));

// 4. Now with optimization on
optimize = true;
boost::optional<Point3> actual4 = //
triangulatePoint3<Calibration>(poses, sharedDistortedCal, measurements, rank_tol, optimize);
EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-3));
}


//******************************************************************************
// Similar, but now with Bundler calibration
TEST(triangulation, twoPosesBundler) {
boost::shared_ptr<Cal3Bundler> bundlerCal = //
boost::make_shared<Cal3Bundler>(1500, 0, 0, 640, 480);
boost::make_shared<Cal3Bundler>(1500, 0.1, 0.2, 640, 480);
PinholeCamera<Cal3Bundler> camera1(pose1, *bundlerCal);
PinholeCamera<Cal3Bundler> camera2(pose2, *bundlerCal);

Expand All @@ -126,7 +229,7 @@ TEST(triangulation, twoPosesBundler) {

boost::optional<Point3> actual2 = //
triangulatePoint3<Cal3Bundler>(poses, bundlerCal, measurements, rank_tol, optimize);
EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19847), *actual2, 1e-4));
EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19847), *actual2, 1e-3));
}

//******************************************************************************
Expand Down
34 changes: 33 additions & 1 deletion gtsam/geometry/triangulation.h
Original file line number Diff line number Diff line change
Expand Up @@ -227,6 +227,35 @@ std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>> projectionMatricesFrom
return projection_matrices;
}

/** Remove distortion for measurements so as if the measurements came from a pinhole camera.
*
* Removes distortion but maintains the K matrix of the initial sharedCal. Operates by calibrating using
* full calibration and uncalibrating with only the pinhole component of the calibration.
* @tparam CALIBRATION Calibration type to use.
* @param sharedCal Calibration with which measurements were taken.
* @param measurements Vector of measurements to undistort.
* @return measurements with the effect of the distortion of sharedCal removed.
*/
template <class CALIBRATION>
Point2Vector undistortMeasurements(boost::shared_ptr<CALIBRATION> sharedCal, const Point2Vector& measurements) {
const auto& K = sharedCal->K();
Cal3_S2 pinholeCalibration(K(0,0), K(1,1), K(0,1), K(0,2), K(1,2));
Point2Vector undistortedMeasurements;
// Calibrate with sharedCal and uncalibrate with pinhole version of sharedCal so that measurements are undistorted.
std::transform(measurements.begin(), measurements.end(), std::back_inserter(undistortedMeasurements), [&sharedCal, &pinholeCalibration](auto& measurement) {
return pinholeCalibration.uncalibrate(sharedCal->calibrate(measurement));
});

return undistortedMeasurements;
}

/** Specialization for Cal3_S2 as it doesn't need to be undistorted. */
template <>
Point2Vector undistortMeasurements(boost::shared_ptr<Cal3_S2> sharedCal, const Point2Vector& measurements) {
return measurements;
}


/**
* Function to triangulate 3D landmark point from an arbitrary number
* of poses (at least 2) using the DLT. The function checks that the
Expand All @@ -253,8 +282,11 @@ Point3 triangulatePoint3(const std::vector<Pose3>& poses,
// construct projection matrices from poses & calibration
auto projection_matrices = projectionMatricesFromPoses(poses, sharedCal);

// Undistort the measurements, leaving only the pinhole elements in effect.
auto undistortedMeasurements = undistortMeasurements<CALIBRATION>(sharedCal, measurements);

// Triangulate linearly
Point3 point = triangulateDLT(projection_matrices, measurements, rank_tol);
Point3 point = triangulateDLT(projection_matrices, undistortedMeasurements, rank_tol);

// Then refine using non-linear optimization
if (optimize)
Expand Down