33 const G& t1,
const G& t2) {
41 EXPECT(assert_equal<G>(t1.inverse(),T::Inverse(t1, H1)));
44 EXPECT(assert_equal<G>(t2.inverse(),T::Inverse(t2, H1)));
48 EXPECT(assert_equal<G>(t1 * t2,T::Compose(t1, t2, H1, H2)));
49 EXPECT(
assert_equal(numericalDerivative41<G,G,G,OJ,OJ>(T::Compose, t1, t2, none, none), H1));
50 EXPECT(
assert_equal(numericalDerivative42<G,G,G,OJ,OJ>(T::Compose, t1, t2, none, none), H2));
61 const G& t1,
const G& t2) {
65 typedef typename T::TangentVector
V;
70 V w12 = T::Local(t1, t2);
71 EXPECT(assert_equal<G>(t2, T::Retract(t1,w12, H1, H2)));
72 EXPECT(
assert_equal(numericalDerivative41<G,G,V,OJ,OJ>(T::Retract, t1, w12, none, none), H1));
73 EXPECT(
assert_equal(numericalDerivative42<G,G,V,OJ,OJ>(T::Retract, t1, w12, none, none), H2));
77 EXPECT(
assert_equal(numericalDerivative41<V,G,G,OJ,OJ>(T::Local, t1, t2, none, none), H1));
78 EXPECT(
assert_equal(numericalDerivative42<V,G,G,OJ,OJ>(T::Local, t1, t2, none, none), H2));
82 #define CHECK_LIE_GROUP_DERIVATIVES(t1,t2) \ 83 { gtsam::testLieGroupDerivatives(result_, name_, t1, t2); } 85 #define CHECK_CHART_DERIVATIVES(t1,t2) \ 86 { gtsam::testChartDerivatives(result_, name_, t1, t2); } void testChartDerivatives(TestResult &result_, const std::string &name_, const G &t1, const G &t2)
JacobiRotation< float > G
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Some functions to compute numerical derivatives.
void testLieGroupDerivatives(TestResult &result_, const std::string &name_, const G &t1, const G &t2)
#define EXPECT(condition)
Eigen::Triplet< double > T
BetweenFactor< Rot3 > Between
Base class and basic functions for Lie types.