Now argument of LogmapDerivative is correct
parent
1b61d0a7f3
commit
4635d22d7f
|
|
@ -76,7 +76,7 @@ Pose2 Pose2::Expmap(const Vector& xi, OptionalJacobian<3, 3> H) {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
Vector3 Pose2::Logmap(const Pose2& p, OptionalJacobian<3, 3> H) {
|
Vector3 Pose2::Logmap(const Pose2& p, OptionalJacobian<3, 3> H) {
|
||||||
if (H) CONCEPT_NOT_IMPLEMENTED;
|
if (H) *H = Pose2::LogmapDerivative(p);
|
||||||
const Rot2& R = p.r();
|
const Rot2& R = p.r();
|
||||||
const Point2& t = p.t();
|
const Point2& t = p.t();
|
||||||
double w = R.theta();
|
double w = R.theta();
|
||||||
|
|
@ -164,7 +164,8 @@ Matrix3 Pose2::ExpmapDerivative(const Vector3& v) {
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
Matrix3 Pose2::LogmapDerivative(const Vector3& v) {
|
Matrix3 Pose2::LogmapDerivative(const Pose2& p) {
|
||||||
|
Vector3 v = Logmap(p);
|
||||||
double alpha = v[2];
|
double alpha = v[2];
|
||||||
if (fabs(alpha) > 1e-5) {
|
if (fabs(alpha) > 1e-5) {
|
||||||
double alphaInv = 1/alpha;
|
double alphaInv = 1/alpha;
|
||||||
|
|
|
||||||
|
|
@ -157,7 +157,7 @@ public:
|
||||||
static Matrix3 ExpmapDerivative(const Vector3& v);
|
static Matrix3 ExpmapDerivative(const Vector3& v);
|
||||||
|
|
||||||
/// Left-trivialized derivative inverse of the exponential map
|
/// Left-trivialized derivative inverse of the exponential map
|
||||||
static Matrix3 LogmapDerivative(const Vector3& v);
|
static Matrix3 LogmapDerivative(const Pose2& v);
|
||||||
|
|
||||||
// Chart at origin, depends on compile-time flag SLOW_BUT_CORRECT_EXPMAP
|
// Chart at origin, depends on compile-time flag SLOW_BUT_CORRECT_EXPMAP
|
||||||
struct ChartAtOrigin {
|
struct ChartAtOrigin {
|
||||||
|
|
|
||||||
|
|
@ -198,53 +198,44 @@ TEST(Pose2, logmap_full) {
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
Vector3 w(0.1, 0.27, -0.3);
|
TEST( Pose2, ExpmapDerivative1) {
|
||||||
Vector3 w0(0.1, 0.27, 0.0); // alpha = 0
|
Matrix3 actualH;
|
||||||
|
Vector3 w(0.1, 0.27, -0.3);
|
||||||
// Left trivialization Derivative of exp(w) over w:
|
Pose2::Expmap(w,actualH);
|
||||||
// How exp(w) changes when w changes?
|
Matrix3 expectedH = numericalDerivative21<Pose2, Vector3,
|
||||||
// We find y such that: exp(w) exp(y) = exp(w + dw) for dw --> 0
|
OptionalJacobian<3, 3> >(&Pose2::Expmap, w, boost::none, 1e-2);
|
||||||
// => y = log (exp(-w) * exp(w+dw))
|
EXPECT(assert_equal(expectedH, actualH, 1e-5));
|
||||||
Vector3 testDexpL(const Vector3 w, const Vector3& dw) {
|
|
||||||
Vector3 y = Pose2::Logmap(Pose2::Expmap(-w) * Pose2::Expmap(w + dw));
|
|
||||||
return y;
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST( Pose2, ExpmapDerivative) {
|
|
||||||
Matrix actualDexpL = Pose2::ExpmapDerivative(w);
|
|
||||||
Matrix expectedDexpL = numericalDerivative11<Vector3, Vector3>(
|
|
||||||
boost::bind(testDexpL, w, _1), zero(3), 1e-2);
|
|
||||||
EXPECT(assert_equal(expectedDexpL, actualDexpL, 1e-5));
|
|
||||||
|
|
||||||
Matrix actualDexpInvL = Pose2::LogmapDerivative(w);
|
|
||||||
EXPECT(assert_equal(expectedDexpL.inverse(), actualDexpInvL, 1e-5));
|
|
||||||
|
|
||||||
// test case where alpha = 0
|
|
||||||
Matrix actualDexpL0 = Pose2::ExpmapDerivative(w0);
|
|
||||||
Matrix expectedDexpL0 = numericalDerivative11<Vector3, Vector3>(
|
|
||||||
boost::bind(testDexpL, w0, _1), zero(3), 1e-2);
|
|
||||||
EXPECT(assert_equal(expectedDexpL0, actualDexpL0, 1e-5));
|
|
||||||
|
|
||||||
Matrix actualDexpInvL0 = Pose2::LogmapDerivative(w0);
|
|
||||||
EXPECT(assert_equal(expectedDexpL.inverse(), actualDexpInvL, 1e-5));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST( Pose2, ExpmapDerivative2) {
|
TEST( Pose2, ExpmapDerivative2) {
|
||||||
Matrix3 actualH;
|
Matrix3 actualH;
|
||||||
Pose2::Expmap(w,actualH);
|
Vector3 w0(0.1, 0.27, 0.0); // alpha = 0
|
||||||
Matrix3 expectedH = numericalDerivative11<Pose2, Vector3>(
|
Pose2::Expmap(w0,actualH);
|
||||||
boost::bind(Pose2::Expmap, _1, boost::none), w, 1e-2);
|
Matrix3 expectedH = numericalDerivative21<Pose2, Vector3,
|
||||||
|
OptionalJacobian<3, 3> >(&Pose2::Expmap, w0, boost::none, 1e-2);
|
||||||
|
EXPECT(assert_equal(expectedH, actualH, 1e-5));
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
TEST( Pose2, LogmapDerivative1) {
|
||||||
|
Matrix3 actualH;
|
||||||
|
Vector3 w(0.1, 0.27, -0.3);
|
||||||
|
Pose2 p = Pose2::Expmap(w);
|
||||||
|
EXPECT(assert_equal(w, Pose2::Logmap(p,actualH), 1e-5));
|
||||||
|
Matrix3 expectedH = numericalDerivative21<Vector3, Pose2,
|
||||||
|
OptionalJacobian<3, 3> >(&Pose2::Logmap, p, boost::none, 1e-2);
|
||||||
EXPECT(assert_equal(expectedH, actualH, 1e-5));
|
EXPECT(assert_equal(expectedH, actualH, 1e-5));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST( Pose2, LogmapDerivative2) {
|
TEST( Pose2, LogmapDerivative2) {
|
||||||
Pose2 p = Pose2::Expmap(w);
|
Matrix3 actualH;
|
||||||
EXPECT(assert_equal(w, Pose2::Logmap(p), 1e-5));
|
Vector3 w0(0.1, 0.27, 0.0); // alpha = 0
|
||||||
Matrix3 actualH = Pose2::LogmapDerivative(w);
|
Pose2 p = Pose2::Expmap(w0);
|
||||||
Matrix3 expectedH = numericalDerivative11<Vector3, Pose2>(
|
EXPECT(assert_equal(w0, Pose2::Logmap(p,actualH), 1e-5));
|
||||||
boost::bind(Pose2::Logmap, _1, boost::none), p, 1e-2);
|
Matrix3 expectedH = numericalDerivative21<Vector3, Pose2,
|
||||||
|
OptionalJacobian<3, 3> >(&Pose2::Logmap, p, boost::none, 1e-2);
|
||||||
EXPECT(assert_equal(expectedH, actualH, 1e-5));
|
EXPECT(assert_equal(expectedH, actualH, 1e-5));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue