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

Add Similarity(2) support in gtsam/geometry #918

Merged
merged 40 commits into from
Apr 30, 2022
Merged
Show file tree
Hide file tree
Changes from 9 commits
Commits
Show all changes
40 commits
Select commit Hold shift + click to select a range
d5918dc
Create Similarity2.h
johnwlambert Nov 6, 2021
6b7b31a
Create Similarity2.cpp
johnwlambert Nov 6, 2021
e48704d
add basic Python interface to .i file
johnwlambert Nov 6, 2021
6005390
add python unit tests
johnwlambert Nov 6, 2021
8e9815b
fix typo
johnwlambert Nov 6, 2021
9fd7451
add Pose2Pair typedef
johnwlambert Nov 6, 2021
7082b67
fix typo in types
johnwlambert Nov 7, 2021
4372ed8
add means() function to Point2.h
johnwlambert Nov 7, 2021
1dd20a3
add missing `means()` function for Point2
johnwlambert Nov 7, 2021
2252d5e
fix typo in size of mean vector for Point2Pair means()
johnwlambert Nov 8, 2021
dfb9497
add Rot2.ClosestTo()
johnwlambert Dec 7, 2021
37af8cf
finish Rot2.ClosestTo()
johnwlambert Dec 7, 2021
6853570
fix typo
johnwlambert Dec 7, 2021
c2040fb
use ClosestTo() in initializer list
johnwlambert Dec 7, 2021
7ebbe18
fix Eigen error
Dec 8, 2021
784bdc6
minor fixes to Pose2 and Rot2
varunagrawal Feb 6, 2022
bf668e5
Similarity2 fixes
varunagrawal Feb 6, 2022
a57465e
Similarity3 fixes
varunagrawal Feb 6, 2022
5e75986
fix wrapper
varunagrawal Feb 6, 2022
b484a21
fix tests
varunagrawal Feb 6, 2022
1933597
Merge branch 'develop' into add-Similarity2-classes-2
varunagrawal Feb 6, 2022
c716f63
wrap Pose2Pairs
varunagrawal Feb 6, 2022
5098706
wrap equals for Sim2 and Sim3
varunagrawal Feb 6, 2022
464af9f
Fix syntactic errors in test_Sim2.py
varunagrawal Feb 6, 2022
5a1797f
Merge branch 'develop' into add-Similarity2-classes
varunagrawal Feb 6, 2022
b60ca0f
Merge branch 'add-Similarity2-classes' into add-Similarity2-classes-2
varunagrawal Feb 6, 2022
cc8d80f
Remove SFINAE from KarcherMean so we can also use it for Rot2
varunagrawal Feb 6, 2022
37ae703
Fix tests
varunagrawal Feb 6, 2022
10554d8
Merge pull request #1090 from borglab/add-Similarity2-classes-2
johnwlambert Feb 7, 2022
d8e5658
capitalize static methods
varunagrawal Apr 29, 2022
5be6309
GTSAM_EXPORT at the class level
varunagrawal Apr 29, 2022
53b3705
remove Pose2/3 casts from Sim2/3
varunagrawal Apr 29, 2022
ad2e347
update assertions
varunagrawal Apr 29, 2022
ba6c3cc
Merge branch 'develop' into add-Similarity2-classes
varunagrawal Apr 29, 2022
e704b40
typo fix
varunagrawal Apr 29, 2022
9eff71e
Rot2::ClosestTo with SVD
varunagrawal Apr 29, 2022
7a56473
add Lie group operations
varunagrawal Apr 30, 2022
b8b52cb
AdjointMap method
varunagrawal Apr 30, 2022
a73d6e0
Sim3 cpp unit tests
varunagrawal Apr 30, 2022
12dd2ec
identity needs to be lowercase and fix tests
varunagrawal Apr 30, 2022
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
12 changes: 12 additions & 0 deletions gtsam/geometry/Point2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,18 @@ list<Point2> circleCircleIntersection(Point2 c1, double r1, Point2 c2,
return circleCircleIntersection(c1, c2, fh);
}

Point2Pair means(const std::vector<Point2Pair> &abPointPairs) {
Copy link
Member

Choose a reason for hiding this comment

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

For this PR and my latest PR, I'm starting to think we should "light-deprecate" PointPairs and do the computation in Eigen.
https://eigen.tuxfamily.org/dox/group__TutorialReductionsVisitorsBroadcasting.html

Copy link
Collaborator

Choose a reason for hiding this comment

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

Should we save this for another PR in favor of landing this one?
We can create an issue to track it.

const size_t n = abPointPairs.size();
if (n == 0) throw std::invalid_argument("Point2::mean input Point2Pair vector is empty");
Point2 aSum(0, 0, 0), bSum(0, 0, 0);
for (const Point2Pair &abPair : abPointPairs) {
aSum += abPair.first;
bSum += abPair.second;
}
const double f = 1.0 / n;
return {aSum * f, bSum * f};
}

