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