gtsam/gtsam_unstable/geometry/Similarity3.h

232 lines
6.0 KiB
C
Raw Normal View History

2015-02-19 14:21:20 +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 Similarity3.h
* @brief Implementation of Similarity3 transform
2015-02-27 04:10:59 +08:00
* @author Paul Drews
2015-02-19 14:21:20 +08:00
*/
2015-02-27 04:10:59 +08:00
#pragma once
2015-02-19 14:21:20 +08:00
#include <gtsam/geometry/Rot3.h>
#include <gtsam/geometry/Point3.h>
#include <gtsam/geometry/Pose3.h>
2015-02-27 04:10:59 +08:00
#include <gtsam/base/Lie.h>
2015-02-19 14:21:20 +08:00
#include <gtsam/base/Manifold.h>
2019-07-18 17:09:08 +08:00
#include <gtsam_unstable/dllexport.h>
2015-02-19 14:21:20 +08:00
namespace gtsam {
2015-02-27 04:10:59 +08:00
// Forward declarations
class Pose3;
2015-02-19 14:21:20 +08:00
/**
* 3D similarity transform
*/
class Similarity3: public LieGroup<Similarity3, 7> {
/// @name Pose Concept
/// @{
2015-02-19 14:21:20 +08:00
typedef Rot3 Rotation;
typedef Point3 Translation;
/// @}
2015-02-19 14:21:20 +08:00
private:
Rot3 R_;
Point3 t_;
2015-02-19 14:21:20 +08:00
double s_;
public:
2015-02-27 04:10:59 +08:00
/// @name Constructors
/// @{
/// Default constructor
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT Similarity3();
2015-02-19 14:21:20 +08:00
/// Construct pure scaling
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT Similarity3(double s);
2015-02-19 14:21:20 +08:00
/// Construct from GTSAM types
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT Similarity3(const Rot3& R, const Point3& t, double s);
2015-02-19 14:21:20 +08:00
/// Construct from Eigen types
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT Similarity3(const Matrix3& R, const Vector3& t, double s);
2015-02-19 14:21:20 +08:00
2016-02-08 07:02:07 +08:00
/// Construct from matrix [R t; 0 s^-1]
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT Similarity3(const Matrix4& T);
2016-02-08 07:02:07 +08:00
2015-02-27 04:10:59 +08:00
/// @}
/// @name Testable
/// @{
2015-02-25 23:59:25 +08:00
2015-02-27 04:10:59 +08:00
/// Compare with tolerance
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT bool equals(const Similarity3& sim, double tol) const;
2015-02-19 14:21:20 +08:00
/// Exact equality
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT bool operator==(const Similarity3& other) const;
2015-02-19 14:21:20 +08:00
2015-02-27 04:10:59 +08:00
/// Print with optional string
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT void print(const std::string& s) const;
2015-02-19 14:21:20 +08:00
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT friend std::ostream &operator<<(std::ostream &os, const Similarity3& p);
2015-02-27 04:10:59 +08:00
/// @}
/// @name Group
/// @{
2015-02-19 14:21:20 +08:00
2015-02-27 04:10:59 +08:00
/// Return an identity transform
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT static Similarity3 identity();
2015-02-19 14:21:20 +08:00
/// Composition
2020-08-20 04:48:05 +08:00
GTSAM_UNSTABLE_EXPORT Similarity3 operator*(const Similarity3& S) const;
2015-02-27 04:10:59 +08:00
/// Return the inverse
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT Similarity3 inverse() const;
2015-02-19 14:21:20 +08:00
/// @}
/// @name Group action on Point3
/// @{
/// Action on a point p is s*(R*p+t)
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT Point3 transformFrom(const Point3& p, //
OptionalJacobian<3, 7> H1 = boost::none, //
OptionalJacobian<3, 3> H2 = boost::none) const;
2015-02-19 14:21:20 +08:00
2020-08-22 09:09:36 +08:00
/**
* Action on a pose T.
* |Rs ts| |R t| |Rs*R Rs*t+ts|
* |0 1/s| * |0 1| = | 0 1/s |, the result is still a Sim3 object.
* To retrieve a Pose3, we normalized the scale value into 1.
* |Rs*R Rs*t+ts| |Rs*R s(Rs*t+ts)|
* | 0 1/s | = | 0 1 |
*
* This group action satisfies the compatibility condition.
* For more details, refer to: https://en.wikipedia.org/wiki/Group_action
2020-08-22 09:09:36 +08:00
*/
GTSAM_UNSTABLE_EXPORT Pose3 transformFrom(const Pose3& T) const;
2019-05-17 02:33:58 +08:00
/** syntactic sugar for transformFrom */
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT Point3 operator*(const Point3& p) const;
2015-02-19 14:21:20 +08:00
/**
2020-08-10 20:25:21 +08:00
* Create Similarity3 by aligning at least three point pairs
*/
GTSAM_UNSTABLE_EXPORT static Similarity3 Align(const std::vector<Point3Pair>& abPointPairs);
/**
2020-08-10 20:25:21 +08:00
* Create Similarity3 by aligning at least two pose pairs
*/
GTSAM_UNSTABLE_EXPORT static Similarity3 Align(const std::vector<Pose3Pair>& abPosePairs);
/// @}
/// @name Lie Group
/// @{
2015-06-27 03:44:08 +08:00
/** Log map at the identity
* \f$ [R_x,R_y,R_z, t_x, t_y, t_z, \lambda] \f$
*/
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT static Vector7 Logmap(const Similarity3& s, //
OptionalJacobian<7, 7> Hm = boost::none);
2015-06-27 03:44:08 +08:00
/** Exponential map at the identity
*/
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT static Similarity3 Expmap(const Vector7& v, //
OptionalJacobian<7, 7> Hm = boost::none);
2015-06-27 03:44:08 +08:00
/// Chart at the origin
struct ChartAtOrigin {
2015-06-27 03:44:08 +08:00
static Similarity3 Retract(const Vector7& v, ChartJacobian H = boost::none) {
2016-02-08 07:02:07 +08:00
return Similarity3::Expmap(v, H);
2015-06-27 03:44:08 +08:00
}
static Vector7 Local(const Similarity3& other, ChartJacobian H = boost::none) {
2016-02-08 07:02:07 +08:00
return Similarity3::Logmap(other, H);
2015-06-27 03:44:08 +08:00
}
};
using LieGroup<Similarity3, 7>::inverse;
/**
* wedge for Similarity3:
* @param xi 7-dim twist (w,u,lambda) where
* @return 4*4 element of Lie algebra that can be exponentiated
* TODO(frank): rename to Hat, make part of traits
*/
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT static Matrix4 wedge(const Vector7& xi);
/// Project from one tangent space to another
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT Matrix7 AdjointMap() const;
2015-02-27 04:10:59 +08:00
/// @}
/// @name Standard interface
/// @{
2015-02-19 14:21:20 +08:00
2015-03-03 13:08:23 +08:00
/// Calculate 4*4 matrix group equivalent
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT const Matrix4 matrix() const;
2015-03-03 13:08:23 +08:00
2015-02-27 04:10:59 +08:00
/// Return a GTSAM rotation
const Rot3& rotation() const {
2015-02-27 04:10:59 +08:00
return R_;
}
2015-02-19 14:21:20 +08:00
2015-02-27 04:10:59 +08:00
/// Return a GTSAM translation
const Point3& translation() const {
2015-02-27 04:10:59 +08:00
return t_;
}
2015-02-19 14:21:20 +08:00
2015-02-27 04:10:59 +08:00
/// Return the scale
double scale() const {
return s_;
}
2015-02-27 04:10:59 +08:00
2015-03-03 13:08:41 +08:00
/// Convert to a rigid body pose (R, s*t)
/// TODO(frank): why is this here? Red flag! Definitely don't have it as a cast.
2019-07-18 17:09:08 +08:00
GTSAM_UNSTABLE_EXPORT operator Pose3() const;
2015-02-19 14:21:20 +08:00
/// Dimensionality of tangent space = 7 DOF - used to autodetect sizes
inline static size_t Dim() {
return 7;
}
2015-02-19 14:21:20 +08:00
/// Dimensionality of tangent space = 7 DOF
inline size_t dim() const {
return 7;
}
2015-02-19 14:21:20 +08:00
2015-02-27 04:10:59 +08:00
/// @}
/// @name Helper functions
/// @{
private:
/// Calculate expmap and logmap coefficients.
static Matrix3 GetV(Vector3 w, double lambda);
/// Calculate scale and translation with point pairs, rotation, and centroids.
static Similarity3 GetSim3(const std::vector<Point3Pair>& abPointPairs, const Point3 aCentroid, const Point3 bCentroid, const Rot3 aRb);
/// @}
2015-02-19 14:21:20 +08:00
};
template<>
2016-02-08 07:02:07 +08:00
inline Matrix wedge<Similarity3>(const Vector& xi) {
return Similarity3::wedge(xi);
}
template<>
2016-02-08 07:02:07 +08:00
struct traits<Similarity3> : public internal::LieGroup<Similarity3> {};
2016-02-08 07:02:07 +08:00
template<>
struct traits<const Similarity3> : public internal::LieGroup<Similarity3> {};
} // namespace gtsam