CombinedImuFactorsExample.cpp 11 KB

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