/* ************************************************************************* */
ostream &operator<<(ostream &os, const gtsam::Point2Pair &p) {
os << p.first << " <-> " << p.second;
Expand Down
3 changes: 3 additions & 0 deletions gtsam/geometry/Point2.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,9 @@ GTSAM_EXPORT boost::optional<Point2> circleCircleIntersection(double R_d, double
* @return list of solutions (0,1, or 2). Identical circles will return empty list, as well.
*/
GTSAM_EXPORT std::list<Point2> circleCircleIntersection(Point2 c1, Point2 c2, boost::optional<Point2> fh);

/// Calculate the two means of a set of Point2 pairs
GTSAM_EXPORT Point2Pair means(const std::vector<Point2Pair> &abPointPairs);

/**
* @brief Intersect 2 circles
Expand Down
4 changes: 4 additions & 0 deletions gtsam/geometry/Pose2.h
Original file line number Diff line number Diff line change
Expand Up @@ -322,6 +322,10 @@ inline Matrix wedge<Pose2>(const Vector& xi) {
typedef std::pair<Point2,Point2> Point2Pair;
GTSAM_EXPORT boost::optional<Pose2> align(const std::vector<Point2Pair>& pairs);

// Convenience typedef
using Pose2Pair = std::pair<Pose2, Pose2>;
varunagrawal marked this conversation as resolved.
Show resolved Hide resolved
using Pose2Pairs = std::vector<std::pair<Pose2, Pose2> >;

template <>
struct traits<Pose2> : public internal::LieGroup<Pose2> {};

Expand Down
203 changes: 203 additions & 0 deletions gtsam/geometry/Similarity2.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,203 @@
/* ----------------------------------------------------------------------------

* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)

* See LICENSE for the license information

* -------------------------------------------------------------------------- */

/**
* @file Similarity2.cpp
* @brief Implementation of Similarity2 transform
* @author John Lambert
*/

#include <gtsam/geometry/Similarity2.h>

#include <gtsam/geometry/Pose2.h>
#include <gtsam/base/Manifold.h>
#include <gtsam/slam/KarcherMeanFactor-inl.h>

namespace gtsam {

using std::vector;

namespace {
varunagrawal marked this conversation as resolved.
Show resolved Hide resolved
/// Subtract centroids from point pairs.
static Point2Pairs subtractCentroids(const Point2Pairs &abPointPairs,
const Point2Pair &centroids) {
Point2Pairs d_abPointPairs;
for (const Point2Pair& abPair : abPointPairs) {
Point2 da = abPair.first - centroids.first;
Point2 db = abPair.second - centroids.second;
d_abPointPairs.emplace_back(da, db);
}
return d_abPointPairs;
}

/// Form inner products x and y and calculate scale.
static const double calculateScale(const Point2Pairs &d_abPointPairs,
varunagrawal marked this conversation as resolved.
Show resolved Hide resolved
const Rot2 &aRb) {
double x = 0, y = 0;
dellaert marked this conversation as resolved.
Show resolved Hide resolved
Point2 da, db;
for (const Point2Pair& d_abPair : d_abPointPairs) {
std::tie(da, db) = d_abPair;
const Vector2 da_prime = aRb * db;
y += da.transpose() * da_prime;
x += da_prime.transpose() * da_prime;
}
const double s = y / x;
return s;
}

/// Form outer product H.
static Matrix2 calculateH(const Point2Pairs &d_abPointPairs) {
Matrix2 H = Z_2x2;
for (const Point2Pair& d_abPair : d_abPointPairs) {
H += d_abPair.first * d_abPair.second.transpose();
}
return H;
}

/// This method estimates the similarity transform from differences point pairs,
// given a known or estimated rotation and point centroids.
static Similarity2 align(const Point2Pairs &d_abPointPairs, const Rot2 &aRb,
const Point2Pair &centroids) {
const double s = calculateScale(d_abPointPairs, aRb);
// dividing aTb by s is required because the registration cost function
// minimizes ||a - sRb - t||, whereas Sim(2) computes s(Rb + t)
const Point2 aTb = (centroids.first - s * (aRb * centroids.second)) / s;
return Similarity2(aRb, aTb, s);
}

/// This method estimates the similarity transform from point pairs, given a known or estimated rotation.
// Refer to: http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf Chapter 3
static Similarity2 alignGivenR(const Point2Pairs &abPointPairs,
const Rot2 &aRb) {
auto centroids = means(abPointPairs);
auto d_abPointPairs = subtractCentroids(abPointPairs, centroids);
return align(d_abPointPairs, aRb, centroids);
}
} // namespace

Similarity2::Similarity2() :
t_(0,0), s_(1) {
}

Similarity2::Similarity2(double s) :
t_(0,0), s_(s) {
}

Similarity2::Similarity2(const Rot2& R, const Point2& t, double s) :
R_(R), t_(t), s_(s) {
varunagrawal marked this conversation as resolved.
Show resolved Hide resolved
}

Similarity2::Similarity2(const Matrix2& R, const Vector2& t, double s) :
R_(R), t_(t), s_(s) {
}

Similarity2::Similarity2(const Matrix3& T) :
R_(T.topLeftCorner<2, 2>()), t_(T.topRightCorner<2, 1>()), s_(1.0 / T(2, 2)) {
}

bool Similarity2::equals(const Similarity2& other, double tol) const {
return R_.equals(other.R_, tol) && traits<Point2>::Equals(t_, other.t_, tol)
&& s_ < (other.s_ + tol) && s_ > (other.s_ - tol);
}

bool Similarity2::operator==(const Similarity2& other) const {
return R_.matrix() == other.R_.matrix() && t_ == other.t_ && s_ == other.s_;
}

void Similarity2::print(const std::string& s) const {
std::cout << std::endl;
std::cout << s;
rotation().print("\nR:\n");
std::cout << "t: " << translation().transpose() << " s: " << scale() << std::endl;
}

Similarity2 Similarity2::identity() {
return Similarity2();
}
Similarity2 Similarity2::operator*(const Similarity2& S) const {
dellaert marked this conversation as resolved.
Show resolved Hide resolved
return Similarity2(R_ * S.R_, ((1.0 / S.s_) * t_) + R_ * S.t_, s_ * S.s_);
}

Similarity2 Similarity2::inverse() const {
const Rot2 Rt = R_.inverse();
const Point2 sRt = Rt * (-s_ * t_);
return Similarity2(Rt, sRt, 1.0 / s_);
}

Point2 Similarity2::transformFrom(const Point2& p) const {
const Point2 q = R_ * p + t_;
return s_ * q;
}

Pose2 Similarity2::transformFrom(const Pose2& T) const {
Rot2 R = R_.compose(T.rotation());
Point2 t = Point2(s_ * (R_ * T.translation() + t_));
return Pose2(R, t);
}

Point2 Similarity2::operator*(const Point2& p) const {
return transformFrom(p);
}

Similarity2 Similarity2::Align(const Point2Pairs &abPointPairs) {
// Refer to Chapter 3 of
// http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf
if (abPointPairs.size() < 2)
throw std::runtime_error("input should have at least 2 pairs of points");
auto centroids = means(abPointPairs);
auto d_abPointPairs = subtractCentroids(abPointPairs, centroids);
Matrix3 H = calculateH(d_abPointPairs);
// ClosestTo finds rotation matrix closest to H in Frobenius sense
Rot2 aRb = Rot2::ClosestTo(H);
return align(d_abPointPairs, aRb, centroids);
}

Similarity2 Similarity2::Align(const vector<Pose2Pair> &abPosePairs) {
const size_t n = abPosePairs.size();
if (n < 2)
throw std::runtime_error("input should have at least 2 pairs of poses");

// calculate rotation
vector<Rot2> rotations;
Point2Pairs abPointPairs;
rotations.reserve(n);
abPointPairs.reserve(n);
// Below denotes the pose of the i'th object/camera/etc in frame "a" or frame "b"
Pose2 aTi, bTi;
for (const Pose2Pair &abPair : abPosePairs) {
std::tie(aTi, bTi) = abPair;
const Rot2 aRb = aTi.rotation().compose(bTi.rotation().inverse());
rotations.emplace_back(aRb);
abPointPairs.emplace_back(aTi.translation(), bTi.translation());
}
const Rot2 aRb_estimate = FindKarcherMean<Rot2>(rotations);

return alignGivenR(abPointPairs, aRb_estimate);
}

std::ostream &operator<<(std::ostream &os, const Similarity2& p) {
os << "[" << p.rotation().theta() << " "
<< p.translation().transpose() << " " << p.scale() << "]\';";
return os;
}

const Matrix3 Similarity2::matrix() const {
varunagrawal marked this conversation as resolved.
Show resolved Hide resolved
Matrix3 T;
T.topRows<2>() << R_.matrix(), t_;
T.bottomRows<1>() << 0, 0, 1.0 / s_;
return T;
}

Similarity2::operator Pose2() const {
Copy link
Member

Choose a reason for hiding this comment

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

That’s a weird cast

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Casting Sim2 to Pose2 is a bit of an unusual cast, but quite useful for some of my use cases (sometimes ground truth is provided in this form for some datasets).

return Pose2(R_, s_ * t_);
}

} // namespace gtsam
Loading