gtsam/gtsam/geometry/Similarity2.h

226 lines
5.7 KiB
C
Raw Normal View History

2021-11-07 03:31:33 +08:00
/* ----------------------------------------------------------------------------
* 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.h
* @brief Implementation of Similarity2 transform
2022-04-30 17:12:43 +08:00
* @author John Lambert, Varun Agrawal
2021-11-07 03:31:33 +08:00
*/
#pragma once
#include <gtsam/base/Lie.h>
#include <gtsam/base/Manifold.h>
#include <gtsam/dllexport.h>
2022-02-06 13:08:54 +08:00
#include <gtsam/geometry/Point2.h>
#include <gtsam/geometry/Pose2.h>
#include <gtsam/geometry/Rot2.h>
2021-11-07 03:31:33 +08:00
namespace gtsam {
// Forward declarations
class Pose2;
/**
* 2D similarity transform
*/
2022-04-30 05:36:53 +08:00
class GTSAM_EXPORT Similarity2 : public LieGroup<Similarity2, 4> {
2021-11-07 03:31:33 +08:00
/// @name Pose Concept
/// @{
typedef Rot2 Rotation;
typedef Point2 Translation;
/// @}
2022-02-06 13:08:54 +08:00
private:
2021-11-07 03:31:33 +08:00
Rot2 R_;
Point2 t_;
double s_;
2022-02-06 13:08:54 +08:00
public:
2021-11-07 03:31:33 +08:00
/// @name Constructors
/// @{
/// Default constructor
2022-04-30 05:36:53 +08:00
Similarity2();
2021-11-07 03:31:33 +08:00
/// Construct pure scaling
2022-04-30 05:36:53 +08:00
Similarity2(double s);
2021-11-07 03:31:33 +08:00
/// Construct from GTSAM types
2022-04-30 05:36:53 +08:00
Similarity2(const Rot2& R, const Point2& t, double s);
2021-11-07 03:31:33 +08:00
2022-02-06 13:08:54 +08:00
/// Construct from Eigen types
2022-04-30 05:36:53 +08:00
Similarity2(const Matrix2& R, const Vector2& t, double s);
2021-11-07 03:31:33 +08:00
2022-02-06 13:08:54 +08:00
/// Construct from matrix [R t; 0 s^-1]
2022-04-30 05:36:53 +08:00
Similarity2(const Matrix3& T);
2021-11-07 03:31:33 +08:00
/// @}
/// @name Testable
/// @{
/// Compare with tolerance
2022-04-30 05:36:53 +08:00
bool equals(const Similarity2& sim, double tol) const;
2021-11-07 03:31:33 +08:00
/// Exact equality
2022-04-30 05:36:53 +08:00
bool operator==(const Similarity2& other) const;
2021-11-07 03:31:33 +08:00
/// Print with optional string
2023-09-27 05:51:52 +08:00
void print(const std::string& s = "") const;
2021-11-07 03:31:33 +08:00
GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os,
const Similarity2& p);
2021-11-07 03:31:33 +08:00
/// @}
/// @name Group
/// @{
/// Return an identity transform
static Similarity2 Identity();
2021-11-07 03:31:33 +08:00
/// Composition
2022-04-30 05:36:53 +08:00
Similarity2 operator*(const Similarity2& S) const;
2021-11-07 03:31:33 +08:00
/// Return the inverse
2022-04-30 05:36:53 +08:00
Similarity2 inverse() const;
2021-11-07 03:31:33 +08:00
2022-02-06 13:08:54 +08:00
/// @}
/// @name Group action on Point2
/// @{
2021-11-07 03:31:33 +08:00
/// Action on a point p is s*(R*p+t)
2022-04-30 05:36:53 +08:00
Point2 transformFrom(const Point2& p) const;
2021-11-07 03:31:33 +08:00
2022-02-06 13:08:54 +08:00
/**
2021-11-07 03:31:33 +08:00
* Action on a pose T.
2022-02-06 13:08:54 +08:00
* |Rs ts| |R t| |Rs*R Rs*t+ts|
2021-11-07 03:31:33 +08:00
* |0 1/s| * |0 1| = | 0 1/s |, the result is still a Sim2 object.
* To retrieve a Pose2, we normalized the scale value into 1.
* |Rs*R Rs*t+ts| |Rs*R s(Rs*t+ts)|
* | 0 1/s | = | 0 1 |
2022-02-06 13:08:54 +08:00
*
* This group action satisfies the compatibility condition.
2021-11-07 03:31:33 +08:00
* For more details, refer to: https://en.wikipedia.org/wiki/Group_action
*/
2022-04-30 05:36:53 +08:00
Pose2 transformFrom(const Pose2& T) const;
2021-11-07 03:31:33 +08:00
2021-12-08 08:07:50 +08:00
/* syntactic sugar for transformFrom */
2022-04-30 05:36:53 +08:00
Point2 operator*(const Point2& p) const;
2021-11-07 03:31:33 +08:00
2022-02-06 13:08:54 +08:00
/**
* Create Similarity2 by aligning at least two point pairs
*/
2022-04-30 05:36:53 +08:00
static Similarity2 Align(const Point2Pairs& abPointPairs);
2022-02-06 13:08:54 +08:00
/**
* Create the Similarity2 object that aligns at least two pose pairs.
* Each pair is of the form (aTi, bTi).
* Given a list of pairs in frame a, and a list of pairs in frame b,
Align()
* will compute the best-fit Similarity2 aSb transformation to align them.
* First, the rotation aRb will be computed as the average (Karcher mean)
of
* many estimates aRb (from each pair). Afterwards, the scale factor will
be computed
* using the algorithm described here:
* http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf
*/
static Similarity2 Align(const Pose2Pairs& abPosePairs);
2021-11-07 03:31:33 +08:00
/// @}
/// @name Lie Group
/// @{
2025-03-09 00:39:25 +08:00
using LieAlgebra = Matrix3;
2025-03-11 03:49:35 +08:00
/// Calculate expmap and logmap coefficients.
static Matrix2 GetV(double theta, double lambda);
2022-04-30 17:12:43 +08:00
/**
* Log map at the identity
* \f$ [t_x, t_y, \delta, \lambda] \f$
*/
static Vector4 Logmap(const Similarity2& S, //
2023-01-14 06:11:03 +08:00
OptionalJacobian<4, 4> Hm = {});
2022-04-30 17:12:43 +08:00
/// Exponential map at the identity
static Similarity2 Expmap(const Vector4& v, //
2023-01-14 06:11:03 +08:00
OptionalJacobian<4, 4> Hm = {});
2022-04-30 17:12:43 +08:00
/// Chart at the origin
struct ChartAtOrigin {
static Similarity2 Retract(const Vector4& v,
2023-01-14 06:11:03 +08:00
ChartJacobian H = {}) {
2022-04-30 17:12:43 +08:00
return Similarity2::Expmap(v, H);
}
static Vector4 Local(const Similarity2& other,
2023-01-14 06:11:03 +08:00
ChartJacobian H = {}) {
2022-04-30 17:12:43 +08:00
return Similarity2::Logmap(other, H);
}
};
2022-04-30 20:52:19 +08:00
/// Project from one tangent space to another
Matrix4 AdjointMap() const;
2021-11-07 03:31:33 +08:00
using LieGroup<Similarity2, 4>::inverse;
2025-03-09 00:39:25 +08:00
/// Hat maps from tangent vector to Lie algebra
2025-03-09 04:25:59 +08:00
static Matrix3 Hat(const Vector4& xi);
2025-03-09 00:39:25 +08:00
/// Vee maps from Lie algebra to tangent vector
2025-03-09 04:25:59 +08:00
static Vector4 Vee(const Matrix3& X);
2025-03-09 00:39:25 +08:00
2021-11-07 03:31:33 +08:00
/// @}
/// @name Standard interface
/// @{
/// Calculate 4*4 matrix group equivalent
2022-04-30 05:36:53 +08:00
Matrix3 matrix() const;
2021-11-07 03:31:33 +08:00
/// Return a GTSAM rotation
2022-02-06 13:08:54 +08:00
Rot2 rotation() const { return R_; }
2021-11-07 03:31:33 +08:00
/// Return a GTSAM translation
2022-02-06 13:08:54 +08:00
Point2 translation() const { return t_; }
2021-11-07 03:31:33 +08:00
/// Return the scale
2022-02-06 13:08:54 +08:00
double scale() const { return s_; }
2021-11-07 03:31:33 +08:00
/// Dimensionality of tangent space = 4 DOF - used to autodetect sizes
2022-02-06 13:08:54 +08:00
inline static size_t Dim() { return 4; }
2021-11-07 03:31:33 +08:00
/// Dimensionality of tangent space = 4 DOF
2022-02-06 13:08:54 +08:00
inline size_t dim() const { return 4; }
2021-11-07 03:31:33 +08:00
2025-03-21 23:00:36 +08:00
private:
#if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_NVP(R_);
ar & BOOST_SERIALIZATION_NVP(t_);
ar & BOOST_SERIALIZATION_NVP(s_);
}
#endif
2021-11-07 03:31:33 +08:00
/// @}
};
2022-02-06 13:08:54 +08:00
template <>
2025-03-09 04:25:59 +08:00
struct traits<Similarity2> : public internal::MatrixLieGroup<Similarity2> {};
2021-11-07 03:31:33 +08:00
2022-02-06 13:08:54 +08:00
template <>
2025-03-09 04:25:59 +08:00
struct traits<const Similarity2> : public internal::MatrixLieGroup<Similarity2> {};
2021-11-07 03:31:33 +08:00
2022-02-06 13:08:54 +08:00
} // namespace gtsam