imuFactorTesting.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
18 #pragma once
19 
21 #include <gtsam/inference/Symbol.h>
22 
23 using namespace std;
24 using namespace gtsam;
25 
26 // Convenience for named keys
30 
31 namespace {
32 static const Vector3 kZero = Z_3x1;
34 static const Bias kZeroBiasHat, kZeroBias;
35 
36 static const Vector3 kZeroOmegaCoriolis(0, 0, 0);
37 static const Vector3 kNonZeroOmegaCoriolis(0, 0.1, 0.1);
38 
39 static const double kGravity = 10;
40 static const Vector3 kGravityAlongNavZDown(0, 0, kGravity);
41 
42 // Realistic MEMS white noise characteristics. Angular and velocity random walk
43 // expressed in degrees respectively m/s per sqrt(hr).
44 auto radians = [](double t) { return t * M_PI / 180; };
45 static const double kGyroSigma = radians(0.5) / 60; // 0.5 degree ARW
46 static const double kAccelSigma = 0.1 / 60; // 10 cm VRW
47 }
48 
49 namespace testing {
50 
52  ImuMeasurement(const Vector3& acc, const Vector3& gyro, double dt)
53  : acc(acc), gyro(gyro), dt(dt) {}
54  const Vector3 acc, gyro;
55  const double dt;
56 };
57 
58 template <typename PIM>
59 void integrateMeasurements(const vector<ImuMeasurement>& measurements,
60  PIM* pim) {
61  for (const auto& m : measurements)
62  pim->integrateMeasurement(m.acc, m.gyro, m.dt);
63 }
64 
65 struct SomeMeasurements : vector<ImuMeasurement> {
67  reserve(102);
68  const double dt = 0.01, pi100 = M_PI / 100;
69  emplace_back(Vector3(0.1, 0, 0), Vector3(pi100, 0, 0), dt);
70  emplace_back(Vector3(0.1, 0, 0), Vector3(pi100, 0, 0), dt);
71  for (int i = 1; i < 100; i++) {
72  emplace_back(Vector3(0.05, 0.09, 0.01),
73  Vector3(pi100, pi100 * 3, 2 * pi100), dt);
74  }
75  }
76 };
77 
78 } // namespace testing
testing
Definition: benchmark.h:20
kGyroSigma
static const double kGyroSigma
Definition: testScenarioRunner.cpp:32
B
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
Definition: bench_gemm.cpp:49
kAccelSigma
static const double kAccelSigma
Definition: testScenarioRunner.cpp:33
gtsam::Z_3x1
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
dt
const double dt
Definition: testVelocityConstraint.cpp:15
X
#define X
Definition: icosphere.cpp:20
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
testing::integrateMeasurements
void integrateMeasurements(const vector< ImuMeasurement > &measurements, PIM *pim)
Definition: imuFactorTesting.h:59
kGravity
const double kGravity
Definition: ImuFactorsExample2.cpp:36
testing::ImuMeasurement
Definition: imuFactorTesting.h:51
Symbol.h
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
testing::SomeMeasurements::SomeMeasurements
SomeMeasurements()
Definition: imuFactorTesting.h:66
testing::ImuMeasurement::ImuMeasurement
ImuMeasurement(const Vector3 &acc, const Vector3 &gyro, double dt)
Definition: imuFactorTesting.h:52
ImuBias.h
gtsam::imuBias::ConstantBias
Definition: ImuBias.h:32
gtsam
traits
Definition: chartTesting.h:28
kZeroOmegaCoriolis
Vector3 kZeroOmegaCoriolis(0, 0, 0)
Bias
imuBias::ConstantBias Bias
Definition: testImuBias.cpp:27
std
Definition: BFloat16.h:88
kZero
static const Vector kZero
Definition: testLPSolver.cpp:37
V
MatrixXcd V
Definition: EigenSolver_EigenSolver_MatrixType.cpp:15
testing::ImuMeasurement::gyro
const Vector3 gyro
Definition: imuFactorTesting.h:54
M_PI
#define M_PI
Definition: mconf.h:117
align_3::t
Point2 t(10, 10)
testing::ImuMeasurement::dt
const double dt
Definition: imuFactorTesting.h:55
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
testing::SomeMeasurements
Definition: imuFactorTesting.h:65


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:01:01