Go to the documentation of this file.
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;
111 vec << 1, 2, 0.1, 0.2, 0.3;
121 return Product::Logmap(
p);
127 Product::Logmap(
state, actH);
134 return interpolate<Product>(
x,
y,
t);
142 Matrix actH1, numericH1, actH2, numericH2;
145 interpolate<Product>(
x,
y,
t, actH1, actH2);
146 numericH1 = numericalDerivative31<Product, Product, Product, double>(
149 numericH2 = numericalDerivative32<Product, Product, Product, double>(
154 interpolate<Product>(
x,
y,
t, actH1, actH2);
155 numericH1 = numericalDerivative31<Product, Product, Product, double>(
158 numericH2 = numericalDerivative32<Product, Product, Product, double>(
163 interpolate<Product>(
x,
y,
t, actH1, actH2);
164 numericH1 = numericalDerivative31<Product, Product, Product, double>(
167 numericH2 = numericalDerivative32<Product, Product, Product, double>(
static int runAllTests(TestResult &result)
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const double d[K][N]
#define EXPECT(condition)
Product between_proxy(const Product &A, const Product &B)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(std::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
Vector5 logmap_proxy(const Product &p)
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
Group product of two Lie Groups.
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Pose2_ Expmap(const Vector3_ &xi)
TEST(Lie, ProductLieGroup)
Product expmap_proxy(const Vector5 &vec)
static bool Equals(const Product &m1, const Product &m2, double tol=1e-8)
Product inverse_proxy(const Product &A)
static const NavState state2(x2, v2)
ProductLieGroup expmap(const TangentVector &v) const
Product compose_proxy(const Product &A, const Product &B)
TangentVector logmap(const ProductLieGroup &g) const
Product interpolate_proxy(const Product &x, const Product &y, double t)
static void Print(const Product &m, const string &s="")
T compose(const T &t1, const T &t2)
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const std::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
ProductLieGroup< Point2, Pose2 > Product
T between(const T &t1, const T &t2)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
static const NavState state1(x1, v1)
#define GTSAM_CONCEPT_ASSERT(concept)
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:07:48