12 using namespace gtsam;
16 const double h = 0.01;
22 Vector6
V1_w((
Vector(6) << 0.0, 0.0,
M_PI/3, 0.0, 0.0, 30.0).finished());
39 distT*
sin(gamma_p*
cos(gamma_r)), 0.0,
41 sin(gamma_p)*
cos(gamma_r), 0.0,
43 cos(gamma_p)*
sin(gamma_r), 0.0
61 boost::none, boost::none, boost::none)),
g2,
g1, V1_g1, 1
e-5);
66 boost::none, boost::none, boost::none)),
g2,
g1, V1_g1, 1
e-5);
71 boost::none, boost::none, boost::none)),
g2,
g1, V1_g1, 1
e-5);
75 #ifdef GTSAM_USE_QUATERNIONS // TODO: why is the quaternion version much less accurate?? 86 Vector dV = Inertia.inverse()*(Fb - W*Inertia*Vb);
92 Vector fGravity_g1 = Z_6x1;
94 Vector Fb = Fu+fGravity_g1;
101 Vector6 expectedv2(V2_g2);
112 boost::function<
Vector(
const Vector6&,
const Vector6&,
const Pose3&)>(
115 expectedv2, V1_g1,
g2, 1
e-5
119 boost::function<
Vector(
const Vector6&,
const Vector6&,
const Pose3&)>(
122 expectedv2, V1_g1,
g2, 1
e-5
126 boost::function<
Vector(
const Vector6&,
const Vector6&,
const Pose3&)>(
129 expectedv2, V1_g1,
g2, 1
e-5
Vector6 V1_w((Vector(6)<< 0.0, 0.0, M_PI/3, 0.0, 0.0, 30.0).finished())
static Matrix6 adjointMap(const Vector6 &xi)
FIXME Not tested - marked as incorrect.
static int runAllTests(TestResult &result)
Vector6 Adjoint(const Vector6 &xi_b) const
FIXME Not tested - marked as incorrect.
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
rotate point from world to rotated frame
internal::FixedSizeMatrix< Y, X3 >::type numericalDerivative33(boost::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Some functions to compute numerical derivatives.
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative31(boost::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
EIGEN_DEVICE_FUNC const CosReturnType cos() const
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative32(boost::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Pose3 inverse() const
inverse transformation with derivatives
const mpreal gamma(const mpreal &x, mp_rnd_t r=mpreal::get_default_rnd())
Vector evaluateError(const Vector6 &xik, const Vector6 &xik_1, const Pose3 &gk, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const override
Class expmap(const TangentVector &v) const
#define EXPECT(condition)
Vector newtonEuler(const Vector &Vb, const Vector &Fb, const Matrix &Inertia)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Vector computeFu(const Vector &gamma, const Vector &control)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0))
Class between(const Class &g) const
TEST(LPInitSolver, InfiniteLoopSingleVar)
EIGEN_DEVICE_FUNC const SinReturnType sin() const
virtual Vector evaluateError(const X1 &, const X2 &, const X3 &, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const =0
Pose3 g2(g1.expmap(h *V1_g1))
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation