22 #include <boost/bind.hpp> 26 using namespace gtsam;
76 const double R = v /
w;
96 const double R = v /
w;
99 #ifdef GTSAM_USE_QUATERNIONS 123 const double R = v /
w;
138 const double a = 0.2;
139 const Vector3 A(0, a, 0),
W(0.1, 0.2, 0.3);
150 boost::bind(&Scenario::velocity_n, scenario, _1),
T);
Simple class to test navigation scenarios.
const Vector3 V0(0, 0, 0)
static const Pose3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3))
static int runAllTests(TestResult &result)
Vector3 omega_b(double t) const override
angular velocity in body frame
Vector3 velocity_n(double t) const override
velocity at time t, in nav frame
Vector3 acceleration_b(double t) const
Rot2 R(Rot2::fromAngle(0.1))
Some functions to compute numerical derivatives.
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Vector3 velocity_b(double t) const
Vector3 omega_b(double t) const override
angular velocity in body frame
Vector3 xyz(OptionalJacobian< 3, 3 > H=boost::none) const
Pose3 pose(double t) const override
pose at time t
Vector3 acceleration_n(double t) const override
acceleration in nav frame
Class expmap(const TangentVector &v) const
#define EXPECT(condition)
Eigen::Triplet< double > T
Array< double, 1, 3 > e(1./3., 0.5, 2.)
ConstantTwistScenario scenario(Z_3x1, Vector3(v, 0, 0))
Pose3 pose(double t) const override
pose at time t
Simple trajectory simulator.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
static const double kDegree
Accelerating from an arbitrary initial state, with optional rotation.
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation