CombinedImuFactorsExample.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 
36 #include <boost/program_options.hpp>
37 
38 // GTSAM related includes.
39 #include <gtsam/inference/Symbol.h>
46 #include <gtsam/slam/dataset.h>
47 
48 #include <cstring>
49 #include <fstream>
50 #include <iostream>
51 #include <cassert>
52 
53 using namespace gtsam;
54 using namespace std;
55 
56 using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz)
57 using symbol_shorthand::V; // Vel (xdot,ydot,zdot)
58 using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y)
59 
60 namespace po = boost::program_options;
61 
62 po::variables_map parseOptions(int argc, char* argv[]) {
63  po::options_description desc;
64  desc.add_options()("help,h", "produce help message") // help message
65  ("data_csv_path", po::value<string>()->default_value("imuAndGPSdata.csv"),
66  "path to the CSV file with the IMU data") // path to the data file
67  ("output_filename",
68  po::value<string>()->default_value("imuFactorExampleResults.csv"),
69  "path to the result file to use") // filename to save results to
70  ("use_isam", po::bool_switch(),
71  "use ISAM as the optimizer"); // flag for ISAM optimizer
72 
73  po::variables_map vm;
74  po::store(po::parse_command_line(argc, argv, desc), vm);
75 
76  if (vm.count("help")) {
77  cout << desc << "\n";
78  exit(1);
79  }
80 
81  return vm;
82 }
83 
84 Vector10 readInitialState(ifstream& file) {
85  string value;
86  // Format is (N,E,D,qX,qY,qZ,qW,velN,velE,velD)
87  Vector10 initial_state;
88  getline(file, value, ','); // i
89  for (int i = 0; i < 9; i++) {
90  getline(file, value, ',');
91  initial_state(i) = stof(value.c_str());
92  }
93  getline(file, value, '\n');
94  initial_state(9) = stof(value.c_str());
95 
96  return initial_state;
97 }
98 
99 std::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() {
100  // We use the sensor specs to build the noise model for the IMU factor.
101  double accel_noise_sigma = 0.0003924;
102  double gyro_noise_sigma = 0.000205689024915;
103  double accel_bias_rw_sigma = 0.004905;
104  double gyro_bias_rw_sigma = 0.000001454441043;
105  Matrix33 measured_acc_cov = I_3x3 * pow(accel_noise_sigma, 2);
106  Matrix33 measured_omega_cov = I_3x3 * pow(gyro_noise_sigma, 2);
107  Matrix33 integration_error_cov =
108  I_3x3 * 1e-8; // error committed in integrating position from velocities
109  Matrix33 bias_acc_cov = I_3x3 * pow(accel_bias_rw_sigma, 2);
110  Matrix33 bias_omega_cov = I_3x3 * pow(gyro_bias_rw_sigma, 2);
111  Matrix66 bias_acc_omega_init =
112  I_6x6 * 1e-5; // error in the bias used for preintegration
113 
115  // PreintegrationBase params:
116  p->accelerometerCovariance =
117  measured_acc_cov; // acc white noise in continuous
118  p->integrationCovariance =
119  integration_error_cov; // integration uncertainty continuous
120  // should be using 2nd order integration
121  // PreintegratedRotation params:
122  p->gyroscopeCovariance =
123  measured_omega_cov; // gyro white noise in continuous
124  // PreintegrationCombinedMeasurements params:
125  p->biasAccCovariance = bias_acc_cov; // acc bias in continuous
126  p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous
127  p->biasAccOmegaInt = bias_acc_omega_init;
128 
129  return p;
130 }
131 
132 int main(int argc, char* argv[]) {
133  string data_filename, output_filename;
134  po::variables_map var_map = parseOptions(argc, argv);
135 
136  data_filename = findExampleDataFile(var_map["data_csv_path"].as<string>());
137  output_filename = var_map["output_filename"].as<string>();
138 
139  // Set up output file for plotting errors
140  FILE* fp_out = fopen(output_filename.c_str(), "w+");
141  fprintf(fp_out,
142  "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m),gt_qx,"
143  "gt_qy,gt_qz,gt_qw\n");
144 
145  // Begin parsing the CSV file. Input the first line for initialization.
146  // From there, we'll iterate through the file and we'll preintegrate the IMU
147  // or add in the GPS given the input.
148  ifstream file(data_filename.c_str());
149 
150  Vector10 initial_state = readInitialState(file);
151  cout << "initial state:\n" << initial_state.transpose() << "\n\n";
152 
153  // Assemble initial quaternion through GTSAM constructor
154  // ::Quaternion(w,x,y,z);
155  Rot3 prior_rotation = Rot3::Quaternion(initial_state(6), initial_state(3),
156  initial_state(4), initial_state(5));
157  Point3 prior_point(initial_state.head<3>());
158  Pose3 prior_pose(prior_rotation, prior_point);
159  Vector3 prior_velocity(initial_state.tail<3>());
160 
161  imuBias::ConstantBias prior_imu_bias; // assume zero initial bias
162 
163  int index = 0;
164 
165  Values initial_values;
166 
167  // insert pose at initialization
168  initial_values.insert(X(index), prior_pose);
169  initial_values.insert(V(index), prior_velocity);
170  initial_values.insert(B(index), prior_imu_bias);
171 
172  // Assemble prior noise model and add it the graph.`
173  auto pose_noise_model = noiseModel::Diagonal::Sigmas(
174  (Vector(6) << 0.01, 0.01, 0.01, 0.5, 0.5, 0.5)
175  .finished()); // rad,rad,rad,m, m, m
176  auto velocity_noise_model = noiseModel::Isotropic::Sigma(3, 0.1); // m/s
177  auto bias_noise_model = noiseModel::Isotropic::Sigma(6, 1e-3);
178 
179  // Add all prior factors (pose, velocity, bias) to the graph.
181  graph.addPrior<Pose3>(X(index), prior_pose, pose_noise_model);
182  graph.addPrior<Vector3>(V(index), prior_velocity, velocity_noise_model);
183  graph.addPrior<imuBias::ConstantBias>(B(index), prior_imu_bias,
184  bias_noise_model);
185 
186  auto p = imuParams();
187 
188  std::shared_ptr<PreintegrationType> preintegrated =
189  std::make_shared<PreintegratedCombinedMeasurements>(p, prior_imu_bias);
190 
191  assert(preintegrated);
192 
193  // Store previous state for imu integration and latest predicted outcome.
194  NavState prev_state(prior_pose, prior_velocity);
195  NavState prop_state = prev_state;
196  imuBias::ConstantBias prev_bias = prior_imu_bias;
197 
198  // Keep track of total error over the entire run as simple performance metric.
199  double current_position_error = 0.0, current_orientation_error = 0.0;
200 
201  double output_time = 0.0;
202  double dt = 0.005; // The real system has noise, but here, results are nearly
203  // exactly the same, so keeping this for simplicity.
204 
205  // All priors have been set up, now iterate through the data file.
206  while (file.good()) {
207  // Parse out first value
208  string value;
209  getline(file, value, ',');
210  int type = stoi(value.c_str());
211 
212  if (type == 0) { // IMU measurement
213  Vector6 imu;
214  for (int i = 0; i < 5; ++i) {
215  getline(file, value, ',');
216  imu(i) = stof(value.c_str());
217  }
218  getline(file, value, '\n');
219  imu(5) = stof(value.c_str());
220 
221  // Adding the IMU preintegration.
222  preintegrated->integrateMeasurement(imu.head<3>(), imu.tail<3>(), dt);
223 
224  } else if (type == 1) { // GPS measurement
225  Vector7 gps;
226  for (int i = 0; i < 6; ++i) {
227  getline(file, value, ',');
228  gps(i) = stof(value.c_str());
229  }
230  getline(file, value, '\n');
231  gps(6) = stof(value.c_str());
232 
233  index++;
234 
235  // Adding IMU factor and GPS factor and optimizing.
236  auto preint_imu_combined =
237  dynamic_cast<const PreintegratedCombinedMeasurements&>(
238  *preintegrated);
239  CombinedImuFactor imu_factor(X(index - 1), V(index - 1), X(index),
240  V(index), B(index - 1), B(index),
241  preint_imu_combined);
242  graph.add(imu_factor);
243 
244  auto correction_noise = noiseModel::Isotropic::Sigma(3, 1.0);
245  GPSFactor gps_factor(X(index),
246  Point3(gps(0), // N,
247  gps(1), // E,
248  gps(2)), // D,
249  correction_noise);
250  graph.add(gps_factor);
251 
252  // Now optimize and compare results.
253  prop_state = preintegrated->predict(prev_state, prev_bias);
254  initial_values.insert(X(index), prop_state.pose());
255  initial_values.insert(V(index), prop_state.v());
256  initial_values.insert(B(index), prev_bias);
257 
259  params.setVerbosityLM("SUMMARY");
260  LevenbergMarquardtOptimizer optimizer(graph, initial_values, params);
261  Values result = optimizer.optimize();
262 
263  // Overwrite the beginning of the preintegration for the next step.
264  prev_state =
265  NavState(result.at<Pose3>(X(index)), result.at<Vector3>(V(index)));
266  prev_bias = result.at<imuBias::ConstantBias>(B(index));
267 
268  // Reset the preintegration object.
269  preintegrated->resetIntegrationAndSetBias(prev_bias);
270 
271  // Print out the position and orientation error for comparison.
272  Vector3 result_position = prev_state.pose().translation();
273  Vector3 position_error = result_position - gps.head<3>();
274  current_position_error = position_error.norm();
275 
276  Quaternion result_quat = prev_state.pose().rotation().toQuaternion();
277  Quaternion gps_quat(gps(6), gps(3), gps(4), gps(5));
278  Quaternion quat_error = result_quat * gps_quat.inverse();
279  quat_error.normalize();
280  Vector3 euler_angle_error(quat_error.x() * 2, quat_error.y() * 2,
281  quat_error.z() * 2);
282  current_orientation_error = euler_angle_error.norm();
283 
284  // display statistics
285  cout << "Position error:" << current_position_error << "\t "
286  << "Angular error:" << current_orientation_error << "\n"
287  << endl;
288 
289  fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n",
290  output_time, result_position(0), result_position(1),
291  result_position(2), result_quat.x(), result_quat.y(),
292  result_quat.z(), result_quat.w(), gps(0), gps(1), gps(2),
293  gps_quat.x(), gps_quat.y(), gps_quat.z(), gps_quat.w());
294 
295  output_time += 1.0;
296 
297  } else {
298  cerr << "ERROR parsing file\n";
299  return 1;
300  }
301  }
302  fclose(fp_out);
303  cout << "Complete, results written to " << output_filename << "\n\n";
304 
305  return 0;
306 }
gtsam::NonlinearOptimizer::optimize
virtual const Values & optimize()
Definition: NonlinearOptimizer.h:98
gtsam.examples.DogLegOptimizerExample.type
type
Definition: DogLegOptimizerExample.py:111
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::Rot3::Quaternion
static Rot3 Quaternion(double w, double x, double y, double z)
Definition: Rot3.h:208
LevenbergMarquardtOptimizer.h
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
dt
const double dt
Definition: testVelocityConstraint.cpp:15
E1::B
@ B
gtsam::NavState
Definition: NavState.h:38
gtsam::noiseModel::Diagonal::Sigmas
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:292
X
#define X
Definition: icosphere.cpp:20
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
gtsam::NavState::v
const Vector3 & v() const
Return velocity as Vector3. Computation-free.
Definition: NavState.h:111
vanilla::params
static const SmartProjectionParams params
Definition: smartFactorScenarios.h:69
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
result
Values result
Definition: OdometryOptimize.cpp:8
make_changelog.desc
desc
Definition: make_changelog.py:71
gtsam::symbol_shorthand::X
Key X(std::uint64_t j)
Definition: inference/Symbol.h:171
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
dataset.h
utility functions for loading datasets
gtsam::PreintegrationCombinedParams::MakeSharedD
static std::shared_ptr< PreintegrationCombinedParams > MakeSharedD(double g=9.81)
Definition: PreintegrationCombinedParams.h:60
BetweenFactor.h
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Pose3
Definition: Pose3.h:37
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::Rot3::toQuaternion
gtsam::Quaternion toQuaternion() const
Definition: Rot3M.cpp:232
gtsam::Pose3::translation
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
Definition: Pose3.cpp:324
gtsam::NonlinearFactorGraph::addPrior
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
Definition: NonlinearFactorGraph.h:199
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
Symbol.h
main
int main(int argc, char *argv[])
Definition: CombinedImuFactorsExample.cpp:132
gtsam::symbol_shorthand::B
Key B(std::uint64_t j)
Definition: inference/Symbol.h:149
ceres::pow
Jet< T, N > pow(const Jet< T, N > &f, double g)
Definition: jet.h:570
gtsam::CombinedImuFactor
Definition: CombinedImuFactor.h:205
gtsam::imuBias::ConstantBias
Definition: ImuBias.h:32
gtsam::Pose3::rotation
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Definition: Pose3.cpp:330
Eigen::Quaternion
The quaternion class used to represent 3D orientations and rotations.
Definition: ForwardDeclarations.h:293
gtsam
traits
Definition: SFMdata.h:40
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::Values
Definition: Values.h:65
std
Definition: BFloat16.h:88
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:156
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
V
MatrixXcd V
Definition: EigenSolver_EigenSolver_MatrixType.cpp:15
gtsam::noiseModel::Isotropic::Sigma
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:625
CombinedImuFactor.h
gtsam::findExampleDataFile
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
Definition: dataset.cpp:70
output_filename
const string output_filename
Definition: IMUKittiExampleGPS.cpp:70
gtsam::FactorGraph::add
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
Definition: FactorGraph.h:171
gtsam::PreintegratedCombinedMeasurements
Definition: CombinedImuFactor.h:66
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::NavState::pose
const Pose3 pose() const
Definition: NavState.h:90
GPSFactor.h
Header file for GPS factor.
gtsam::symbol_shorthand::V
Key V(std::uint64_t j)
Definition: inference/Symbol.h:169
readInitialState
Vector10 readInitialState(ifstream &file)
Definition: CombinedImuFactorsExample.cpp:84
matlab_wrap.file
file
Definition: matlab_wrap.py:57
test_callbacks.value
value
Definition: test_callbacks.py:160
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::GPSFactor
Definition: GPSFactor.h:35
ImuFactor.h
imuParams
std::shared_ptr< PreintegratedCombinedMeasurements::Params > imuParams()
Definition: CombinedImuFactorsExample.cpp:99
parseOptions
po::variables_map parseOptions(int argc, char *argv[])
Definition: CombinedImuFactorsExample.cpp:62


gtsam
Author(s):
autogenerated on Wed Jan 1 2025 04:01:15