IMUKittiExampleGPS.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384
  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 IMUKittiExampleGPS
  10. * @brief Example of application of ISAM2 for GPS-aided navigation on the KITTI
  11. * VISION BENCHMARK SUITE
  12. * @author Ported by Thomas Jespersen (thomasj@tkjelectronics.dk), TKJ
  13. * Electronics
  14. */
  15. // GTSAM related includes.
  16. #include <gtsam/inference/Symbol.h>
  17. #include <gtsam/navigation/CombinedImuFactor.h>
  18. #include <gtsam/navigation/GPSFactor.h>
  19. #include <gtsam/navigation/ImuFactor.h>
  20. #include <gtsam/nonlinear/ISAM2.h>
  21. #include <gtsam/nonlinear/ISAM2Params.h>
  22. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  23. #include <gtsam/slam/BetweenFactor.h>
  24. #include <gtsam/slam/PriorFactor.h>
  25. #include <gtsam/slam/dataset.h>
  26. #include <cstring>
  27. #include <fstream>
  28. #include <iostream>
  29. using namespace std;
  30. using namespace gtsam;
  31. using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz)
  32. using symbol_shorthand::V; // Vel (xdot,ydot,zdot)
  33. using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y)
  34. struct KittiCalibration {
  35. double body_ptx;
  36. double body_pty;
  37. double body_ptz;
  38. double body_prx;
  39. double body_pry;
  40. double body_prz;
  41. double accelerometer_sigma;
  42. double gyroscope_sigma;
  43. double integration_sigma;
  44. double accelerometer_bias_sigma;
  45. double gyroscope_bias_sigma;
  46. double average_delta_t;
  47. };
  48. struct ImuMeasurement {
  49. double time;
  50. double dt;
  51. Vector3 accelerometer;
  52. Vector3 gyroscope; // omega
  53. };
  54. struct GpsMeasurement {
  55. double time;
  56. Vector3 position; // x,y,z
  57. };
  58. const string output_filename = "IMUKittiExampleGPSResults.csv";
  59. void loadKittiData(KittiCalibration& kitti_calibration,
  60. vector<ImuMeasurement>& imu_measurements,
  61. vector<GpsMeasurement>& gps_measurements) {
  62. string line;
  63. // Read IMU metadata and compute relative sensor pose transforms
  64. // BodyPtx BodyPty BodyPtz BodyPrx BodyPry BodyPrz AccelerometerSigma
  65. // GyroscopeSigma IntegrationSigma AccelerometerBiasSigma GyroscopeBiasSigma
  66. // AverageDeltaT
  67. string imu_metadata_file =
  68. findExampleDataFile("KittiEquivBiasedImu_metadata.txt");
  69. ifstream imu_metadata(imu_metadata_file.c_str());
  70. printf("-- Reading sensor metadata\n");
  71. getline(imu_metadata, line, '\n'); // ignore the first line
  72. // Load Kitti calibration
  73. getline(imu_metadata, line, '\n');
  74. sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf",
  75. &kitti_calibration.body_ptx, &kitti_calibration.body_pty,
  76. &kitti_calibration.body_ptz, &kitti_calibration.body_prx,
  77. &kitti_calibration.body_pry, &kitti_calibration.body_prz,
  78. &kitti_calibration.accelerometer_sigma,
  79. &kitti_calibration.gyroscope_sigma,
  80. &kitti_calibration.integration_sigma,
  81. &kitti_calibration.accelerometer_bias_sigma,
  82. &kitti_calibration.gyroscope_bias_sigma,
  83. &kitti_calibration.average_delta_t);
  84. printf("IMU metadata: %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf\n",
  85. kitti_calibration.body_ptx, kitti_calibration.body_pty,
  86. kitti_calibration.body_ptz, kitti_calibration.body_prx,
  87. kitti_calibration.body_pry, kitti_calibration.body_prz,
  88. kitti_calibration.accelerometer_sigma,
  89. kitti_calibration.gyroscope_sigma, kitti_calibration.integration_sigma,
  90. kitti_calibration.accelerometer_bias_sigma,
  91. kitti_calibration.gyroscope_bias_sigma,
  92. kitti_calibration.average_delta_t);
  93. // Read IMU data
  94. // Time dt accelX accelY accelZ omegaX omegaY omegaZ
  95. string imu_data_file = findExampleDataFile("KittiEquivBiasedImu.txt");
  96. printf("-- Reading IMU measurements from file\n");
  97. {
  98. ifstream imu_data(imu_data_file.c_str());
  99. getline(imu_data, line, '\n'); // ignore the first line
  100. double time = 0, dt = 0, acc_x = 0, acc_y = 0, acc_z = 0, gyro_x = 0,
  101. gyro_y = 0, gyro_z = 0;
  102. while (!imu_data.eof()) {
  103. getline(imu_data, line, '\n');
  104. sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf", &time, &dt,
  105. &acc_x, &acc_y, &acc_z, &gyro_x, &gyro_y, &gyro_z);
  106. ImuMeasurement measurement;
  107. measurement.time = time;
  108. measurement.dt = dt;
  109. measurement.accelerometer = Vector3(acc_x, acc_y, acc_z);
  110. measurement.gyroscope = Vector3(gyro_x, gyro_y, gyro_z);
  111. imu_measurements.push_back(measurement);
  112. }
  113. }
  114. // Read GPS data
  115. // Time,X,Y,Z
  116. string gps_data_file = findExampleDataFile("KittiGps_converted.txt");
  117. printf("-- Reading GPS measurements from file\n");
  118. {
  119. ifstream gps_data(gps_data_file.c_str());
  120. getline(gps_data, line, '\n'); // ignore the first line
  121. double time = 0, gps_x = 0, gps_y = 0, gps_z = 0;
  122. while (!gps_data.eof()) {
  123. getline(gps_data, line, '\n');
  124. sscanf(line.c_str(), "%lf,%lf,%lf,%lf", &time, &gps_x, &gps_y, &gps_z);
  125. GpsMeasurement measurement;
  126. measurement.time = time;
  127. measurement.position = Vector3(gps_x, gps_y, gps_z);
  128. gps_measurements.push_back(measurement);
  129. }
  130. }
  131. }
  132. int main(int argc, char* argv[]) {
  133. KittiCalibration kitti_calibration;
  134. vector<ImuMeasurement> imu_measurements;
  135. vector<GpsMeasurement> gps_measurements;
  136. loadKittiData(kitti_calibration, imu_measurements, gps_measurements);
  137. Vector6 BodyP =
  138. (Vector6() << kitti_calibration.body_ptx, kitti_calibration.body_pty,
  139. kitti_calibration.body_ptz, kitti_calibration.body_prx,
  140. kitti_calibration.body_pry, kitti_calibration.body_prz)
  141. .finished();
  142. auto body_T_imu = Pose3::Expmap(BodyP);
  143. if (!body_T_imu.equals(Pose3(), 1e-5)) {
  144. printf(
  145. "Currently only support IMUinBody is identity, i.e. IMU and body frame "
  146. "are the same");
  147. exit(-1);
  148. }
  149. // Configure different variables
  150. // double t_offset = gps_measurements[0].time;
  151. size_t first_gps_pose = 1;
  152. size_t gps_skip = 10; // Skip this many GPS measurements each time
  153. double g = 9.8;
  154. auto w_coriolis = Vector3::Zero(); // zero vector
  155. // Configure noise models
  156. auto noise_model_gps = noiseModel::Diagonal::Precisions(
  157. (Vector6() << Vector3::Constant(0), Vector3::Constant(1.0 / 0.07))
  158. .finished());
  159. // Set initial conditions for the estimated trajectory
  160. // initial pose is the reference frame (navigation frame)
  161. auto current_pose_global =
  162. Pose3(Rot3(), gps_measurements[first_gps_pose].position);
  163. // the vehicle is stationary at the beginning at position 0,0,0
  164. Vector3 current_velocity_global = Vector3::Zero();
  165. auto current_bias = imuBias::ConstantBias(); // init with zero bias
  166. auto sigma_init_x = noiseModel::Diagonal::Precisions(
  167. (Vector6() << Vector3::Constant(0), Vector3::Constant(1.0)).finished());
  168. auto sigma_init_v = noiseModel::Diagonal::Sigmas(Vector3::Constant(1000.0));
  169. auto sigma_init_b = noiseModel::Diagonal::Sigmas(
  170. (Vector6() << Vector3::Constant(0.100), Vector3::Constant(5.00e-05))
  171. .finished());
  172. // Set IMU preintegration parameters
  173. Matrix33 measured_acc_cov =
  174. I_3x3 * pow(kitti_calibration.accelerometer_sigma, 2);
  175. Matrix33 measured_omega_cov =
  176. I_3x3 * pow(kitti_calibration.gyroscope_sigma, 2);
  177. // error committed in integrating position from velocities
  178. Matrix33 integration_error_cov =
  179. I_3x3 * pow(kitti_calibration.integration_sigma, 2);
  180. auto imu_params = PreintegratedImuMeasurements::Params::MakeSharedU(g);
  181. imu_params->accelerometerCovariance =
  182. measured_acc_cov; // acc white noise in continuous
  183. imu_params->integrationCovariance =
  184. integration_error_cov; // integration uncertainty continuous
  185. imu_params->gyroscopeCovariance =
  186. measured_omega_cov; // gyro white noise in continuous
  187. imu_params->omegaCoriolis = w_coriolis;
  188. std::shared_ptr<PreintegratedImuMeasurements> current_summarized_measurement =
  189. nullptr;
  190. // Set ISAM2 parameters and create ISAM2 solver object
  191. ISAM2Params isam_params;
  192. isam_params.factorization = ISAM2Params::CHOLESKY;
  193. isam_params.relinearizeSkip = 10;
  194. ISAM2 isam(isam_params);
  195. // Create the factor graph and values object that will store new factors and
  196. // values to add to the incremental graph
  197. NonlinearFactorGraph new_factors;
  198. Values new_values; // values storing the initial estimates of new nodes in
  199. // the factor graph
  200. /// Main loop:
  201. /// (1) we read the measurements
  202. /// (2) we create the corresponding factors in the graph
  203. /// (3) we solve the graph to obtain and optimal estimate of robot trajectory
  204. printf(
  205. "-- Starting main loop: inference is performed at each time step, but we "
  206. "plot trajectory every 10 steps\n");
  207. size_t j = 0;
  208. size_t included_imu_measurement_count = 0;
  209. for (size_t i = first_gps_pose; i < gps_measurements.size() - 1; i++) {
  210. // At each non=IMU measurement we initialize a new node in the graph
  211. auto current_pose_key = X(i);
  212. auto current_vel_key = V(i);
  213. auto current_bias_key = B(i);
  214. double t = gps_measurements[i].time;
  215. if (i == first_gps_pose) {
  216. // Create initial estimate and prior on initial pose, velocity, and biases
  217. new_values.insert(current_pose_key, current_pose_global);
  218. new_values.insert(current_vel_key, current_velocity_global);
  219. new_values.insert(current_bias_key, current_bias);
  220. new_factors.emplace_shared<PriorFactor<Pose3>>(
  221. current_pose_key, current_pose_global, sigma_init_x);
  222. new_factors.emplace_shared<PriorFactor<Vector3>>(
  223. current_vel_key, current_velocity_global, sigma_init_v);
  224. new_factors.emplace_shared<PriorFactor<imuBias::ConstantBias>>(
  225. current_bias_key, current_bias, sigma_init_b);
  226. } else {
  227. double t_previous = gps_measurements[i - 1].time;
  228. // Summarize IMU data between the previous GPS measurement and now
  229. current_summarized_measurement =
  230. std::make_shared<PreintegratedImuMeasurements>(imu_params,
  231. current_bias);
  232. while (j < imu_measurements.size() && imu_measurements[j].time <= t) {
  233. if (imu_measurements[j].time >= t_previous) {
  234. current_summarized_measurement->integrateMeasurement(
  235. imu_measurements[j].accelerometer, imu_measurements[j].gyroscope,
  236. imu_measurements[j].dt);
  237. included_imu_measurement_count++;
  238. }
  239. j++;
  240. }
  241. // Create IMU factor
  242. auto previous_pose_key = X(i - 1);
  243. auto previous_vel_key = V(i - 1);
  244. auto previous_bias_key = B(i - 1);
  245. new_factors.emplace_shared<ImuFactor>(
  246. previous_pose_key, previous_vel_key, current_pose_key,
  247. current_vel_key, previous_bias_key, *current_summarized_measurement);
  248. // Bias evolution as given in the IMU metadata
  249. auto sigma_between_b = noiseModel::Diagonal::Sigmas(
  250. (Vector6() << Vector3::Constant(
  251. sqrt(included_imu_measurement_count) *
  252. kitti_calibration.accelerometer_bias_sigma),
  253. Vector3::Constant(sqrt(included_imu_measurement_count) *
  254. kitti_calibration.gyroscope_bias_sigma))
  255. .finished());
  256. new_factors.emplace_shared<BetweenFactor<imuBias::ConstantBias>>(
  257. previous_bias_key, current_bias_key, imuBias::ConstantBias(),
  258. sigma_between_b);
  259. // Create GPS factor
  260. auto gps_pose =
  261. Pose3(current_pose_global.rotation(), gps_measurements[i].position);
  262. if ((i % gps_skip) == 0) {
  263. new_factors.emplace_shared<PriorFactor<Pose3>>(
  264. current_pose_key, gps_pose, noise_model_gps);
  265. new_values.insert(current_pose_key, gps_pose);
  266. printf("############ POSE INCLUDED AT TIME %.6lf ############\n",
  267. t);
  268. cout << gps_pose.translation();
  269. printf("\n\n");
  270. } else {
  271. new_values.insert(current_pose_key, current_pose_global);
  272. }
  273. // Add initial values for velocity and bias based on the previous
  274. // estimates
  275. new_values.insert(current_vel_key, current_velocity_global);
  276. new_values.insert(current_bias_key, current_bias);
  277. // Update solver
  278. // =======================================================================
  279. // We accumulate 2*GPSskip GPS measurements before updating the solver at
  280. // first so that the heading becomes observable.
  281. if (i > (first_gps_pose + 2 * gps_skip)) {
  282. printf("############ NEW FACTORS AT TIME %.6lf ############\n",
  283. t);
  284. new_factors.print();
  285. isam.update(new_factors, new_values);
  286. // Reset the newFactors and newValues list
  287. new_factors.resize(0);
  288. new_values.clear();
  289. // Extract the result/current estimates
  290. Values result = isam.calculateEstimate();
  291. current_pose_global = result.at<Pose3>(current_pose_key);
  292. current_velocity_global = result.at<Vector3>(current_vel_key);
  293. current_bias = result.at<imuBias::ConstantBias>(current_bias_key);
  294. printf("\n############ POSE AT TIME %lf ############\n", t);
  295. current_pose_global.print();
  296. printf("\n\n");
  297. }
  298. }
  299. }
  300. // Save results to file
  301. printf("\nWriting results to file...\n");
  302. FILE* fp_out = fopen(output_filename.c_str(), "w+");
  303. fprintf(fp_out,
  304. "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m)\n");
  305. Values result = isam.calculateEstimate();
  306. for (size_t i = first_gps_pose; i < gps_measurements.size() - 1; i++) {
  307. auto pose_key = X(i);
  308. auto vel_key = V(i);
  309. auto bias_key = B(i);
  310. auto pose = result.at<Pose3>(pose_key);
  311. auto velocity = result.at<Vector3>(vel_key);
  312. auto bias = result.at<imuBias::ConstantBias>(bias_key);
  313. auto pose_quat = pose.rotation().toQuaternion();
  314. auto gps = gps_measurements[i].position;
  315. cout << "State at #" << i << endl;
  316. cout << "Pose:" << endl << pose << endl;
  317. cout << "Velocity:" << endl << velocity << endl;
  318. cout << "Bias:" << endl << bias << endl;
  319. fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n",
  320. gps_measurements[i].time, pose.x(), pose.y(), pose.z(),
  321. pose_quat.x(), pose_quat.y(), pose_quat.z(), pose_quat.w(), gps(0),
  322. gps(1), gps(2));
  323. }
  324. fclose(fp_out);
  325. }