34 for (
const Point3Pair& abPair : abPointPairs) {
35 Point3 da = abPair.first - centroids.first;
36 Point3 db = abPair.second - centroids.second;
37 d_abPointPairs.emplace_back(da, db);
39 return d_abPointPairs;
43 static const double calculateScale(
const Point3Pairs &d_abPointPairs,
47 for (
const Point3Pair& d_abPair : d_abPointPairs) {
48 std::tie(da, db) = d_abPair;
49 const Vector3 da_prime = aRb * db;
50 y += da.transpose() * da_prime;
51 x += da_prime.transpose() * da_prime;
53 const double s =
y /
x;
58 static Matrix3 calculateH(
const Point3Pairs &d_abPointPairs) {
60 for (
const Point3Pair& d_abPair : d_abPointPairs) {
61 H += d_abPair.first * d_abPair.second.transpose();
70 const double s = calculateScale(d_abPointPairs, aRb);
73 const Point3 aTb = (centroids.first - s * (aRb * centroids.second)) /
s;
74 return Similarity3(aRb, aTb, s);
79 static Similarity3 alignGivenR(
const Point3Pairs &abPointPairs,
81 auto centroids =
means(abPointPairs);
82 auto d_abPointPairs = subtractCentroids(abPointPairs, centroids);
83 return align(d_abPointPairs, aRb, centroids);
117 std::cout << std::endl;
120 std::cout <<
"t: " <<
translation().transpose() <<
" s: " <<
scale() << std::endl;
142 const Matrix3 DR = sR *
skewSymmetric(-p.x(), -p.y(), -p.z());
143 *H1 << DR, sR, sR *
p;
163 if (abPointPairs.size() < 3)
164 throw std::runtime_error(
"input should have at least 3 pairs of points");
165 auto centroids =
means(abPointPairs);
166 auto d_abPointPairs = subtractCentroids(abPointPairs, centroids);
167 Matrix3 H = calculateH(d_abPointPairs);
170 return align(d_abPointPairs, aRb, centroids);
174 const size_t n = abPosePairs.size();
176 throw std::runtime_error(
"input should have at least 2 pairs of poses");
179 vector<Rot3> rotations;
181 rotations.reserve(n);
182 abPointPairs.reserve(n);
185 for (
const Pose3Pair &abPair : abPosePairs) {
186 std::tie(aTi, bTi) = abPair;
188 rotations.emplace_back(aRb);
191 const Rot3 aRb_estimate = FindKarcherMean<Rot3>(rotations);
193 return alignGivenR(abPointPairs, aRb_estimate);
198 const auto w = xi.head<3>();
199 const auto u = xi.segment<3>(3);
200 const double lambda = xi[6];
212 adj <<
R, Z_3x3, Matrix31::Zero(),
220 const double theta2 = w.transpose() *
w;
225 Y = (1 -
cos(theta)) / theta2;
226 Z = (1 -
X) / theta2;
227 W = (0.5 -
Y) / theta2;
230 Y = 0.5 - theta2 / 24.0;
231 Z = 1.0 / 6.0 - theta2 / 120.0;
232 W = 1.0 / 24.0 - theta2 / 720.0;
234 const double lambda2 = lambda *
lambda, lambda3 = lambda2 *
lambda;
235 const double expMinLambda =
exp(-lambda);
237 if (lambda2 > 1
e-9) {
238 A = (1.0 - expMinLambda) / lambda;
239 alpha = 1.0 / (1.0 + theta2 / lambda2);
240 beta = (expMinLambda - 1 +
lambda) / lambda2;
241 mu = (1 - lambda + (0.5 * lambda2) - expMinLambda) / lambda3;
243 A = 1.0 - lambda / 2.0 + lambda2 / 6.0;
244 beta = 0.5 - lambda / 6.0 + lambda2 / 24.0 - lambda3 / 120.0;
245 mu = 1.0 / 6.0 - lambda / 24.0 + lambda2 / 120.0 - lambda3 / 720.0;
247 const double gamma = Y - (lambda *
Z), upsilon = Z - (lambda * W);
248 const double B = alpha * (beta -
gamma) + gamma;
249 const double C = alpha * (mu - upsilon) + upsilon;
251 return A * I_3x3 + B * Wx + C * Wx * Wx;
262 throw std::runtime_error(
"Similarity3::Logmap: derivative not implemented");
268 const auto w = v.head<3>();
269 const auto u = v.segment<3>(3);
270 const double lambda = v[6];
272 throw std::runtime_error(
"Similarity3::Expmap: derivative not implemented");
274 const Matrix3
V =
GetV(
w, lambda);
287 T.bottomRows<1>() << 0, 0, 0, 1.0 /
s_;
291 Similarity3::operator
Pose3()
const {
GTSAM_EXPORT bool operator==(const Similarity3 &other) const
Exact equality.
GTSAM_EXPORT const Matrix4 matrix() const
Calculate 4*4 matrix group equivalent.
static GTSAM_EXPORT Vector7 Logmap(const Similarity3 &s, OptionalJacobian< 7, 7 > Hm=boost::none)
static GTSAM_EXPORT Similarity3 Expmap(const Vector7 &v, OptionalJacobian< 7, 7 > Hm=boost::none)
static GTSAM_EXPORT Similarity3 identity()
Return an identity transform.
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
Rot2 R(Rot2::fromAngle(0.1))
EIGEN_DEVICE_FUNC const LogReturnType log() const
double scale() const
Return the scale.
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
std::vector< Point3Pair > Point3Pairs
static GTSAM_EXPORT Matrix4 wedge(const Vector7 &xi)
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
GTSAM_EXPORT bool equals(const Similarity3 &sim, double tol) const
Compare with tolerance.
Matrix< SCALARB, Dynamic, Dynamic > B
Rot3 inverse() const
inverse of a rotation
mat1 topRightCorner(size/2, size/2)
Vector3 xyz(OptionalJacobian< 3, 3 > H=boost::none) const
EIGEN_DEVICE_FUNC const CosReturnType cos() const
Class compose(const Class &g) const
const mpreal gamma(const mpreal &x, mp_rnd_t r=mpreal::get_default_rnd())
bool equals(const Rot3 &p, double tol=1e-9) const
GTSAM_EXPORT Similarity3 operator*(const Similarity3 &S) const
Composition.
Base class and basic functions for Manifold types.
GTSAM_EXPORT Similarity3()
Default constructor.
void print(const std::string &s="") const
GTSAM_EXPORT void print(const std::string &s) const
Print with optional string.
const Point3 & translation() const
Return a GTSAM translation.
Eigen::Triplet< double > T
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EIGEN_DEVICE_FUNC const Scalar & q
static GTSAM_EXPORT Similarity3 Align(const std::vector< Point3Pair > &abPointPairs)
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
Matrix< Scalar, Dynamic, Dynamic > C
boost::optional< Pose2 > align(const vector< Point2Pair > &pairs)
Matrix3 skewSymmetric(double wx, double wy, double wz)
GTSAM_EXPORT Similarity3 inverse() const
Return the inverse.
const Rot3 & rotation() const
Return a GTSAM rotation.
ofstream os("timeSchurFactors.csv")
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H=boost::none)
GTSAM_EXPORT Point3 transformFrom(const Point3 &p, OptionalJacobian< 3, 7 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Action on a point p is s*(R*p+t)
Point3Pair means(const std::vector< Point3Pair > &abPointPairs)
Calculate the two means of a set of Point3 pairs.
static Matrix3 GetV(Vector3 w, double lambda)
Calculate expmap and logmap coefficients.
static Rot3 ClosestTo(const Matrix3 &M)
EIGEN_DEVICE_FUNC const SinReturnType sin() const
std::pair< Pose3, Pose3 > Pose3Pair
Implementation of Similarity3 transform.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
GTSAM_EXPORT Matrix7 AdjointMap() const
Project from one tangent space to another.
Eigen::Block< Derived > topLeftCorner(MatrixBase< Derived > &m, int rows, int cols)
std::pair< Point3, Point3 > Point3Pair
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const Similarity3 &p)