testImuPreintegration.cpp
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 
19 #include <gtsam/base/Testable.h>
22 #include <gtsam/slam/dataset.h>
23 #include <tests/ImuMeasurement.h>
24 
25 #include <fstream>
26 #include <iostream>
27 
28 using namespace std;
29 using namespace gtsam;
30 
31 /* ************************************************************************* */
36 TEST(TestImuPreintegration, LoadedSimulationData) {
37  Vector3 finalPos(0, 0, 0);
38 
39  vector<ImuMeasurement> imuMeasurements;
40 
41  double accNoiseSigma = 0.001249;
42  double accBiasRwSigma = 0.000106;
43  double gyrNoiseSigma = 0.000208;
44  double gyrBiasRwSigma = 0.000004;
45  double integrationCovariance = 1e-8;
46  double biasAccOmegaInt = 1e-5;
47 
48  double gravity = 9.81;
49  double rate = 400.0; // Hz
50 
51  string inFileString = findExampleDataFile("quadraped_imu_data.csv");
52  ifstream inputFile(inFileString);
53  string line;
54  while (getline(inputFile, line)) {
55  stringstream ss(line);
56  string str;
57  vector<double> results;
58  while (getline(ss, str, ',')) {
59  results.push_back(atof(str.c_str()));
60  }
62  measurement.dt = static_cast<size_t>(1e9 * (1 / rate));
63  measurement.time = results[2];
64  measurement.I_a_WI = {results[29], results[30], results[31]};
65  measurement.I_w_WI = {results[17], results[18], results[19]};
66  imuMeasurements.push_back(measurement);
67  }
68 
69  // Assume a Z-up navigation (assuming we are performing optimization in the
70  // IMU frame).
71  auto imuPreintegratedParams =
72  PreintegratedCombinedMeasurements::Params::MakeSharedU(gravity);
73  imuPreintegratedParams->accelerometerCovariance =
74  I_3x3 * pow(accNoiseSigma, 2);
75  imuPreintegratedParams->biasAccCovariance = I_3x3 * pow(accBiasRwSigma, 2);
76  imuPreintegratedParams->gyroscopeCovariance = I_3x3 * pow(gyrNoiseSigma, 2);
77  imuPreintegratedParams->biasOmegaCovariance = I_3x3 * pow(gyrBiasRwSigma, 2);
78  imuPreintegratedParams->integrationCovariance = I_3x3 * integrationCovariance;
79  imuPreintegratedParams->biasAccOmegaInt = I_6x6 * biasAccOmegaInt;
80 
81  // Initial state
82  Pose3 priorPose;
83  Vector3 priorVelocity(0, 0, 0);
84  imuBias::ConstantBias priorImuBias;
85  PreintegratedCombinedMeasurements imuPreintegrated;
86  Vector3 position(0, 0, 0);
87  Vector3 velocity(0, 0, 0);
88  NavState propState;
89 
90  NavState initialNavState(priorPose, priorVelocity);
91 
92  // Assume zero bias for simulated data
93  priorImuBias =
94  imuBias::ConstantBias(Eigen::Vector3d(0, 0, 0), Eigen::Vector3d(0, 0, 0));
95 
96  imuPreintegrated =
97  PreintegratedCombinedMeasurements(imuPreintegratedParams, priorImuBias);
98 
99  // start at 1 to skip header
100  for (size_t n = 1; n < imuMeasurements.size(); n++) {
101  // integrate
102  imuPreintegrated.integrateMeasurement(imuMeasurements[n].I_a_WI,
103  imuMeasurements[n].I_w_WI, 1 / rate);
104  // predict
105  propState = imuPreintegrated.predict(initialNavState, priorImuBias);
106  position = propState.pose().translation();
107  velocity = propState.velocity();
108  }
109 
110  Vector3 rotation = propState.pose().rotation().rpy();
111 
112  // Dont have ground truth for x and y position yet
113  // DOUBLES_EQUAL(0.1, position[0], 1e-2);
114  // DOUBLES_EQUAL(0.1, position[1], 1e-2);
115  DOUBLES_EQUAL(0.0, position[2], 1e-2);
116 
117  DOUBLES_EQUAL(0.0, rotation[0], 1e-2);
118  DOUBLES_EQUAL(0.0, rotation[1], 1e-2);
119  DOUBLES_EQUAL(0.0, rotation[2], 1e-2);
120 }
121 
122 /* ************************************************************************* */
123 int main() {
124  TestResult tr;
125  return TestRegistry::runAllTests(tr);
126 }
127 /* ************************************************************************* */
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Eigen::Vector3d I_a_WI
Raw acceleration from the IMU (m/s/s)
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:142
int n
void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
const Pose3 pose() const
Definition: NavState.h:86
double measurement(10.0)
Definition: Half.h:150
Some functions to compute numerical derivatives.
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:259
int main()
NavState predict(const NavState &state_i, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 9 > H1=boost::none, OptionalJacobian< 9, 6 > H2=boost::none) const
Predict state at time j.
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
string inputFile
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static std::stringstream ss
Definition: testBTree.cpp:33
Velocity3 velocity(const NavState &X, OptionalJacobian< 3, 9 > H)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW size_t dt
Time since the last message of this type (nanoseconds).
Definition: Measurement.h:14
traits
Definition: chartTesting.h:28
TEST(TestImuPreintegration, LoadedSimulationData)
Uses the GTSAM library to perform IMU preintegration on an acceleration input.
const Velocity3 & velocity(OptionalJacobian< 3, 9 > H=boost::none) const
Definition: NavState.cpp:64
std::map< std::string, Array< float, 1, 8, DontAlign|RowMajor > > results
Eigen::Vector3d I_w_WI
Raw angular velocity from the IMU (rad/s)
size_t time
The type of message (to enable dynamic/static casting).
Definition: Measurement.h:15
Vector3 rpy(OptionalJacobian< 3, 3 > H=boost::none) const
Definition: Rot3.cpp:192
Jet< T, N > pow(const Jet< T, N > &f, double g)
Definition: jet.h:570
Rot3 rotation(const Pose3 &pose, OptionalJacobian< 3, 6 > H)
Contains data from the IMU mesaurements.
Point3 position(const NavState &X, OptionalJacobian< 3, 9 > H)
utility functions for loading datasets
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:47:19