ImuFactorsExample.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324
  1. /* ----------------------------------------------------------------------------
  2. * GTSAM Copyright 2010, Georgia Tech Research Corporation,
  3. * Atlanta, Georgia 30332-0415
  4. * All Rights Reserved
  5. * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
  6. * See LICENSE for the license information
  7. * -------------------------------------------------------------------------- */
  8. /**
  9. * @file ImuFactorsExample
  10. * @brief Test example for using GTSAM ImuFactor and ImuCombinedFactor
  11. * navigation code.
  12. * @author Garrett (ghemann@gmail.com), Luca Carlone
  13. */
  14. /**
  15. * Example of use of the imuFactors (imuFactor and combinedImuFactor) in
  16. * conjunction with GPS
  17. * - imuFactor is used by default. You can test combinedImuFactor by
  18. * appending a `-c` flag at the end (see below for example command).
  19. * - we read IMU and GPS data from a CSV file, with the following format:
  20. * A row starting with "i" is the first initial position formatted with
  21. * N, E, D, qx, qY, qZ, qW, velN, velE, velD
  22. * A row starting with "0" is an imu measurement
  23. * (body frame - Forward, Right, Down)
  24. * linAccX, linAccY, linAccZ, angVelX, angVelY, angVelX
  25. * A row starting with "1" is a gps correction formatted with
  26. * N, E, D, qX, qY, qZ, qW
  27. * Note that for GPS correction, we're only using the position not the
  28. * rotation. The rotation is provided in the file for ground truth comparison.
  29. *
  30. * See usage: ./ImuFactorsExample --help
  31. */
  32. #include <boost/program_options.hpp>
  33. // GTSAM related includes.
  34. #include <gtsam/inference/Symbol.h>
  35. #include <gtsam/navigation/CombinedImuFactor.h>
  36. #include <gtsam/navigation/GPSFactor.h>
  37. #include <gtsam/navigation/ImuFactor.h>
  38. #include <gtsam/nonlinear/ISAM2.h>
  39. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  40. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  41. #include <gtsam/slam/BetweenFactor.h>
  42. #include <gtsam/slam/dataset.h>
  43. #include <cstring>
  44. #include <fstream>
  45. #include <iostream>
  46. using namespace gtsam;
  47. using namespace std;
  48. using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz)
  49. using symbol_shorthand::V; // Vel (xdot,ydot,zdot)
  50. using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y)
  51. namespace po = boost::program_options;
  52. po::variables_map parseOptions(int argc, char* argv[]) {
  53. po::options_description desc;
  54. desc.add_options()("help,h", "produce help message")(
  55. "data_csv_path", po::value<string>()->default_value("imuAndGPSdata.csv"),
  56. "path to the CSV file with the IMU data")(
  57. "output_filename",
  58. po::value<string>()->default_value("imuFactorExampleResults.csv"),
  59. "path to the result file to use")("use_isam", po::bool_switch(),
  60. "use ISAM as the optimizer");
  61. po::variables_map vm;
  62. po::store(po::parse_command_line(argc, argv, desc), vm);
  63. if (vm.count("help")) {
  64. cout << desc << "\n";
  65. exit(1);
  66. }
  67. return vm;
  68. }
  69. boost::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() {
  70. // We use the sensor specs to build the noise model for the IMU factor.
  71. double accel_noise_sigma = 0.0003924;
  72. double gyro_noise_sigma = 0.000205689024915;
  73. double accel_bias_rw_sigma = 0.004905;
  74. double gyro_bias_rw_sigma = 0.000001454441043;
  75. Matrix33 measured_acc_cov = I_3x3 * pow(accel_noise_sigma, 2);
  76. Matrix33 measured_omega_cov = I_3x3 * pow(gyro_noise_sigma, 2);
  77. Matrix33 integration_error_cov =
  78. I_3x3 * 1e-8; // error committed in integrating position from velocities
  79. Matrix33 bias_acc_cov = I_3x3 * pow(accel_bias_rw_sigma, 2);
  80. Matrix33 bias_omega_cov = I_3x3 * pow(gyro_bias_rw_sigma, 2);
  81. Matrix66 bias_acc_omega_int =
  82. I_6x6 * 1e-5; // error in the bias used for preintegration
  83. auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(0.0);
  84. // PreintegrationBase params:
  85. p->accelerometerCovariance =
  86. measured_acc_cov; // acc white noise in continuous
  87. p->integrationCovariance =
  88. integration_error_cov; // integration uncertainty continuous
  89. // should be using 2nd order integration
  90. // PreintegratedRotation params:
  91. p->gyroscopeCovariance =
  92. measured_omega_cov; // gyro white noise in continuous
  93. // PreintegrationCombinedMeasurements params:
  94. p->biasAccCovariance = bias_acc_cov; // acc bias in continuous
  95. p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous
  96. p->biasAccOmegaInt = bias_acc_omega_int;
  97. return p;
  98. }
  99. int main(int argc, char* argv[]) {
  100. string data_filename, output_filename;
  101. bool use_isam = false;
  102. po::variables_map var_map = parseOptions(argc, argv);
  103. data_filename = findExampleDataFile(var_map["data_csv_path"].as<string>());
  104. output_filename = var_map["output_filename"].as<string>();
  105. use_isam = var_map["use_isam"].as<bool>();
  106. ISAM2* isam2 = 0;
  107. if (use_isam) {
  108. printf("Using ISAM2\n");
  109. ISAM2Params parameters;
  110. parameters.relinearizeThreshold = 0.01;
  111. parameters.relinearizeSkip = 1;
  112. isam2 = new ISAM2(parameters);
  113. } else {
  114. printf("Using Levenberg Marquardt Optimizer\n");
  115. }
  116. // Set up output file for plotting errors
  117. FILE* fp_out = fopen(output_filename.c_str(), "w+");
  118. fprintf(fp_out,
  119. "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m),gt_qx,"
  120. "gt_qy,gt_qz,gt_qw\n");
  121. // Begin parsing the CSV file. Input the first line for initialization.
  122. // From there, we'll iterate through the file and we'll preintegrate the IMU
  123. // or add in the GPS given the input.
  124. ifstream file(data_filename.c_str());
  125. string value;
  126. // Format is (N,E,D,qX,qY,qZ,qW,velN,velE,velD)
  127. Vector10 initial_state;
  128. getline(file, value, ','); // i
  129. for (int i = 0; i < 9; i++) {
  130. getline(file, value, ',');
  131. initial_state(i) = stof(value.c_str());
  132. }
  133. getline(file, value, '\n');
  134. initial_state(9) = stof(value.c_str());
  135. cout << "initial state:\n" << initial_state.transpose() << "\n\n";
  136. // Assemble initial quaternion through GTSAM constructor
  137. // ::quaternion(w,x,y,z);
  138. Rot3 prior_rotation = Rot3::Quaternion(initial_state(6), initial_state(3),
  139. initial_state(4), initial_state(5));
  140. Point3 prior_point(initial_state.head<3>());
  141. Pose3 prior_pose(prior_rotation, prior_point);
  142. Vector3 prior_velocity(initial_state.tail<3>());
  143. imuBias::ConstantBias prior_imu_bias; // assume zero initial bias
  144. Values initial_values;
  145. int correction_count = 0;
  146. initial_values.insert(X(correction_count), prior_pose);
  147. initial_values.insert(V(correction_count), prior_velocity);
  148. initial_values.insert(B(correction_count), prior_imu_bias);
  149. // Assemble prior noise model and add it the graph.`
  150. auto pose_noise_model = noiseModel::Diagonal::Sigmas(
  151. (Vector(6) << 0.01, 0.01, 0.01, 0.5, 0.5, 0.5)
  152. .finished()); // rad,rad,rad,m, m, m
  153. auto velocity_noise_model = noiseModel::Isotropic::Sigma(3, 0.1); // m/s
  154. auto bias_noise_model = noiseModel::Isotropic::Sigma(6, 1e-3);
  155. // Add all prior factors (pose, velocity, bias) to the graph.
  156. NonlinearFactorGraph* graph = new NonlinearFactorGraph();
  157. graph->addPrior(X(correction_count), prior_pose, pose_noise_model);
  158. graph->addPrior(V(correction_count), prior_velocity, velocity_noise_model);
  159. graph->addPrior(B(correction_count), prior_imu_bias, bias_noise_model);
  160. auto p = imuParams();
  161. std::shared_ptr<PreintegrationType> preintegrated =
  162. std::make_shared<PreintegratedImuMeasurements>(p, prior_imu_bias);
  163. assert(preintegrated);
  164. // Store previous state for imu integration and latest predicted outcome.
  165. NavState prev_state(prior_pose, prior_velocity);
  166. NavState prop_state = prev_state;
  167. imuBias::ConstantBias prev_bias = prior_imu_bias;
  168. // Keep track of total error over the entire run as simple performance metric.
  169. double current_position_error = 0.0, current_orientation_error = 0.0;
  170. double output_time = 0.0;
  171. double dt = 0.005; // The real system has noise, but here, results are nearly
  172. // exactly the same, so keeping this for simplicity.
  173. // All priors have been set up, now iterate through the data file.
  174. while (file.good()) {
  175. // Parse out first value
  176. getline(file, value, ',');
  177. int type = stoi(value.c_str());
  178. if (type == 0) { // IMU measurement
  179. Vector6 imu;
  180. for (int i = 0; i < 5; ++i) {
  181. getline(file, value, ',');
  182. imu(i) = stof(value.c_str());
  183. }
  184. getline(file, value, '\n');
  185. imu(5) = stof(value.c_str());
  186. // Adding the IMU preintegration.
  187. preintegrated->integrateMeasurement(imu.head<3>(), imu.tail<3>(), dt);
  188. } else if (type == 1) { // GPS measurement
  189. Vector7 gps;
  190. for (int i = 0; i < 6; ++i) {
  191. getline(file, value, ',');
  192. gps(i) = stof(value.c_str());
  193. }
  194. getline(file, value, '\n');
  195. gps(6) = stof(value.c_str());
  196. correction_count++;
  197. // Adding IMU factor and GPS factor and optimizing.
  198. auto preint_imu =
  199. dynamic_cast<const PreintegratedImuMeasurements&>(*preintegrated);
  200. ImuFactor imu_factor(X(correction_count - 1), V(correction_count - 1),
  201. X(correction_count), V(correction_count),
  202. B(correction_count - 1), preint_imu);
  203. graph->add(imu_factor);
  204. imuBias::ConstantBias zero_bias(Vector3(0, 0, 0), Vector3(0, 0, 0));
  205. graph->add(BetweenFactor<imuBias::ConstantBias>(
  206. B(correction_count - 1), B(correction_count), zero_bias,
  207. bias_noise_model));
  208. auto correction_noise = noiseModel::Isotropic::Sigma(3, 1.0);
  209. GPSFactor gps_factor(X(correction_count),
  210. Point3(gps(0), // N,
  211. gps(1), // E,
  212. gps(2)), // D,
  213. correction_noise);
  214. graph->add(gps_factor);
  215. // Now optimize and compare results.
  216. prop_state = preintegrated->predict(prev_state, prev_bias);
  217. initial_values.insert(X(correction_count), prop_state.pose());
  218. initial_values.insert(V(correction_count), prop_state.v());
  219. initial_values.insert(B(correction_count), prev_bias);
  220. Values result;
  221. if (use_isam) {
  222. isam2->update(*graph, initial_values);
  223. isam2->update();
  224. result = isam2->calculateEstimate();
  225. // reset the graph
  226. graph->resize(0);
  227. initial_values.clear();
  228. } else {
  229. LevenbergMarquardtOptimizer optimizer(*graph, initial_values);
  230. result = optimizer.optimize();
  231. }
  232. // Overwrite the beginning of the preintegration for the next step.
  233. prev_state = NavState(result.at<Pose3>(X(correction_count)),
  234. result.at<Vector3>(V(correction_count)));
  235. prev_bias = result.at<imuBias::ConstantBias>(B(correction_count));
  236. // Reset the preintegration object.
  237. preintegrated->resetIntegrationAndSetBias(prev_bias);
  238. // Print out the position and orientation error for comparison.
  239. Vector3 gtsam_position = prev_state.pose().translation();
  240. Vector3 position_error = gtsam_position - gps.head<3>();
  241. current_position_error = position_error.norm();
  242. Quaternion gtsam_quat = prev_state.pose().rotation().toQuaternion();
  243. Quaternion gps_quat(gps(6), gps(3), gps(4), gps(5));
  244. Quaternion quat_error = gtsam_quat * gps_quat.inverse();
  245. quat_error.normalize();
  246. Vector3 euler_angle_error(quat_error.x() * 2, quat_error.y() * 2,
  247. quat_error.z() * 2);
  248. current_orientation_error = euler_angle_error.norm();
  249. // display statistics
  250. cout << "Position error:" << current_position_error << "\t "
  251. << "Angular error:" << current_orientation_error << "\n";
  252. fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n",
  253. output_time, gtsam_position(0), gtsam_position(1),
  254. gtsam_position(2), gtsam_quat.x(), gtsam_quat.y(), gtsam_quat.z(),
  255. gtsam_quat.w(), gps(0), gps(1), gps(2), gps_quat.x(),
  256. gps_quat.y(), gps_quat.z(), gps_quat.w());
  257. output_time += 1.0;
  258. } else {
  259. cerr << "ERROR parsing file\n";
  260. return 1;
  261. }
  262. }
  263. fclose(fp_out);
  264. cout << "Complete, results written to " << output_filename << "\n\n";
  265. return 0;
  266. }