2013-12-22 03:55:07 +08:00
|
|
|
/*
|
|
|
|
|
* @file EssentialMatrix.h
|
|
|
|
|
* @brief EssentialMatrix class
|
|
|
|
|
* @author Frank Dellaert
|
|
|
|
|
* @date December 17, 2013
|
|
|
|
|
*/
|
|
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
|
|
#include <gtsam/geometry/Pose3.h>
|
2014-02-23 05:20:28 +08:00
|
|
|
#include <gtsam/geometry/Unit3.h>
|
2013-12-22 03:55:07 +08:00
|
|
|
#include <gtsam/geometry/Point2.h>
|
2014-01-22 14:03:40 +08:00
|
|
|
#include <iostream>
|
2013-12-22 03:55:07 +08:00
|
|
|
|
|
|
|
|
namespace gtsam {
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* An essential matrix is like a Pose3, except with translation up to scale
|
|
|
|
|
* It is named after the 3*3 matrix aEb = [aTb]x aRb from computer vision,
|
2014-02-23 05:20:28 +08:00
|
|
|
* but here we choose instead to parameterize it as a (Rot3,Unit3) pair.
|
2013-12-22 03:55:07 +08:00
|
|
|
* We can then non-linearly optimize immediately on this 5-dimensional manifold.
|
|
|
|
|
*/
|
|
|
|
|
class EssentialMatrix: public DerivedValue<EssentialMatrix> {
|
|
|
|
|
|
|
|
|
|
private:
|
|
|
|
|
|
|
|
|
|
Rot3 aRb_; ///< Rotation between a and b
|
2014-02-23 05:20:28 +08:00
|
|
|
Unit3 aTb_; ///< translation direction from a to b
|
2014-01-06 05:26:19 +08:00
|
|
|
Matrix3 E_; ///< Essential matrix
|
2013-12-22 03:55:07 +08:00
|
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
|
|
/// Static function to convert Point2 to homogeneous coordinates
|
|
|
|
|
static Vector Homogeneous(const Point2& p) {
|
|
|
|
|
return Vector(3) << p.x(), p.y(), 1;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/// @name Constructors and named constructors
|
|
|
|
|
/// @{
|
|
|
|
|
|
2013-12-23 05:04:47 +08:00
|
|
|
/// Default constructor
|
|
|
|
|
EssentialMatrix() :
|
|
|
|
|
aTb_(1, 0, 0), E_(aTb_.skew()) {
|
|
|
|
|
}
|
|
|
|
|
|
2013-12-22 03:55:07 +08:00
|
|
|
/// Construct from rotation and translation
|
2014-02-23 05:20:28 +08:00
|
|
|
EssentialMatrix(const Rot3& aRb, const Unit3& aTb) :
|
2013-12-22 03:55:07 +08:00
|
|
|
aRb_(aRb), aTb_(aTb), E_(aTb_.skew() * aRb_.matrix()) {
|
|
|
|
|
}
|
|
|
|
|
|
2014-01-06 05:26:19 +08:00
|
|
|
/// Named constructor converting a Pose3 with scale to EssentialMatrix (no scale)
|
|
|
|
|
static EssentialMatrix FromPose3(const Pose3& _1P2_,
|
|
|
|
|
boost::optional<Matrix&> H = boost::none);
|
|
|
|
|
|
2014-02-23 05:20:28 +08:00
|
|
|
/// Random, using Rot3::Random and Unit3::Random
|
2013-12-27 03:00:07 +08:00
|
|
|
template<typename Engine>
|
|
|
|
|
static EssentialMatrix Random(Engine & rng) {
|
2014-02-23 05:20:28 +08:00
|
|
|
return EssentialMatrix(Rot3::Random(rng), Unit3::Random(rng));
|
2013-12-27 03:00:07 +08:00
|
|
|
}
|
|
|
|
|
|
2013-12-22 03:55:07 +08:00
|
|
|
/// @}
|
|
|
|
|
|
|
|
|
|
/// @name Testable
|
|
|
|
|
/// @{
|
|
|
|
|
|
|
|
|
|
/// print with optional string
|
2014-01-06 05:26:19 +08:00
|
|
|
void print(const std::string& s = "") const;
|
2013-12-22 03:55:07 +08:00
|
|
|
|
|
|
|
|
/// assert equality up to a tolerance
|
|
|
|
|
bool equals(const EssentialMatrix& other, double tol = 1e-8) const {
|
|
|
|
|
return aRb_.equals(other.aRb_, tol) && aTb_.equals(other.aTb_, tol);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/// @}
|
|
|
|
|
|
|
|
|
|
/// @name Manifold
|
|
|
|
|
/// @{
|
|
|
|
|
|
|
|
|
|
/// Dimensionality of tangent space = 5 DOF
|
|
|
|
|
inline static size_t Dim() {
|
|
|
|
|
return 5;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/// Return the dimensionality of the tangent space
|
|
|
|
|
virtual size_t dim() const {
|
|
|
|
|
return 5;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/// Retract delta to manifold
|
2014-01-06 05:26:19 +08:00
|
|
|
virtual EssentialMatrix retract(const Vector& xi) const;
|
2013-12-22 03:55:07 +08:00
|
|
|
|
|
|
|
|
/// Compute the coordinates in the tangent space
|
2014-01-06 05:26:19 +08:00
|
|
|
virtual Vector localCoordinates(const EssentialMatrix& other) const;
|
2013-12-22 03:55:07 +08:00
|
|
|
|
|
|
|
|
/// @}
|
|
|
|
|
|
|
|
|
|
/// @name Essential matrix methods
|
|
|
|
|
/// @{
|
|
|
|
|
|
|
|
|
|
/// Rotation
|
2014-01-06 05:26:19 +08:00
|
|
|
inline const Rot3& rotation() const {
|
2013-12-22 03:55:07 +08:00
|
|
|
return aRb_;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/// Direction
|
2014-02-23 05:20:28 +08:00
|
|
|
inline const Unit3& direction() const {
|
2013-12-22 03:55:07 +08:00
|
|
|
return aTb_;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/// Return 3*3 matrix representation
|
2014-01-06 05:26:19 +08:00
|
|
|
inline const Matrix3& matrix() const {
|
2013-12-22 03:55:07 +08:00
|
|
|
return E_;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief takes point in world coordinates and transforms it to pose with |t|==1
|
|
|
|
|
* @param p point in world coordinates
|
|
|
|
|
* @param DE optional 3*5 Jacobian wrpt to E
|
|
|
|
|
* @param Dpoint optional 3*3 Jacobian wrpt point
|
|
|
|
|
* @return point in pose coordinates
|
|
|
|
|
*/
|
|
|
|
|
Point3 transform_to(const Point3& p,
|
|
|
|
|
boost::optional<Matrix&> DE = boost::none,
|
2014-01-06 05:26:19 +08:00
|
|
|
boost::optional<Matrix&> Dpoint = boost::none) const;
|
2013-12-22 03:55:07 +08:00
|
|
|
|
2014-01-04 08:54:43 +08:00
|
|
|
/**
|
|
|
|
|
* Given essential matrix E in camera frame B, convert to body frame C
|
|
|
|
|
* @param cRb rotation from body frame to camera frame
|
|
|
|
|
* @param E essential matrix E in camera frame C
|
|
|
|
|
*/
|
|
|
|
|
EssentialMatrix rotate(const Rot3& cRb, boost::optional<Matrix&> HE =
|
2014-01-06 05:26:19 +08:00
|
|
|
boost::none, boost::optional<Matrix&> HR = boost::none) const;
|
2014-01-04 08:54:43 +08:00
|
|
|
|
2014-01-04 06:49:45 +08:00
|
|
|
/**
|
|
|
|
|
* Given essential matrix E in camera frame B, convert to body frame C
|
|
|
|
|
* @param cRb rotation from body frame to camera frame
|
|
|
|
|
* @param E essential matrix E in camera frame C
|
|
|
|
|
*/
|
|
|
|
|
friend EssentialMatrix operator*(const Rot3& cRb, const EssentialMatrix& E) {
|
2014-01-04 08:54:43 +08:00
|
|
|
return E.rotate(cRb);
|
2014-01-04 06:49:45 +08:00
|
|
|
}
|
|
|
|
|
|
2013-12-22 03:55:07 +08:00
|
|
|
/// epipolar error, algebraic
|
|
|
|
|
double error(const Vector& vA, const Vector& vB, //
|
2014-01-06 05:26:19 +08:00
|
|
|
boost::optional<Matrix&> H = boost::none) const;
|
2013-12-22 03:55:07 +08:00
|
|
|
|
|
|
|
|
/// @}
|
|
|
|
|
|
2014-01-22 14:03:40 +08:00
|
|
|
/// @name Streaming operators
|
|
|
|
|
/// @{
|
|
|
|
|
|
2014-01-22 14:05:32 +08:00
|
|
|
/// stream to stream
|
|
|
|
|
friend std::ostream& operator <<(std::ostream& os, const EssentialMatrix& E);
|
2014-01-22 14:03:40 +08:00
|
|
|
|
|
|
|
|
/// stream from stream
|
2014-01-22 14:05:32 +08:00
|
|
|
friend std::istream& operator >>(std::istream& is, EssentialMatrix& E);
|
2014-01-22 14:03:40 +08:00
|
|
|
|
|
|
|
|
/// @}
|
|
|
|
|
|
2013-12-22 03:55:07 +08:00
|
|
|
};
|
|
|
|
|
|
|
|
|
|
} // gtsam
|
|
|
|
|
|