IMUKittiExampleGPS.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 
18 // GTSAM related includes.
22 #include <gtsam/slam/dataset.h>
24 #include <gtsam/slam/PriorFactor.h>
25 #include <gtsam/nonlinear/ISAM2.h>
28 #include <gtsam/inference/Symbol.h>
29 
30 #include <cstring>
31 #include <fstream>
32 #include <iostream>
33 
34 using namespace std;
35 using namespace gtsam;
36 
37 using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y)
38 using symbol_shorthand::V; // Vel (xdot,ydot,zdot)
39 using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz)
40 
42  double body_ptx;
43  double body_pty;
44  double body_ptz;
45  double body_prx;
46  double body_pry;
47  double body_prz;
54 };
55 
57  double time;
58  double dt;
60  Vector3 gyroscope; // omega
61 };
62 
64  double time;
65  Vector3 position; // x,y,z
66 };
67 
68 const string output_filename = "IMUKittiExampleGPSResults.csv";
69 
70 void loadKittiData(KittiCalibration& kitti_calibration,
71  vector<ImuMeasurement>& imu_measurements,
72  vector<GpsMeasurement>& gps_measurements) {
73  string line;
74 
75  // Read IMU metadata and compute relative sensor pose transforms
76  // BodyPtx BodyPty BodyPtz BodyPrx BodyPry BodyPrz AccelerometerSigma GyroscopeSigma IntegrationSigma
77  // AccelerometerBiasSigma GyroscopeBiasSigma AverageDeltaT
78  string imu_metadata_file = findExampleDataFile("KittiEquivBiasedImu_metadata.txt");
79  ifstream imu_metadata(imu_metadata_file.c_str());
80 
81  printf("-- Reading sensor metadata\n");
82 
83  getline(imu_metadata, line, '\n'); // ignore the first line
84 
85  // Load Kitti calibration
86  getline(imu_metadata, line, '\n');
87  sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf",
88  &kitti_calibration.body_ptx,
89  &kitti_calibration.body_pty,
90  &kitti_calibration.body_ptz,
91  &kitti_calibration.body_prx,
92  &kitti_calibration.body_pry,
93  &kitti_calibration.body_prz,
94  &kitti_calibration.accelerometer_sigma,
95  &kitti_calibration.gyroscope_sigma,
96  &kitti_calibration.integration_sigma,
97  &kitti_calibration.accelerometer_bias_sigma,
98  &kitti_calibration.gyroscope_bias_sigma,
99  &kitti_calibration.average_delta_t);
100  printf("IMU metadata: %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf\n",
101  kitti_calibration.body_ptx,
102  kitti_calibration.body_pty,
103  kitti_calibration.body_ptz,
104  kitti_calibration.body_prx,
105  kitti_calibration.body_pry,
106  kitti_calibration.body_prz,
107  kitti_calibration.accelerometer_sigma,
108  kitti_calibration.gyroscope_sigma,
109  kitti_calibration.integration_sigma,
110  kitti_calibration.accelerometer_bias_sigma,
111  kitti_calibration.gyroscope_bias_sigma,
112  kitti_calibration.average_delta_t);
113 
114  // Read IMU data
115  // Time dt accelX accelY accelZ omegaX omegaY omegaZ
116  string imu_data_file = findExampleDataFile("KittiEquivBiasedImu.txt");
117  printf("-- Reading IMU measurements from file\n");
118  {
119  ifstream imu_data(imu_data_file.c_str());
120  getline(imu_data, line, '\n'); // ignore the first line
121 
122  double time = 0, dt = 0, acc_x = 0, acc_y = 0, acc_z = 0, gyro_x = 0, gyro_y = 0, gyro_z = 0;
123  while (!imu_data.eof()) {
124  getline(imu_data, line, '\n');
125  sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf",
126  &time, &dt,
127  &acc_x, &acc_y, &acc_z,
128  &gyro_x, &gyro_y, &gyro_z);
129 
131  measurement.time = time;
132  measurement.dt = dt;
133  measurement.accelerometer = Vector3(acc_x, acc_y, acc_z);
134  measurement.gyroscope = Vector3(gyro_x, gyro_y, gyro_z);
135  imu_measurements.push_back(measurement);
136  }
137  }
138 
139  // Read GPS data
140  // Time,X,Y,Z
141  string gps_data_file = findExampleDataFile("KittiGps_converted.txt");
142  printf("-- Reading GPS measurements from file\n");
143  {
144  ifstream gps_data(gps_data_file.c_str());
145  getline(gps_data, line, '\n'); // ignore the first line
146 
147  double time = 0, gps_x = 0, gps_y = 0, gps_z = 0;
148  while (!gps_data.eof()) {
149  getline(gps_data, line, '\n');
150  sscanf(line.c_str(), "%lf,%lf,%lf,%lf", &time, &gps_x, &gps_y, &gps_z);
151 
153  measurement.time = time;
154  measurement.position = Vector3(gps_x, gps_y, gps_z);
155  gps_measurements.push_back(measurement);
156  }
157  }
158 }
159 
160 int main(int argc, char* argv[]) {
161  KittiCalibration kitti_calibration;
162  vector<ImuMeasurement> imu_measurements;
163  vector<GpsMeasurement> gps_measurements;
164  loadKittiData(kitti_calibration, imu_measurements, gps_measurements);
165 
166  Vector6 BodyP = (Vector6() << kitti_calibration.body_ptx, kitti_calibration.body_pty, kitti_calibration.body_ptz,
167  kitti_calibration.body_prx, kitti_calibration.body_pry, kitti_calibration.body_prz)
168  .finished();
169  auto body_T_imu = Pose3::Expmap(BodyP);
170  if (!body_T_imu.equals(Pose3(), 1e-5)) {
171  printf("Currently only support IMUinBody is identity, i.e. IMU and body frame are the same");
172  exit(-1);
173  }
174 
175  // Configure different variables
176  // double t_offset = gps_measurements[0].time;
177  size_t first_gps_pose = 1;
178  size_t gps_skip = 10; // Skip this many GPS measurements each time
179  double g = 9.8;
180  auto w_coriolis = Vector3::Zero(); // zero vector
181 
182  // Configure noise models
183  auto noise_model_gps = noiseModel::Diagonal::Precisions((Vector6() << Vector3::Constant(0),
184  Vector3::Constant(1.0/0.07))
185  .finished());
186 
187  // Set initial conditions for the estimated trajectory
188  // initial pose is the reference frame (navigation frame)
189  auto current_pose_global = Pose3(Rot3(), gps_measurements[first_gps_pose].position);
190  // the vehicle is stationary at the beginning at position 0,0,0
191  Vector3 current_velocity_global = Vector3::Zero();
192  auto current_bias = imuBias::ConstantBias(); // init with zero bias
193 
194  auto sigma_init_x = noiseModel::Diagonal::Precisions((Vector6() << Vector3::Constant(0),
195  Vector3::Constant(1.0))
196  .finished());
197  auto sigma_init_v = noiseModel::Diagonal::Sigmas(Vector3::Constant(1000.0));
198  auto sigma_init_b = noiseModel::Diagonal::Sigmas((Vector6() << Vector3::Constant(0.100),
199  Vector3::Constant(5.00e-05))
200  .finished());
201 
202  // Set IMU preintegration parameters
203  Matrix33 measured_acc_cov = I_3x3 * pow(kitti_calibration.accelerometer_sigma, 2);
204  Matrix33 measured_omega_cov = I_3x3 * pow(kitti_calibration.gyroscope_sigma, 2);
205  // error committed in integrating position from velocities
206  Matrix33 integration_error_cov = I_3x3 * pow(kitti_calibration.integration_sigma, 2);
207 
208  auto imu_params = PreintegratedImuMeasurements::Params::MakeSharedU(g);
209  imu_params->accelerometerCovariance = measured_acc_cov; // acc white noise in continuous
210  imu_params->integrationCovariance = integration_error_cov; // integration uncertainty continuous
211  imu_params->gyroscopeCovariance = measured_omega_cov; // gyro white noise in continuous
212  imu_params->omegaCoriolis = w_coriolis;
213 
214  std::shared_ptr<PreintegratedImuMeasurements> current_summarized_measurement = nullptr;
215 
216  // Set ISAM2 parameters and create ISAM2 solver object
217  ISAM2Params isam_params;
218  isam_params.factorization = ISAM2Params::CHOLESKY;
219  isam_params.relinearizeSkip = 10;
220 
221  ISAM2 isam(isam_params);
222 
223  // Create the factor graph and values object that will store new factors and values to add to the incremental graph
224  NonlinearFactorGraph new_factors;
225  Values new_values; // values storing the initial estimates of new nodes in the factor graph
226 
231  printf("-- Starting main loop: inference is performed at each time step, but we plot trajectory every 10 steps\n");
232  size_t j = 0;
233  for (size_t i = first_gps_pose; i < gps_measurements.size() - 1; i++) {
234  // At each non=IMU measurement we initialize a new node in the graph
235  auto current_pose_key = X(i);
236  auto current_vel_key = V(i);
237  auto current_bias_key = B(i);
238  double t = gps_measurements[i].time;
239 
240  if (i == first_gps_pose) {
241  // Create initial estimate and prior on initial pose, velocity, and biases
242  new_values.insert(current_pose_key, current_pose_global);
243  new_values.insert(current_vel_key, current_velocity_global);
244  new_values.insert(current_bias_key, current_bias);
245  new_factors.emplace_shared<PriorFactor<Pose3>>(current_pose_key, current_pose_global, sigma_init_x);
246  new_factors.emplace_shared<PriorFactor<Vector3>>(current_vel_key, current_velocity_global, sigma_init_v);
247  new_factors.emplace_shared<PriorFactor<imuBias::ConstantBias>>(current_bias_key, current_bias, sigma_init_b);
248  } else {
249  double t_previous = gps_measurements[i-1].time;
250 
251  // Summarize IMU data between the previous GPS measurement and now
252  current_summarized_measurement = std::make_shared<PreintegratedImuMeasurements>(imu_params, current_bias);
253  static size_t included_imu_measurement_count = 0;
254  while (j < imu_measurements.size() && imu_measurements[j].time <= t) {
255  if (imu_measurements[j].time >= t_previous) {
256  current_summarized_measurement->integrateMeasurement(imu_measurements[j].accelerometer,
257  imu_measurements[j].gyroscope,
258  imu_measurements[j].dt);
259  included_imu_measurement_count++;
260  }
261  j++;
262  }
263 
264  // Create IMU factor
265  auto previous_pose_key = X(i-1);
266  auto previous_vel_key = V(i-1);
267  auto previous_bias_key = B(i-1);
268 
269  new_factors.emplace_shared<ImuFactor>(previous_pose_key, previous_vel_key,
270  current_pose_key, current_vel_key,
271  previous_bias_key, *current_summarized_measurement);
272 
273  // Bias evolution as given in the IMU metadata
274  auto sigma_between_b = noiseModel::Diagonal::Sigmas((Vector6() <<
275  Vector3::Constant(sqrt(included_imu_measurement_count) * kitti_calibration.accelerometer_bias_sigma),
276  Vector3::Constant(sqrt(included_imu_measurement_count) * kitti_calibration.gyroscope_bias_sigma))
277  .finished());
278  new_factors.emplace_shared<BetweenFactor<imuBias::ConstantBias>>(previous_bias_key,
279  current_bias_key,
281  sigma_between_b);
282 
283  // Create GPS factor
284  auto gps_pose = Pose3(current_pose_global.rotation(), gps_measurements[i].position);
285  if ((i % gps_skip) == 0) {
286  new_factors.emplace_shared<PriorFactor<Pose3>>(current_pose_key, gps_pose, noise_model_gps);
287  new_values.insert(current_pose_key, gps_pose);
288 
289  printf("################ POSE INCLUDED AT TIME %lf ################\n", t);
290  cout << gps_pose.translation();
291  printf("\n\n");
292  } else {
293  new_values.insert(current_pose_key, current_pose_global);
294  }
295 
296  // Add initial values for velocity and bias based on the previous estimates
297  new_values.insert(current_vel_key, current_velocity_global);
298  new_values.insert(current_bias_key, current_bias);
299 
300  // Update solver
301  // =======================================================================
302  // We accumulate 2*GPSskip GPS measurements before updating the solver at
303  // first so that the heading becomes observable.
304  if (i > (first_gps_pose + 2*gps_skip)) {
305  printf("################ NEW FACTORS AT TIME %lf ################\n", t);
306  new_factors.print();
307 
308  isam.update(new_factors, new_values);
309 
310  // Reset the newFactors and newValues list
311  new_factors.resize(0);
312  new_values.clear();
313 
314  // Extract the result/current estimates
316 
317  current_pose_global = result.at<Pose3>(current_pose_key);
318  current_velocity_global = result.at<Vector3>(current_vel_key);
319  current_bias = result.at<imuBias::ConstantBias>(current_bias_key);
320 
321  printf("\n################ POSE AT TIME %lf ################\n", t);
322  current_pose_global.print();
323  printf("\n\n");
324  }
325  }
326  }
327 
328  // Save results to file
329  printf("\nWriting results to file...\n");
330  FILE* fp_out = fopen(output_filename.c_str(), "w+");
331  fprintf(fp_out, "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m)\n");
332 
334  for (size_t i = first_gps_pose; i < gps_measurements.size() - 1; i++) {
335  auto pose_key = X(i);
336  auto vel_key = V(i);
337  auto bias_key = B(i);
338 
339  auto pose = result.at<Pose3>(pose_key);
340  auto velocity = result.at<Vector3>(vel_key);
341  auto bias = result.at<imuBias::ConstantBias>(bias_key);
342 
343  auto pose_quat = pose.rotation().toQuaternion();
344  auto gps = gps_measurements[i].position;
345 
346  cout << "State at #" << i << endl;
347  cout << "Pose:" << endl << pose << endl;
348  cout << "Velocity:" << endl << velocity << endl;
349  cout << "Bias:" << endl << bias << endl;
350 
351  fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n",
352  gps_measurements[i].time,
353  pose.x(), pose.y(), pose.z(),
354  pose_quat.x(), pose_quat.y(), pose_quat.z(), pose_quat.w(),
355  gps(0), gps(1), gps(2));
356  }
357 
358  fclose(fp_out);
359 }
void clear()
Definition: Values.h:311
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 const SqrtReturnType sqrt() const
Pose2_ Expmap(const Vector3_ &xi)
double measurement(10.0)
Definition: Half.h:150
Factorization factorization
Definition: ISAM2Params.h:193
Matrix< SCALARB, Dynamic, Dynamic > B
Definition: bench_gemm.cpp:36
void g(const string &key, int i)
Definition: testBTree.cpp:43
double x() const
get x
Definition: Pose3.h:269
const double dt
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
const string output_filename
Values calculateEstimate() const
Definition: ISAM2.cpp:763
Header file for GPS factor.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:172
Values result
const ValueType at(Key j) const
Definition: Values-inl.h:342
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
double y() const
get y
Definition: Pose3.h:274
void loadKittiData(KittiCalibration &kitti_calibration, vector< ImuMeasurement > &imu_measurements, vector< GpsMeasurement > &gps_measurements)
#define time
Array< double, 1, 3 > e(1./3., 0.5, 2.)
NonlinearISAM isam(relinearizeInterval)
int main(int argc, char *argv[])
Point3 bias(10,-10, 50)
Velocity3 velocity(const NavState &X, OptionalJacobian< 3, 9 > H)
traits
Definition: chartTesting.h:28
void print(const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const boost::optional< FastMap< Key, int > > &constrainedKeys=boost::none, const boost::optional< FastList< Key > > &noRelinKeys=boost::none, const boost::optional< FastList< Key > > &extraReelimKeys=boost::none, bool force_relinearize=false)
Definition: ISAM2.cpp:396
void resize(size_t size)
Definition: FactorGraph.h:358
Jet< T, N > pow(const Jet< T, N > &f, double g)
Definition: jet.h:570
#define X
Definition: icosphere.cpp:20
Contains data from the IMU mesaurements.
Point3 position(const NavState &X, OptionalJacobian< 3, 9 > H)
utility functions for loading datasets
gtsam::Quaternion toQuaternion() const
Definition: Rot3M.cpp:233
std::ptrdiff_t j
Parameters for iSAM 2.
Point2 t(10, 10)
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266
double z() const
get z
Definition: Pose3.h:279


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:13