24 using namespace gtsam;
29 static const Vector g = Vector::Unit(3,2)*(-9.81);
32 TEST(testIMUSystem, instantiations) {
41 Vector accel = Vector::Ones(3), gyro = Vector::Ones(3);
55 TEST( testIMUSystem, optimize_chain ) {
57 const double dt = 1.0;
61 pose4(
Point3(3.0, 3.0, 0.0), Rot3::Ypr(0.3, 0.0, 0.0),
Velocity3(2.0, 2.0, 0.0));
66 Vector6 imu23 =
pose2.imuPrediction(
pose3, dt);
67 Vector6 imu34 =
pose3.imuPrediction(pose4, dt);
81 true_values.
insert(x1, pose1);
82 true_values.insert(x2,
pose2);
83 true_values.insert(x3,
pose3);
84 true_values.insert(x4, pose4);
101 TEST( testIMUSystem, optimize_chain_fullfactor ) {
103 const double dt = 1.0;
107 pose4(
Point3(3.0, 0.0, 0.0), Rot3::Ypr(0.0, 0.0, 0.0),
Velocity3(1.0, 0.0, 0.0));
112 Vector6 imu23 =
pose2.imuPrediction(
pose3, dt);
113 Vector6 imu34 =
pose3.imuPrediction(pose4, dt);
124 true_values.insert(x1, pose1);
125 true_values.insert(x2,
pose2);
126 true_values.insert(x3,
pose3);
127 true_values.insert(x4, pose4);
139 cout <<
"Initial Error: " << graph.
error(values) << endl;
146 TEST( testIMUSystem, linear_trajectory) {
149 const double dt = 1.0;
152 Vector accel = Vector::Unit(3,0)*0.5;
153 Vector gyro = Vector::Unit(3,0)*0.1;
156 Values true_traj, init_traj;
160 true_traj.
insert(x0, start);
161 init_traj.
insert(x0, start);
165 for (
size_t i=1;
i<nrPoses; ++
i) {
166 Key xA =
i-1, xB =
i;
169 true_traj.
insert(xB, cur_pose);
virtual const Values & optimize()
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
static int runAllTests(TestResult &result)
Factor Graph consisting of non-linear factors.
noiseModel::Diagonal::shared_ptr model
Priors to be used with dynamic systems (Specifically PoseRTV)
Vector3 Velocity3
Velocity is currently typedef'd to Vector3.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Factor to express an IMU measurement between dynamic poses.
NonlinearFactorGraph graph
Constraint enforcing the relationship between pose and velocity.
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
noiseModel::Isotropic::shared_ptr model1
A simple prior factor that allows for setting a prior only on a part of linear parameters.
TEST(testIMUSystem, instantiations)
#define EXPECT(condition)
static Pose3 pose3(rt3, pt3)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
const SharedNoiseModel model3
double error(const Values &values) const
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
noiseModel::Diagonal::shared_ptr SharedDiagonal
Factor to express an IMU measurement between dynamic poses.
Double_ range(const Point2_ &p, const Point2_ &q)
PoseRTV generalDynamics(const Vector &accel, const Vector &gyro, double dt) const
General Dynamics update - supply control inputs in body frame.
void insert(Key j, const Value &val)
Vector6 imuPrediction(const PoseRTV &x2, double dt) const
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel