28 using namespace gtsam;
30 static const double tol = 1
e-9;
39 cout <<
s <<
"(" << m.first <<
"," << m.second.translation() <<
"/" 40 << m.second.theta() <<
")" << endl;
55 d << 1, 2, 0.1, 0.2, 0.3;
70 state1.compose(state2, actH1, actH2);
85 state1.between(state2, actH1, actH2);
111 vec << 1, 2, 0.1, 0.2, 0.3;
121 return Product::Logmap(p);
127 Product::Logmap(state, actH);
ProductLieGroup inverse() const
TEST(Lie, ProductLieGroup)
static int runAllTests(TestResult &result)
T between(const T &t1, const T &t2)
BOOST_CONCEPT_ASSERT((boost::RandomAccessRangeConcept< ListOfOneContainer< int > >))
Pose2_ Expmap(const Vector3_ &xi)
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const boost::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
TangentVector logmap(const ProductLieGroup &g) const
static void Print(const Product &m, const string &s="")
static const NavState state1(x1, v1)
Group product of two Lie Groups.
T compose(const T &t1, const T &t2)
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(boost::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
ProductLieGroup expmap(const TangentVector &v) const
static const NavState state2(x2, v2)
#define EXPECT(condition)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Product inverse_proxy(const Product &A)
Product expmap_proxy(const Vector5 &vec)
Product compose_proxy(const Product &A, const Product &B)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
ProductLieGroup compose(const ProductLieGroup &g) const
ProductLieGroup< Point2, Pose2 > Product
static bool Equals(const Product &m1, const Product &m2, double tol=1e-8)
Product between_proxy(const Product &A, const Product &B)
ProductLieGroup between(const ProductLieGroup &g) const
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(boost::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
Vector5 logmap_proxy(const Product &p)