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

Implementation of the LOST triangulation algorithm #1241

Merged
merged 12 commits into from
Jul 13, 2022

Conversation

akshay-krishnan
Copy link
Contributor

In collaboration with Sebastien Henry and Prof. John Christian, we implement the LOST triangulation algorithm https://arxiv.org/pdf/2205.12197.pdf.
The triangulatePoint3 method accepts a boolean that initializes the point using the LOST method instead of DLT.

This PR also adds an example that runs DLT, LOST and DLT+nonlinear optimization. It shows that the covariance of LOST is similar to that of DLT + optimization, while being much faster.

@akshay-krishnan akshay-krishnan requested a review from dellaert July 11, 2022 05:37
@akshay-krishnan
Copy link
Contributor Author

Its possible my design choice may not be the best. The goal was to have the LOST implementation share the same triangulatePoint3 interface.
I could not make it more similar than this. LOST required the poses, while DLT works on projection matrices.
@dellaert let me know if you prefer a different design.

Copy link
Member

@dellaert dellaert left a comment

Choose a reason for hiding this comment

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

Awesome! some naming nits - we use camelCase, but after that merge at will.

@@ -96,6 +96,70 @@ TEST(triangulation, twoPoses) {
EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-4));
}

TEST(triangulation, twoCamerasUsingLOST) {
CameraSet<PinholeCamera<Cal3_S2>> cameras;
cameras.push_back(camera1);
Copy link
Member

Choose a reason for hiding this comment

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

Let’s rename global constants in this file kCamera1, kCamera2 etc and make sure they are static const.

// LOST has been shown to preform better when the point is much closer to one
// camera compared to another. This unit test checks this configuration.
Cal3_S2 identity_K;
Pose3 pose_1;
Copy link
Member

Choose a reason for hiding this comment

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

pose1, pose2, identityK

@@ -302,8 +316,8 @@ template <class CAMERA>
typename CAMERA::MeasurementVector undistortMeasurements(
const CameraSet<CAMERA>& cameras,
const typename CAMERA::MeasurementVector& measurements) {
const size_t num_meas = cameras.size();
assert(num_meas == measurements.size());
const size_t num_meas = measurements.size();
Copy link
Member

Choose a reason for hiding this comment

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

rename to nrMeasurements and nrCameras

const Point2Vector& measurements,
double rank_tol = 1e-9, bool optimize = false,
const SharedNoiseModel& model = nullptr,
const bool use_lost_triangulation = false) {
Copy link
Member

Choose a reason for hiding this comment

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

In GTSAM we use camelCase. useLOST seems good.

PrintDuration(lost_duration, num_trials, "LOST");
PrintDuration(dlt_duration, num_trials, "DLT");
PrintDuration(dlt_opt_duration, num_trials, "DLT_OPT");
}
Copy link
Member

Choose a reason for hiding this comment

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

Add newline

@akshay-krishnan akshay-krishnan merged commit b1f441d into develop Jul 13, 2022
@akshay-krishnan akshay-krishnan deleted the lost-triangulate branch July 13, 2022 14:04
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants