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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:13