| 
									
										
										
										
											2016-06-09 22:51:16 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation, | 
					
						
							|  |  |  |  * Atlanta, Georgia 30332-0415 | 
					
						
							|  |  |  |  * All Rights Reserved | 
					
						
							|  |  |  |  * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * See LICENSE for the license information | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2020-06-18 02:47:43 +08:00
										 |  |  |  * @file ImuFactorsExample | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |  * @brief Test example for using GTSAM ImuFactor and ImuCombinedFactor | 
					
						
							|  |  |  |  * navigation code. | 
					
						
							| 
									
										
										
										
											2016-06-09 22:51:16 +08:00
										 |  |  |  * @author Garrett (ghemann@gmail.com), Luca Carlone | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |  * Example of use of the imuFactors (imuFactor and combinedImuFactor) in | 
					
						
							|  |  |  |  * conjunction with GPS | 
					
						
							| 
									
										
										
										
											2019-12-20 15:01:37 +08:00
										 |  |  |  *  - imuFactor is used by default. You can test combinedImuFactor by | 
					
						
							|  |  |  |  *  appending a `-c` flag at the end (see below for example command). | 
					
						
							| 
									
										
										
										
											2016-06-09 22:51:16 +08:00
										 |  |  |  *  - we read IMU and GPS data from a CSV file, with the following format: | 
					
						
							|  |  |  |  *  A row starting with "i" is the first initial position formatted with | 
					
						
							|  |  |  |  *  N, E, D, qx, qY, qZ, qW, velN, velE, velD | 
					
						
							|  |  |  |  *  A row starting with "0" is an imu measurement | 
					
						
							| 
									
										
										
										
											2021-05-29 04:00:34 +08:00
										 |  |  |  *  (body frame - Forward, Right, Down) | 
					
						
							|  |  |  |  *  linAccX, linAccY, linAccZ, angVelX, angVelY, angVelX | 
					
						
							| 
									
										
										
										
											2016-06-09 22:51:16 +08:00
										 |  |  |  *  A row starting with "1" is a gps correction formatted with | 
					
						
							|  |  |  |  *  N, E, D, qX, qY, qZ, qW | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |  * Note that for GPS correction, we're only using the position not the | 
					
						
							|  |  |  |  * rotation. The rotation is provided in the file for ground truth comparison. | 
					
						
							| 
									
										
										
										
											2019-12-20 15:01:37 +08:00
										 |  |  |  * | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:58 +08:00
										 |  |  |  *  See usage: ./ImuFactorsExample --help | 
					
						
							| 
									
										
										
										
											2016-06-09 22:51:16 +08:00
										 |  |  |  */ | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:58 +08:00
										 |  |  | #include <boost/program_options.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | // GTSAM related includes.
 | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:44 +08:00
										 |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | #include <gtsam/navigation/CombinedImuFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/navigation/GPSFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/navigation/ImuFactor.h>
 | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:44 +08:00
										 |  |  | #include <gtsam/nonlinear/ISAM2.h>
 | 
					
						
							| 
									
										
										
										
											2016-06-10 07:43:03 +08:00
										 |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:44 +08:00
										 |  |  | #include <gtsam/slam/BetweenFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/dataset.h>
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2019-12-20 15:01:37 +08:00
										 |  |  | #include <cstring>
 | 
					
						
							| 
									
										
										
										
											2024-12-05 00:43:51 +08:00
										 |  |  | #include <cassert>
 | 
					
						
							| 
									
										
										
										
											2016-06-10 07:43:03 +08:00
										 |  |  | #include <fstream>
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  | using symbol_shorthand::B;  // Bias  (ax,ay,az,gx,gy,gz)
 | 
					
						
							|  |  |  | using symbol_shorthand::V;  // Vel   (xdot,ydot,zdot)
 | 
					
						
							|  |  |  | using symbol_shorthand::X;  // Pose3 (x,y,z,r,p,y)
 | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:58 +08:00
										 |  |  | namespace po = boost::program_options; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | po::variables_map parseOptions(int argc, char* argv[]) { | 
					
						
							|  |  |  |   po::options_description desc; | 
					
						
							|  |  |  |   desc.add_options()("help,h", "produce help message")( | 
					
						
							|  |  |  |       "data_csv_path", po::value<string>()->default_value("imuAndGPSdata.csv"), | 
					
						
							|  |  |  |       "path to the CSV file with the IMU data")( | 
					
						
							|  |  |  |       "output_filename", | 
					
						
							|  |  |  |       po::value<string>()->default_value("imuFactorExampleResults.csv"), | 
					
						
							|  |  |  |       "path to the result file to use")("use_isam", po::bool_switch(), | 
					
						
							|  |  |  |                                         "use ISAM as the optimizer"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   po::variables_map vm; | 
					
						
							|  |  |  |   po::store(po::parse_command_line(argc, argv, desc), vm); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   if (vm.count("help")) { | 
					
						
							|  |  |  |     cout << desc << "\n"; | 
					
						
							|  |  |  |     exit(1); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return vm; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  | std::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() { | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:44 +08:00
										 |  |  |   // We use the sensor specs to build the noise model for the IMU factor.
 | 
					
						
							|  |  |  |   double accel_noise_sigma = 0.0003924; | 
					
						
							|  |  |  |   double gyro_noise_sigma = 0.000205689024915; | 
					
						
							|  |  |  |   double accel_bias_rw_sigma = 0.004905; | 
					
						
							|  |  |  |   double gyro_bias_rw_sigma = 0.000001454441043; | 
					
						
							|  |  |  |   Matrix33 measured_acc_cov = I_3x3 * pow(accel_noise_sigma, 2); | 
					
						
							|  |  |  |   Matrix33 measured_omega_cov = I_3x3 * pow(gyro_noise_sigma, 2); | 
					
						
							|  |  |  |   Matrix33 integration_error_cov = | 
					
						
							|  |  |  |       I_3x3 * 1e-8;  // error committed in integrating position from velocities
 | 
					
						
							|  |  |  |   Matrix33 bias_acc_cov = I_3x3 * pow(accel_bias_rw_sigma, 2); | 
					
						
							|  |  |  |   Matrix33 bias_omega_cov = I_3x3 * pow(gyro_bias_rw_sigma, 2); | 
					
						
							| 
									
										
										
										
											2021-09-29 01:43:04 +08:00
										 |  |  |   Matrix66 bias_acc_omega_init = | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:44 +08:00
										 |  |  |       I_6x6 * 1e-5;  // error in the bias used for preintegration
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(0.0); | 
					
						
							|  |  |  |   // PreintegrationBase params:
 | 
					
						
							|  |  |  |   p->accelerometerCovariance = | 
					
						
							|  |  |  |       measured_acc_cov;  // acc white noise in continuous
 | 
					
						
							|  |  |  |   p->integrationCovariance = | 
					
						
							|  |  |  |       integration_error_cov;  // integration uncertainty continuous
 | 
					
						
							|  |  |  |   // should be using 2nd order integration
 | 
					
						
							|  |  |  |   // PreintegratedRotation params:
 | 
					
						
							|  |  |  |   p->gyroscopeCovariance = | 
					
						
							|  |  |  |       measured_omega_cov;  // gyro white noise in continuous
 | 
					
						
							|  |  |  |   // PreintegrationCombinedMeasurements params:
 | 
					
						
							|  |  |  |   p->biasAccCovariance = bias_acc_cov;      // acc bias in continuous
 | 
					
						
							|  |  |  |   p->biasOmegaCovariance = bias_omega_cov;  // gyro bias in continuous
 | 
					
						
							| 
									
										
										
										
											2022-08-10 22:31:10 +08:00
										 |  |  |   p->biasAccOmegaInt = bias_acc_omega_init; | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   return p; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  | int main(int argc, char* argv[]) { | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:44 +08:00
										 |  |  |   string data_filename, output_filename; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   bool use_isam = false; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:58 +08:00
										 |  |  |   po::variables_map var_map = parseOptions(argc, argv); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   data_filename = findExampleDataFile(var_map["data_csv_path"].as<string>()); | 
					
						
							|  |  |  |   output_filename = var_map["output_filename"].as<string>(); | 
					
						
							|  |  |  |   use_isam = var_map["use_isam"].as<bool>(); | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:44 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-11-28 08:35:12 +08:00
										 |  |  |   ISAM2* isam2 = 0; | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:44 +08:00
										 |  |  |   if (use_isam) { | 
					
						
							|  |  |  |     printf("Using ISAM2\n"); | 
					
						
							|  |  |  |     ISAM2Params parameters; | 
					
						
							|  |  |  |     parameters.relinearizeThreshold = 0.01; | 
					
						
							|  |  |  |     parameters.relinearizeSkip = 1; | 
					
						
							|  |  |  |     isam2 = new ISAM2(parameters); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |   } else { | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:44 +08:00
										 |  |  |     printf("Using Levenberg Marquardt Optimizer\n"); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2016-06-08 08:36:18 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |   // Set up output file for plotting errors
 | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:44 +08:00
										 |  |  |   FILE* fp_out = fopen(output_filename.c_str(), "w+"); | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |   fprintf(fp_out, | 
					
						
							|  |  |  |           "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m),gt_qx," | 
					
						
							|  |  |  |           "gt_qy,gt_qz,gt_qw\n"); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Begin parsing the CSV file.  Input the first line for initialization.
 | 
					
						
							|  |  |  |   // From there, we'll iterate through the file and we'll preintegrate the IMU
 | 
					
						
							|  |  |  |   // or add in the GPS given the input.
 | 
					
						
							| 
									
										
										
										
											2016-06-08 08:36:18 +08:00
										 |  |  |   ifstream file(data_filename.c_str()); | 
					
						
							|  |  |  |   string value; | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Format is (N,E,D,qX,qY,qZ,qW,velN,velE,velD)
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |   Vector10 initial_state; | 
					
						
							|  |  |  |   getline(file, value, ',');  // i
 | 
					
						
							|  |  |  |   for (int i = 0; i < 9; i++) { | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |     getline(file, value, ','); | 
					
						
							| 
									
										
										
										
											2020-08-18 01:12:40 +08:00
										 |  |  |     initial_state(i) = stof(value.c_str()); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |   } | 
					
						
							|  |  |  |   getline(file, value, '\n'); | 
					
						
							| 
									
										
										
										
											2020-08-18 01:12:40 +08:00
										 |  |  |   initial_state(9) = stof(value.c_str()); | 
					
						
							| 
									
										
										
										
											2016-06-08 08:36:18 +08:00
										 |  |  |   cout << "initial state:\n" << initial_state.transpose() << "\n\n"; | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |   // Assemble initial quaternion through GTSAM constructor
 | 
					
						
							|  |  |  |   // ::quaternion(w,x,y,z);
 | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  |   Rot3 prior_rotation = Rot3::Quaternion(initial_state(6), initial_state(3), | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |                                          initial_state(4), initial_state(5)); | 
					
						
							|  |  |  |   Point3 prior_point(initial_state.head<3>()); | 
					
						
							|  |  |  |   Pose3 prior_pose(prior_rotation, prior_point); | 
					
						
							|  |  |  |   Vector3 prior_velocity(initial_state.tail<3>()); | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |   imuBias::ConstantBias prior_imu_bias;  // assume zero initial bias
 | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   Values initial_values; | 
					
						
							|  |  |  |   int correction_count = 0; | 
					
						
							|  |  |  |   initial_values.insert(X(correction_count), prior_pose); | 
					
						
							|  |  |  |   initial_values.insert(V(correction_count), prior_velocity); | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  |   initial_values.insert(B(correction_count), prior_imu_bias); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |   // Assemble prior noise model and add it the graph.`
 | 
					
						
							|  |  |  |   auto pose_noise_model = noiseModel::Diagonal::Sigmas( | 
					
						
							|  |  |  |       (Vector(6) << 0.01, 0.01, 0.01, 0.5, 0.5, 0.5) | 
					
						
							|  |  |  |           .finished());  // rad,rad,rad,m, m, m
 | 
					
						
							|  |  |  |   auto velocity_noise_model = noiseModel::Isotropic::Sigma(3, 0.1);  // m/s
 | 
					
						
							|  |  |  |   auto bias_noise_model = noiseModel::Isotropic::Sigma(6, 1e-3); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Add all prior factors (pose, velocity, bias) to the graph.
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |   NonlinearFactorGraph* graph = new NonlinearFactorGraph(); | 
					
						
							| 
									
										
										
										
											2020-04-13 01:10:09 +08:00
										 |  |  |   graph->addPrior(X(correction_count), prior_pose, pose_noise_model); | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |   graph->addPrior(V(correction_count), prior_velocity, velocity_noise_model); | 
					
						
							|  |  |  |   graph->addPrior(B(correction_count), prior_imu_bias, bias_noise_model); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:44 +08:00
										 |  |  |   auto p = imuParams(); | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:44 +08:00
										 |  |  |   std::shared_ptr<PreintegrationType> preintegrated = | 
					
						
							|  |  |  |       std::make_shared<PreintegratedImuMeasurements>(p, prior_imu_bias); | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |   assert(preintegrated); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |   // Store previous state for imu integration and latest predicted outcome.
 | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |   NavState prev_state(prior_pose, prior_velocity); | 
					
						
							|  |  |  |   NavState prop_state = prev_state; | 
					
						
							|  |  |  |   imuBias::ConstantBias prev_bias = prior_imu_bias; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |   // Keep track of total error over the entire run as simple performance metric.
 | 
					
						
							| 
									
										
										
										
											2016-06-08 08:54:42 +08:00
										 |  |  |   double current_position_error = 0.0, current_orientation_error = 0.0; | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   double output_time = 0.0; | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  |   double dt = 0.005;  // The real system has noise, but here, results are nearly
 | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |                       // exactly the same, so keeping this for simplicity.
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // All priors have been set up, now iterate through the data file.
 | 
					
						
							|  |  |  |   while (file.good()) { | 
					
						
							|  |  |  |     // Parse out first value
 | 
					
						
							|  |  |  |     getline(file, value, ','); | 
					
						
							| 
									
										
										
										
											2020-08-18 01:12:40 +08:00
										 |  |  |     int type = stoi(value.c_str()); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |     if (type == 0) {  // IMU measurement
 | 
					
						
							|  |  |  |       Vector6 imu; | 
					
						
							|  |  |  |       for (int i = 0; i < 5; ++i) { | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |         getline(file, value, ','); | 
					
						
							| 
									
										
										
										
											2020-08-18 01:12:40 +08:00
										 |  |  |         imu(i) = stof(value.c_str()); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |       } | 
					
						
							|  |  |  |       getline(file, value, '\n'); | 
					
						
							| 
									
										
										
										
											2020-08-18 01:12:40 +08:00
										 |  |  |       imu(5) = stof(value.c_str()); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |       // Adding the IMU preintegration.
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |       preintegrated->integrateMeasurement(imu.head<3>(), imu.tail<3>(), dt); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |     } else if (type == 1) {  // GPS measurement
 | 
					
						
							|  |  |  |       Vector7 gps; | 
					
						
							|  |  |  |       for (int i = 0; i < 6; ++i) { | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |         getline(file, value, ','); | 
					
						
							| 
									
										
										
										
											2020-08-18 01:12:40 +08:00
										 |  |  |         gps(i) = stof(value.c_str()); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |       } | 
					
						
							|  |  |  |       getline(file, value, '\n'); | 
					
						
							| 
									
										
										
										
											2020-08-18 01:12:40 +08:00
										 |  |  |       gps(6) = stof(value.c_str()); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |       correction_count++; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |       // Adding IMU factor and GPS factor and optimizing.
 | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:44 +08:00
										 |  |  |       auto preint_imu = | 
					
						
							|  |  |  |           dynamic_cast<const PreintegratedImuMeasurements&>(*preintegrated); | 
					
						
							|  |  |  |       ImuFactor imu_factor(X(correction_count - 1), V(correction_count - 1), | 
					
						
							|  |  |  |                            X(correction_count), V(correction_count), | 
					
						
							|  |  |  |                            B(correction_count - 1), preint_imu); | 
					
						
							|  |  |  |       graph->add(imu_factor); | 
					
						
							|  |  |  |       imuBias::ConstantBias zero_bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); | 
					
						
							|  |  |  |       graph->add(BetweenFactor<imuBias::ConstantBias>( | 
					
						
							|  |  |  |           B(correction_count - 1), B(correction_count), zero_bias, | 
					
						
							|  |  |  |           bias_noise_model)); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |       auto correction_noise = noiseModel::Isotropic::Sigma(3, 1.0); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |       GPSFactor gps_factor(X(correction_count), | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |                            Point3(gps(0),   // N,
 | 
					
						
							|  |  |  |                                   gps(1),   // E,
 | 
					
						
							|  |  |  |                                   gps(2)),  // D,
 | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |                            correction_noise); | 
					
						
							|  |  |  |       graph->add(gps_factor); | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |       // Now optimize and compare results.
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |       prop_state = preintegrated->predict(prev_state, prev_bias); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |       initial_values.insert(X(correction_count), prop_state.pose()); | 
					
						
							|  |  |  |       initial_values.insert(V(correction_count), prop_state.v()); | 
					
						
							|  |  |  |       initial_values.insert(B(correction_count), prev_bias); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-03-31 00:46:30 +08:00
										 |  |  |       Values result; | 
					
						
							| 
									
										
										
										
											2020-08-11 14:32:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |       if (use_isam) { | 
					
						
							|  |  |  |         isam2->update(*graph, initial_values); | 
					
						
							|  |  |  |         result = isam2->calculateEstimate(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |         // reset the graph
 | 
					
						
							|  |  |  |         graph->resize(0); | 
					
						
							|  |  |  |         initial_values.clear(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |       } else { | 
					
						
							|  |  |  |         LevenbergMarquardtOptimizer optimizer(*graph, initial_values); | 
					
						
							|  |  |  |         result = optimizer.optimize(); | 
					
						
							|  |  |  |       } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |       // Overwrite the beginning of the preintegration for the next step.
 | 
					
						
							|  |  |  |       prev_state = NavState(result.at<Pose3>(X(correction_count)), | 
					
						
							|  |  |  |                             result.at<Vector3>(V(correction_count))); | 
					
						
							|  |  |  |       prev_bias = result.at<imuBias::ConstantBias>(B(correction_count)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |       // Reset the preintegration object.
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |       preintegrated->resetIntegrationAndSetBias(prev_bias); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |       // Print out the position and orientation error for comparison.
 | 
					
						
							| 
									
										
										
										
											2016-06-10 07:43:03 +08:00
										 |  |  |       Vector3 gtsam_position = prev_state.pose().translation(); | 
					
						
							|  |  |  |       Vector3 position_error = gtsam_position - gps.head<3>(); | 
					
						
							| 
									
										
										
										
											2016-06-08 08:54:42 +08:00
										 |  |  |       current_position_error = position_error.norm(); | 
					
						
							| 
									
										
										
										
											2016-06-08 08:36:18 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-06-10 07:43:03 +08:00
										 |  |  |       Quaternion gtsam_quat = prev_state.pose().rotation().toQuaternion(); | 
					
						
							|  |  |  |       Quaternion gps_quat(gps(6), gps(3), gps(4), gps(5)); | 
					
						
							|  |  |  |       Quaternion quat_error = gtsam_quat * gps_quat.inverse(); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |       quat_error.normalize(); | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |       Vector3 euler_angle_error(quat_error.x() * 2, quat_error.y() * 2, | 
					
						
							|  |  |  |                                 quat_error.z() * 2); | 
					
						
							| 
									
										
										
										
											2016-06-08 08:54:42 +08:00
										 |  |  |       current_orientation_error = euler_angle_error.norm(); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-06-08 08:36:18 +08:00
										 |  |  |       // display statistics
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |       cout << "Position error:" << current_position_error << "\t " | 
					
						
							|  |  |  |            << "Angular error:" << current_orientation_error << "\n"; | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  |       fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n", | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |               output_time, gtsam_position(0), gtsam_position(1), | 
					
						
							|  |  |  |               gtsam_position(2), gtsam_quat.x(), gtsam_quat.y(), gtsam_quat.z(), | 
					
						
							|  |  |  |               gtsam_quat.w(), gps(0), gps(1), gps(2), gps_quat.x(), | 
					
						
							|  |  |  |               gps_quat.y(), gps_quat.z(), gps_quat.w()); | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |       output_time += 1.0; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     } else { | 
					
						
							| 
									
										
										
										
											2016-06-08 08:36:18 +08:00
										 |  |  |       cerr << "ERROR parsing file\n"; | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |       return 1; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   fclose(fp_out); | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:17 +08:00
										 |  |  |   cout << "Complete, results written to " << output_filename << "\n\n"; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-06-08 07:57:34 +08:00
										 |  |  |   return 0; | 
					
						
							|  |  |  | } |