2009-08-22 06:23:24 +08:00
|
|
|
/**
|
|
|
|
* @file Pose3.cpp
|
|
|
|
* @brief 3D Pose
|
|
|
|
*/
|
|
|
|
|
2010-01-08 08:40:17 +08:00
|
|
|
#include <iostream>
|
2010-08-20 01:23:19 +08:00
|
|
|
#include <gtsam/geometry/Pose3.h>
|
|
|
|
#include <gtsam/base/Lie-inl.h>
|
2009-08-22 06:23:24 +08:00
|
|
|
|
2009-08-30 12:51:46 +08:00
|
|
|
using namespace std;
|
2010-01-08 08:40:17 +08:00
|
|
|
using namespace boost::numeric::ublas;
|
2009-08-30 12:51:46 +08:00
|
|
|
|
2009-08-22 06:23:24 +08:00
|
|
|
namespace gtsam {
|
|
|
|
|
2010-01-10 07:15:06 +08:00
|
|
|
/** Explicit instantiation of base class to export members */
|
2010-01-16 09:16:59 +08:00
|
|
|
INSTANTIATE_LIE(Pose3);
|
2010-01-10 07:15:06 +08:00
|
|
|
|
2010-03-12 05:52:24 +08:00
|
|
|
static const Matrix I3 = eye(3), _I3=-I3, I6 = eye(6), Z3 = zeros(3, 3);
|
2010-02-28 17:09:12 +08:00
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
// Calculate Adjoint map
|
|
|
|
// Ad_pose is 6*6 matrix that when applied to twist xi, returns Ad_pose(xi)
|
|
|
|
// Experimental - unit tests of derivatives based on it do not check out yet
|
2010-08-23 05:45:53 +08:00
|
|
|
Matrix Pose3::AdjointMap() const {
|
|
|
|
const Matrix R = R_.matrix();
|
|
|
|
const Vector t = t_.vector();
|
2010-02-28 17:09:12 +08:00
|
|
|
Matrix A = skewSymmetric(t)*R;
|
|
|
|
Matrix DR = collect(2, &R, &Z3);
|
|
|
|
Matrix Dt = collect(2, &A, &R);
|
|
|
|
return gtsam::stack(2, &DR, &Dt);
|
|
|
|
}
|
|
|
|
|
2010-01-08 08:40:17 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
void Pose3::print(const string& s) const {
|
|
|
|
R_.print(s + ".R");
|
|
|
|
t_.print(s + ".t");
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
bool Pose3::equals(const Pose3& pose, double tol) const {
|
|
|
|
return R_.equals(pose.R_,tol) && t_.equals(pose.t_,tol);
|
|
|
|
}
|
|
|
|
|
2010-01-10 20:24:31 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
|
2010-03-13 03:16:53 +08:00
|
|
|
#ifdef CORRECT_POSE3_EXMAP
|
2010-01-08 08:40:17 +08:00
|
|
|
|
2010-03-03 01:56:26 +08:00
|
|
|
/** Modified from Murray94book version (which assumes w and v normalized?) */
|
|
|
|
template<> Pose3 expmap(const Vector& xi) {
|
|
|
|
|
|
|
|
// get angular velocity omega and translational velocity v from twist xi
|
|
|
|
Point3 w(xi(0),xi(1),xi(2)), v(xi(3),xi(4),xi(5));
|
|
|
|
|
|
|
|
double theta = norm(w);
|
|
|
|
if (theta < 1e-5) {
|
|
|
|
static const Rot3 I;
|
|
|
|
return Pose3(I, v);
|
|
|
|
}
|
2010-01-08 08:40:17 +08:00
|
|
|
else {
|
2010-03-03 01:56:26 +08:00
|
|
|
Point3 n(w/theta); // axis unit vector
|
|
|
|
Rot3 R = rodriguez(n.vector(),theta);
|
|
|
|
double vn = dot(n,v); // translation parallel to n
|
|
|
|
Point3 n_cross_v = cross(n,v); // points towards axis
|
|
|
|
Point3 t = (n_cross_v - R*n_cross_v)/theta + vn*n;
|
|
|
|
return Pose3(R, t);
|
2010-01-08 08:40:17 +08:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
Vector logmap(const Pose3& p) {
|
|
|
|
Vector w = logmap(p.rotation()), T = p.translation().vector();
|
|
|
|
double t = norm_2(w);
|
|
|
|
if (t < 1e-5)
|
|
|
|
return concatVectors(2, &w, &T);
|
|
|
|
else {
|
|
|
|
Matrix W = skewSymmetric(w/t);
|
2010-03-03 01:56:26 +08:00
|
|
|
Matrix Ainv = I3 - (0.5*t)*W + ((2*sin(t)-t*(1+cos(t)))/(2*sin(t))) * (W * W);
|
2010-01-08 08:40:17 +08:00
|
|
|
Vector u = Ainv*T;
|
|
|
|
return concatVectors(2, &w, &u);
|
|
|
|
}
|
|
|
|
}
|
2010-01-10 20:24:31 +08:00
|
|
|
|
2010-03-12 05:52:24 +08:00
|
|
|
Pose3 expmap(const Pose3& T, const Vector& d) {
|
|
|
|
return compose(T,expmap<Pose3>(d));
|
|
|
|
}
|
|
|
|
|
|
|
|
Vector logmap(const Pose3& T1, const Pose3& T2) {
|
|
|
|
return logmap(between(T1,T2));
|
|
|
|
}
|
|
|
|
|
2010-01-10 20:24:31 +08:00
|
|
|
#else
|
|
|
|
|
2010-08-20 04:03:06 +08:00
|
|
|
/* ************************************************************************* */
|
2010-01-10 20:24:31 +08:00
|
|
|
/* incorrect versions for which we know how to compute derivatives */
|
2010-08-20 04:03:06 +08:00
|
|
|
Pose3 Pose3::Expmap(const Vector& d) {
|
2010-01-10 20:24:31 +08:00
|
|
|
Vector w = sub(d, 0,3);
|
|
|
|
Vector u = sub(d, 3,6);
|
2010-08-20 04:03:06 +08:00
|
|
|
return Pose3(Rot3::Expmap(w), Point3::Expmap(u));
|
2010-01-10 20:24:31 +08:00
|
|
|
}
|
|
|
|
|
2010-08-20 04:03:06 +08:00
|
|
|
/* ************************************************************************* */
|
2010-01-10 20:24:31 +08:00
|
|
|
// Log map at identity - return the translation and canonical rotation
|
|
|
|
// coordinates of a pose.
|
2010-08-20 04:03:06 +08:00
|
|
|
Vector Pose3::Logmap(const Pose3& p) {
|
|
|
|
const Vector w = Rot3::Logmap(p.rotation()), u = Point3::Logmap(p.translation());
|
2010-01-10 20:24:31 +08:00
|
|
|
return concatVectors(2, &w, &u);
|
|
|
|
}
|
|
|
|
|
2010-03-12 05:52:24 +08:00
|
|
|
/** These are the "old-style" expmap and logmap about the specified
|
|
|
|
* pose. Increments the offset and rotation independently given a translation and
|
|
|
|
* canonical rotation coordinates. Created to match ML derivatives, but
|
|
|
|
* superseded by the correct exponential map story in .cpp */
|
|
|
|
Pose3 expmap(const Pose3& p0, const Vector& d) {
|
|
|
|
return Pose3(expmap(p0.rotation(), sub(d, 0, 3)),
|
|
|
|
expmap(p0.translation(), sub(d, 3, 6)));
|
|
|
|
}
|
|
|
|
|
|
|
|
/** Independently computes the logmap of the translation and rotation. */
|
|
|
|
Vector logmap(const Pose3& p0, const Pose3& pp) {
|
|
|
|
const Vector r(logmap(p0.rotation(), pp.rotation())),
|
|
|
|
t(logmap(p0.translation(), pp.translation()));
|
|
|
|
return concatVectors(2, &r, &t);
|
|
|
|
}
|
|
|
|
|
|
|
|
#endif
|
2010-01-08 08:40:17 +08:00
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
Matrix Pose3::matrix() const {
|
|
|
|
const Matrix R = R_.matrix(), T = Matrix_(3,1, t_.vector());
|
|
|
|
const Matrix A34 = collect(2, &R, &T);
|
|
|
|
const Matrix A14 = Matrix_(1,4, 0.0, 0.0, 0.0, 1.0);
|
2010-02-17 11:29:12 +08:00
|
|
|
return gtsam::stack(2, &A34, &A14);
|
2010-01-08 08:40:17 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
Pose3 Pose3::transform_to(const Pose3& pose) 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
|
|
|
Rot3 cRv = R_ * Rot3(gtsam::inverse(pose.R_));
|
2010-08-23 05:45:53 +08:00
|
|
|
Point3 t = pose.transform_to(t_);
|
2010-01-08 08:40:17 +08:00
|
|
|
return Pose3(cRv, t);
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2010-08-23 05:45:53 +08:00
|
|
|
// Point3 Pose3::transform_from(const Pose3& pose, const Point3& p) {
|
|
|
|
// return pose.rotation() * p + pose.translation();
|
|
|
|
// }
|
2010-01-08 08:40:17 +08:00
|
|
|
|
2010-05-18 22:51:09 +08:00
|
|
|
/* ************************************************************************* */
|
2010-08-23 05:45:53 +08:00
|
|
|
Point3 Pose3::transform_from(const Point3& p,
|
|
|
|
boost::optional<Matrix&> H1, boost::optional<Matrix&> H2) const {
|
2010-08-20 23:17:13 +08:00
|
|
|
if (H1) {
|
2010-03-13 03:16:53 +08:00
|
|
|
#ifdef CORRECT_POSE3_EXMAP
|
2010-08-23 05:45:53 +08:00
|
|
|
const Matrix R = R_.matrix();
|
2010-08-20 23:17:13 +08:00
|
|
|
Matrix DR = R*skewSymmetric(-p.x(), -p.y(), -p.z());
|
|
|
|
*H1 = collect(2,&DR,&R);
|
2010-01-08 08:40:17 +08:00
|
|
|
#else
|
2010-08-20 23:17:13 +08:00
|
|
|
Matrix DR;
|
2010-08-23 05:45:53 +08:00
|
|
|
R_.rotate(p, DR, boost::none);
|
2010-08-20 23:17:13 +08:00
|
|
|
*H1 = collect(2,&DR,&I3);
|
2010-03-01 09:35:33 +08:00
|
|
|
#endif
|
2010-08-20 23:17:13 +08:00
|
|
|
}
|
2010-08-23 05:45:53 +08:00
|
|
|
if (H2) *H2 = R_.matrix();
|
|
|
|
return R_ * p + t_;
|
2010-01-08 08:40:17 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2010-08-23 05:45:53 +08:00
|
|
|
// Point3 Pose3::transform_to(const Pose3& pose, const Point3& p) {
|
|
|
|
// Point3 sub = p - pose.translation();
|
|
|
|
// return pose.rotation().unrotate(sub);
|
|
|
|
// }
|
2010-01-08 08:40:17 +08:00
|
|
|
|
2010-05-18 22:51:09 +08:00
|
|
|
/* ************************************************************************* */
|
2010-08-23 05:45:53 +08:00
|
|
|
Point3 Pose3::transform_to(const Point3& p,
|
|
|
|
boost::optional<Matrix&> H1, boost::optional<Matrix&> H2) const {
|
|
|
|
const Point3 result = R_.unrotate(p - t_);
|
2010-08-20 23:17:13 +08:00
|
|
|
if (H1) { // *H1 = Dtransform_to1(pose, p);
|
2010-08-23 05:45:53 +08:00
|
|
|
const Point3& q = result;
|
2010-08-20 23:17:13 +08:00
|
|
|
Matrix DR = skewSymmetric(q.x(), q.y(), q.z());
|
2010-03-13 03:16:53 +08:00
|
|
|
#ifdef CORRECT_POSE3_EXMAP
|
2010-08-20 23:17:13 +08:00
|
|
|
*H1 = collect(2, &DR, &_I3);
|
2010-03-12 05:52:24 +08:00
|
|
|
#else
|
2010-08-23 05:45:53 +08:00
|
|
|
Matrix DT = - R_.transpose(); // negative because of sub
|
2010-08-20 23:17:13 +08:00
|
|
|
*H1 = collect(2,&DR,&DT);
|
2010-03-12 05:52:24 +08:00
|
|
|
#endif
|
2010-08-20 23:17:13 +08:00
|
|
|
}
|
2010-01-08 08:40:17 +08:00
|
|
|
|
2010-08-23 05:45:53 +08:00
|
|
|
if (H2) *H2 = R_.transpose();
|
|
|
|
return result;
|
2010-01-08 08:40:17 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2010-08-20 23:17:13 +08:00
|
|
|
Pose3 compose(const Pose3& p1, const Pose3& p2,
|
|
|
|
boost::optional<Matrix&> H1, boost::optional<Matrix&> H2) {
|
|
|
|
if (H1) {
|
2010-03-13 03:16:53 +08:00
|
|
|
#ifdef CORRECT_POSE3_EXMAP
|
2010-08-20 23:17:13 +08:00
|
|
|
*H1 = AdjointMap(inverse(p2));
|
2010-02-28 17:09:12 +08:00
|
|
|
#else
|
|
|
|
const Rot3& R2 = p2.rotation();
|
|
|
|
const Point3& t2 = p2.translation();
|
2010-08-20 23:17:13 +08:00
|
|
|
Matrix DR_R1 = R2.transpose(), DR_t1 = Z3;
|
2010-01-08 11:38:05 +08:00
|
|
|
Matrix DR = collect(2, &DR_R1, &DR_t1);
|
2010-08-20 23:17:13 +08:00
|
|
|
Matrix Dt;
|
2010-08-23 05:45:53 +08:00
|
|
|
p1.transform_from(t2, Dt, boost::none);
|
2010-08-20 23:17:13 +08:00
|
|
|
*H1 = gtsam::stack(2, &DR, &Dt);
|
2010-02-28 17:09:12 +08:00
|
|
|
#endif
|
2010-08-20 23:17:13 +08:00
|
|
|
}
|
|
|
|
if (H2) {
|
2010-03-13 03:16:53 +08:00
|
|
|
#ifdef CORRECT_POSE3_EXMAP
|
2010-03-12 05:52:24 +08:00
|
|
|
|
2010-08-20 23:17:13 +08:00
|
|
|
*H2 = I6;
|
2010-02-28 17:09:12 +08:00
|
|
|
#else
|
2010-01-27 04:00:17 +08:00
|
|
|
Matrix R1 = p1.rotation().matrix();
|
2010-02-28 17:09:12 +08:00
|
|
|
Matrix DR = collect(2, &I3, &Z3);
|
2010-01-08 11:38:05 +08:00
|
|
|
Matrix Dt = collect(2, &Z3, &R1);
|
2010-08-20 23:17:13 +08:00
|
|
|
*H2 = gtsam::stack(2, &DR, &Dt);
|
2010-02-28 17:09:12 +08:00
|
|
|
#endif
|
2010-08-20 23:17:13 +08:00
|
|
|
}
|
|
|
|
return p1.compose(p2);
|
|
|
|
}
|
2010-01-08 08:40:17 +08:00
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2010-08-20 23:17:13 +08:00
|
|
|
Pose3 inverse(const Pose3& p, boost::optional<Matrix&> H1) {
|
|
|
|
if (H1)
|
2010-03-13 03:16:53 +08:00
|
|
|
#ifdef CORRECT_POSE3_EXMAP
|
2010-08-20 23:17:13 +08:00
|
|
|
{ *H1 = - AdjointMap(p); }
|
2010-02-28 17:09:12 +08:00
|
|
|
#else
|
2010-08-20 23:17:13 +08:00
|
|
|
{
|
2010-02-28 17:09:12 +08:00
|
|
|
const Rot3& R = p.rotation();
|
|
|
|
const Point3& t = p.translation();
|
|
|
|
Matrix Rt = R.transpose();
|
|
|
|
Matrix DR_R1 = -R.matrix(), DR_t1 = Z3;
|
2010-08-23 05:45:53 +08:00
|
|
|
Matrix Dt_R1 = -skewSymmetric(R.unrotate(t).vector()), Dt_t1 = -Rt;
|
2010-01-08 11:38:05 +08:00
|
|
|
Matrix DR = collect(2, &DR_R1, &DR_t1);
|
|
|
|
Matrix Dt = collect(2, &Dt_R1, &Dt_t1);
|
2010-08-20 23:17:13 +08:00
|
|
|
*H1 = gtsam::stack(2, &DR, &Dt);
|
|
|
|
}
|
2010-02-28 17:09:12 +08:00
|
|
|
#endif
|
2010-08-20 23:17:13 +08:00
|
|
|
return p.inverse();
|
2010-01-08 11:38:05 +08:00
|
|
|
}
|
2010-01-08 08:40:17 +08:00
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
// between = compose(p2,inverse(p1));
|
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-08-20 23:17:13 +08:00
|
|
|
Matrix invH;
|
|
|
|
Pose3 invp1 = inverse(p1, invH);
|
|
|
|
Matrix composeH1;
|
|
|
|
Pose3 result = compose(invp1, p2, composeH1, H2);
|
|
|
|
if (H1) *H1 = composeH1 * invH;
|
2010-01-16 09:16:59 +08:00
|
|
|
return result;
|
|
|
|
}
|
2010-01-08 08:40:17 +08:00
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2009-08-22 06:23:24 +08:00
|
|
|
} // namespace gtsam
|