2009-08-22 06:23:24 +08:00
|
|
|
/**
|
|
|
|
|
*@file Pose3.h
|
|
|
|
|
*@brief 3D Pose
|
|
|
|
|
*/
|
|
|
|
|
|
|
|
|
|
// \callgraph
|
|
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
2010-01-08 08:40:17 +08:00
|
|
|
#include <boost/numeric/ublas/vector_proxy.hpp>
|
|
|
|
|
|
2010-08-20 01:23:19 +08:00
|
|
|
#include <gtsam/geometry/Point3.h>
|
|
|
|
|
#include <gtsam/geometry/Rot3.h>
|
|
|
|
|
#include <gtsam/base/Testable.h>
|
|
|
|
|
#include <gtsam/base/Lie.h>
|
2009-08-22 06:23:24 +08:00
|
|
|
|
|
|
|
|
namespace gtsam {
|
|
|
|
|
|
2010-01-08 08:40:17 +08:00
|
|
|
/** A 3D pose (R,t) : (Rot3,Point3) */
|
2010-01-10 07:15:06 +08:00
|
|
|
class Pose3 : Testable<Pose3>, public Lie<Pose3> {
|
2010-08-20 04:03:06 +08:00
|
|
|
public:
|
|
|
|
|
static const size_t dimension = 6;
|
|
|
|
|
|
2010-01-08 08:40:17 +08:00
|
|
|
private:
|
|
|
|
|
Rot3 R_;
|
|
|
|
|
Point3 t_;
|
|
|
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
|
|
/** Default constructor is origin */
|
|
|
|
|
Pose3() {}
|
|
|
|
|
|
|
|
|
|
/** Copy constructor */
|
|
|
|
|
Pose3(const Pose3& pose) : R_(pose.R_), t_(pose.t_) {}
|
|
|
|
|
|
|
|
|
|
/** Construct from R,t */
|
|
|
|
|
Pose3(const Rot3& R, const Point3& t) : R_(R), t_(t) {}
|
|
|
|
|
|
|
|
|
|
/** Constructor from 4*4 matrix */
|
|
|
|
|
Pose3(const Matrix &T) :
|
|
|
|
|
R_(T(0, 0), T(0, 1), T(0, 2), T(1, 0), T(1, 1), T(1, 2), T(2, 0),
|
|
|
|
|
T(2, 1), T(2, 2)), t_(T(0, 3), T(1, 3), T(2, 3)) {}
|
|
|
|
|
|
|
|
|
|
/** Constructor from 12D vector */
|
|
|
|
|
Pose3(const Vector &V) :
|
|
|
|
|
R_(V(0), V(3), V(6), V(1), V(4), V(7), V(2), V(5), V(8)),
|
|
|
|
|
t_(V(9), V(10),V(11)) {}
|
|
|
|
|
|
2010-02-24 14:14:43 +08:00
|
|
|
inline const Rot3& rotation() const { return R_; }
|
|
|
|
|
inline const Point3& translation() const { return t_; }
|
2010-01-08 08:40:17 +08:00
|
|
|
|
2010-02-24 14:14:43 +08:00
|
|
|
inline double x() const { return t_.x(); }
|
|
|
|
|
inline double y() const { return t_.y(); }
|
|
|
|
|
inline double z() const { return t_.z(); }
|
2010-01-08 08:40:17 +08:00
|
|
|
|
|
|
|
|
/** convert to 4*4 matrix */
|
|
|
|
|
Matrix matrix() const;
|
|
|
|
|
|
|
|
|
|
/** print with optional string */
|
|
|
|
|
void print(const std::string& s = "") const;
|
|
|
|
|
|
|
|
|
|
/** assert equality up to a tolerance */
|
|
|
|
|
bool equals(const Pose3& pose, double tol = 1e-9) const;
|
|
|
|
|
|
Rot2 "named constructors" (http://www.parashift.com/c++-faq-lite/ctors.html#faq-10.8):
/** Named constructor from angle == exponential map at identity */
static Rot2 fromAngle(double theta) { return Rot2(cos(theta),sin(theta));}
/** Named constructor from cos(theta),sin(theta) pair, will *not* normalize! */
static Rot2 fromCosSin(double c, double s);
/** Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes */
static Rot2 atan2(double y, double x);
which are a bit more verbose, but at least won't cause hours of bug-tracking :-(
I also made most compose, inverse, and rotate functions into methods, with the global functions mostly calling the methods. Methods have privileged access to members and hence are typically much more readable.
2010-03-03 11:31:53 +08:00
|
|
|
/** Compose two poses */
|
|
|
|
|
inline Pose3 operator*(const Pose3& T) const {
|
2010-08-20 04:03:06 +08:00
|
|
|
return Pose3(R_*T.R_, t_ + R_*T.t_);
|
Rot2 "named constructors" (http://www.parashift.com/c++-faq-lite/ctors.html#faq-10.8):
/** Named constructor from angle == exponential map at identity */
static Rot2 fromAngle(double theta) { return Rot2(cos(theta),sin(theta));}
/** Named constructor from cos(theta),sin(theta) pair, will *not* normalize! */
static Rot2 fromCosSin(double c, double s);
/** Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes */
static Rot2 atan2(double y, double x);
which are a bit more verbose, but at least won't cause hours of bug-tracking :-(
I also made most compose, inverse, and rotate functions into methods, with the global functions mostly calling the methods. Methods have privileged access to members and hence are typically much more readable.
2010-03-03 11:31:53 +08:00
|
|
|
}
|
|
|
|
|
|
2010-01-08 08:40:17 +08:00
|
|
|
Pose3 transform_to(const Pose3& pose) const;
|
|
|
|
|
|
2010-08-20 04:03:06 +08:00
|
|
|
/** dimension of the variable - used to autodetect sizes */
|
|
|
|
|
inline static size_t Dim() { return dimension; }
|
|
|
|
|
|
|
|
|
|
/** Lie requirements */
|
|
|
|
|
|
|
|
|
|
/** Dimensionality of the tangent space */
|
|
|
|
|
inline size_t dim() const { return dimension; }
|
|
|
|
|
|
|
|
|
|
/** Find the inverse pose s.t. inverse(p)*p = Pose3() */
|
|
|
|
|
inline Pose3 inverse() const {
|
|
|
|
|
Rot3 Rt = R_.inverse();
|
|
|
|
|
return Pose3(Rt, Rt*(-t_));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/** composes two poses */
|
|
|
|
|
inline Pose3 compose(const Pose3& t) const { return *this * t; }
|
|
|
|
|
|
|
|
|
|
/** Exponential map at identity - create a pose with a translation and
|
|
|
|
|
* rotation (in canonical coordinates). */
|
|
|
|
|
static Pose3 Expmap(const Vector& v);
|
|
|
|
|
|
|
|
|
|
/** Log map at identity - return the translation and canonical rotation
|
|
|
|
|
* coordinates of a pose. */
|
|
|
|
|
static Vector Logmap(const Pose3& p);
|
2010-03-02 05:56:13 +08:00
|
|
|
|
2010-01-08 08:40:17 +08:00
|
|
|
private:
|
|
|
|
|
/** 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_);
|
|
|
|
|
}
|
|
|
|
|
}; // Pose3 class
|
|
|
|
|
|
2010-03-12 05:52:24 +08:00
|
|
|
/** Exponential map around another pose */
|
|
|
|
|
Pose3 expmap(const Pose3& T, const Vector& d);
|
2010-01-08 08:40:17 +08:00
|
|
|
|
2010-03-12 05:52:24 +08:00
|
|
|
/** Logarithm map around another pose T1 */
|
|
|
|
|
Vector logmap(const Pose3& T1, const Pose3& T2);
|
2010-01-08 08:40:17 +08:00
|
|
|
|
|
|
|
|
/** receives the point in Pose coordinates and transforms it to world coordinates */
|
|
|
|
|
Point3 transform_from(const Pose3& pose, const Point3& p);
|
|
|
|
|
inline Point3 operator*(const Pose3& pose, const Point3& p) { return transform_from(pose, p); }
|
2010-05-18 22:51:09 +08:00
|
|
|
Point3 transform_from(const Pose3& pose, const Point3& p,
|
|
|
|
|
boost::optional<Matrix&> H1, boost::optional<Matrix&> H2);
|
|
|
|
|
|
2010-01-08 08:40:17 +08:00
|
|
|
/** receives the point in world coordinates and transforms it to Pose coordinates */
|
|
|
|
|
Point3 transform_to(const Pose3& pose, const Point3& p);
|
2010-05-18 22:51:09 +08:00
|
|
|
Point3 transform_to(const Pose3& pose, const Point3& p,
|
|
|
|
|
boost::optional<Matrix&> H1, boost::optional<Matrix&> H2);
|
2010-01-08 08:40:17 +08:00
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Derivatives of compose
|
|
|
|
|
*/
|
2010-08-20 23:17:13 +08:00
|
|
|
Pose3 compose(const Pose3& p1, const Pose3& p2,
|
|
|
|
|
boost::optional<Matrix&> H1, boost::optional<Matrix&> H2);
|
2010-01-08 08:40:17 +08:00
|
|
|
/**
|
|
|
|
|
* Derivative of inverse
|
|
|
|
|
*/
|
2010-08-20 23:17:13 +08:00
|
|
|
Pose3 inverse(const Pose3& p, boost::optional<Matrix&> H1);
|
2010-01-08 08:40:17 +08:00
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Return relative pose between p1 and p2, in p1 coordinate frame
|
2010-01-16 09:16:59 +08:00
|
|
|
* as well as optionally the derivatives
|
2010-01-08 08:40:17 +08:00
|
|
|
*/
|
2010-01-16 09:16:59 +08:00
|
|
|
Pose3 between(const Pose3& p1, const Pose3& p2,
|
|
|
|
|
boost::optional<Matrix&> H1, boost::optional<Matrix&> H2);
|
2010-01-08 08:40:17 +08:00
|
|
|
|
2010-03-02 10:25:27 +08:00
|
|
|
/**
|
|
|
|
|
* wedge for Pose3:
|
|
|
|
|
* @param xi 6-dim twist (omega,v) where
|
|
|
|
|
* omega = (wx,wy,wz) 3D angular velocity
|
|
|
|
|
* v (vx,vy,vz) = 3D velocity
|
|
|
|
|
* @return xihat, 4*4 element of Lie algebra that can be exponentiated
|
|
|
|
|
*/
|
|
|
|
|
inline Matrix wedge(double wx, double wy, double wz, double vx, double vy, double vz) {
|
|
|
|
|
return Matrix_(4,4,
|
|
|
|
|
0.,-wz, wy, vx,
|
|
|
|
|
wz, 0.,-wx, vy,
|
|
|
|
|
-wy, wx, 0., vz,
|
|
|
|
|
0., 0., 0., 0.);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* wedge for Pose3:
|
|
|
|
|
* @param xi 6-dim twist (omega,v) where
|
|
|
|
|
* omega = 3D angular velocity
|
|
|
|
|
* v = 3D velocity
|
|
|
|
|
* @return xihat, 4*4 element of Lie algebra that can be exponentiated
|
|
|
|
|
*/
|
|
|
|
|
template <>
|
|
|
|
|
inline Matrix wedge<Pose3>(const Vector& xi) {
|
|
|
|
|
return wedge(xi(0),xi(1),xi(2),xi(3),xi(4),xi(5));
|
|
|
|
|
}
|
|
|
|
|
|
2010-03-03 01:56:26 +08:00
|
|
|
/**
|
|
|
|
|
* Calculate Adjoint map
|
|
|
|
|
* Ad_pose is 6*6 matrix that when applied to twist xi, returns Ad_pose(xi)
|
|
|
|
|
*/
|
|
|
|
|
Matrix AdjointMap(const Pose3& p);
|
|
|
|
|
inline Vector Adjoint(const Pose3& p, const Vector& xi) {return AdjointMap(p)*xi; }
|
|
|
|
|
|
2009-08-22 06:23:24 +08:00
|
|
|
} // namespace gtsam
|