IMUKittiExampleGPS.py
Go to the documentation of this file.
1 """
2 Example of application of ISAM2 for GPS-aided navigation on the KITTI VISION BENCHMARK SUITE
3 
4 Author: Varun Agrawal
5 """
6 import argparse
7 from typing import List, Tuple
8 
9 import gtsam
10 import numpy as np
11 from gtsam import ISAM2, Pose3, noiseModel
12 from gtsam.symbol_shorthand import B, V, X
13 
14 GRAVITY = 9.8
15 
16 
18  """Class to hold KITTI calibration info."""
19  def __init__(self, body_ptx: float, body_pty: float, body_ptz: float,
20  body_prx: float, body_pry: float, body_prz: float,
21  accelerometer_sigma: float, gyroscope_sigma: float,
22  integration_sigma: float, accelerometer_bias_sigma: float,
23  gyroscope_bias_sigma: float, average_delta_t: float):
24  self.bodyTimu = Pose3(gtsam.Rot3.RzRyRx(body_prx, body_pry, body_prz),
25  gtsam.Point3(body_ptx, body_pty, body_ptz))
26  self.accelerometer_sigma = accelerometer_sigma
27  self.gyroscope_sigma = gyroscope_sigma
28  self.integration_sigma = integration_sigma
29  self.accelerometer_bias_sigma = accelerometer_bias_sigma
30  self.gyroscope_bias_sigma = gyroscope_bias_sigma
31  self.average_delta_t = average_delta_t
32 
33 
35  """An instance of an IMU measurement."""
36  def __init__(self, time: float, dt: float, accelerometer: gtsam.Point3,
37  gyroscope: gtsam.Point3):
38  self.time = time
39  self.dt = dt
40  self.accelerometer = accelerometer
41  self.gyroscope = gyroscope
42 
43 
45  """An instance of a GPS measurement."""
46  def __init__(self, time: float, position: gtsam.Point3):
47  self.time = time
48  self.position = position
49 
50 
51 def loadImuData(imu_data_file: str) -> List[ImuMeasurement]:
52  """Helper to load the IMU data."""
53  # Read IMU data
54  # Time dt accelX accelY accelZ omegaX omegaY omegaZ
55  imu_data_file = gtsam.findExampleDataFile(imu_data_file)
56  imu_measurements = []
57 
58  print("-- Reading IMU measurements from file")
59  with open(imu_data_file, encoding='UTF-8') as imu_data:
60  data = imu_data.readlines()
61  for i in range(1, len(data)): # ignore the first line
62  time, dt, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z = map(
63  float, data[i].split(' '))
64  imu_measurement = ImuMeasurement(
65  time, dt, np.asarray([acc_x, acc_y, acc_z]),
66  np.asarray([gyro_x, gyro_y, gyro_z]))
67  imu_measurements.append(imu_measurement)
68 
69  return imu_measurements
70 
71 
72 def loadGpsData(gps_data_file: str) -> List[GpsMeasurement]:
73  """Helper to load the GPS data."""
74  # Read GPS data
75  # Time,X,Y,Z
76  gps_data_file = gtsam.findExampleDataFile(gps_data_file)
77  gps_measurements = []
78 
79  print("-- Reading GPS measurements from file")
80  with open(gps_data_file, encoding='UTF-8') as gps_data:
81  data = gps_data.readlines()
82  for i in range(1, len(data)):
83  time, x, y, z = map(float, data[i].split(','))
84  gps_measurement = GpsMeasurement(time, np.asarray([x, y, z]))
85  gps_measurements.append(gps_measurement)
86 
87  return gps_measurements
88 
89 
90 def loadKittiData(
91  imu_data_file: str = "KittiEquivBiasedImu.txt",
92  gps_data_file: str = "KittiGps_converted.txt",
93  imu_metadata_file: str = "KittiEquivBiasedImu_metadata.txt"
94 ) -> Tuple[KittiCalibration, List[ImuMeasurement], List[GpsMeasurement]]:
95  """
96  Load the KITTI Dataset.
97  """
98  # Read IMU metadata and compute relative sensor pose transforms
99  # BodyPtx BodyPty BodyPtz BodyPrx BodyPry BodyPrz AccelerometerSigma
100  # GyroscopeSigma IntegrationSigma AccelerometerBiasSigma GyroscopeBiasSigma
101  # AverageDeltaT
102  imu_metadata_file = gtsam.findExampleDataFile(imu_metadata_file)
103  with open(imu_metadata_file, encoding='UTF-8') as imu_metadata:
104  print("-- Reading sensor metadata")
105  line = imu_metadata.readline() # Ignore the first line
106  line = imu_metadata.readline().strip()
107  data = list(map(float, line.split(' ')))
108  kitti_calibration = KittiCalibration(*data)
109  print("IMU metadata:", data)
110 
111  imu_measurements = loadImuData(imu_data_file)
112  gps_measurements = loadGpsData(gps_data_file)
113 
114  return kitti_calibration, imu_measurements, gps_measurements
115 
116 
117 def getImuParams(kitti_calibration: KittiCalibration):
118  """Get the IMU parameters from the KITTI calibration data."""
119  w_coriolis = np.zeros(3)
120 
121  # Set IMU preintegration parameters
122  measured_acc_cov = np.eye(3) * np.power(
123  kitti_calibration.accelerometer_sigma, 2)
124  measured_omega_cov = np.eye(3) * np.power(
125  kitti_calibration.gyroscope_sigma, 2)
126  # error committed in integrating position from velocities
127  integration_error_cov = np.eye(3) * np.power(
128  kitti_calibration.integration_sigma, 2)
129 
130  imu_params = gtsam.PreintegrationParams.MakeSharedU(GRAVITY)
131  # acc white noise in continuous
132  imu_params.setAccelerometerCovariance(measured_acc_cov)
133  # integration uncertainty continuous
134  imu_params.setIntegrationCovariance(integration_error_cov)
135  # gyro white noise in continuous
136  imu_params.setGyroscopeCovariance(measured_omega_cov)
137  imu_params.setOmegaCoriolis(w_coriolis)
138 
139  return imu_params
140 
141 
142 def save_results(isam: gtsam.ISAM2, output_filename: str, first_gps_pose: int,
143  gps_measurements: List[GpsMeasurement]):
144  """Write the results from `isam` to `output_filename`."""
145  # Save results to file
146  print("Writing results to file...")
147  with open(output_filename, 'w', encoding='UTF-8') as fp_out:
148  fp_out.write(
149  "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m)\n")
150 
151  result = isam.calculateEstimate()
152  for i in range(first_gps_pose, len(gps_measurements)):
153  pose_key = X(i)
154  vel_key = V(i)
155  bias_key = B(i)
156 
157  pose = result.atPose3(pose_key)
158  velocity = result.atVector(vel_key)
159  bias = result.atConstantBias(bias_key)
160 
161  pose_quat = pose.rotation().toQuaternion()
162  gps = gps_measurements[i].position
163 
164  print(f"State at #{i}")
165  print(f"Pose:\n{pose}")
166  print(f"Velocity:\n{velocity}")
167  print(f"Bias:\n{bias}")
168 
169  fp_out.write("{},{},{},{},{},{},{},{},{},{},{}\n".format(
170  gps_measurements[i].time, pose.x(), pose.y(), pose.z(),
171  pose_quat.x(), pose_quat.y(), pose_quat.z(), pose_quat.w(),
172  gps[0], gps[1], gps[2]))
173 
174 
175 def parse_args() -> argparse.Namespace:
176  """Parse command line arguments."""
177  parser = argparse.ArgumentParser()
178  parser.add_argument("--output_filename",
179  default="IMUKittiExampleGPSResults.csv")
180  return parser.parse_args()
181 
182 
183 def optimize(gps_measurements: List[GpsMeasurement],
184  imu_measurements: List[ImuMeasurement],
185  sigma_init_x: gtsam.noiseModel.Diagonal,
186  sigma_init_v: gtsam.noiseModel.Diagonal,
187  sigma_init_b: gtsam.noiseModel.Diagonal,
188  noise_model_gps: gtsam.noiseModel.Diagonal,
189  kitti_calibration: KittiCalibration, first_gps_pose: int,
190  gps_skip: int) -> gtsam.ISAM2:
191  """Run ISAM2 optimization on the measurements."""
192  # Set initial conditions for the estimated trajectory
193  # initial pose is the reference frame (navigation frame)
194  current_pose_global = Pose3(gtsam.Rot3(),
195  gps_measurements[first_gps_pose].position)
196 
197  # the vehicle is stationary at the beginning at position 0,0,0
198  current_velocity_global = np.zeros(3)
199  current_bias = gtsam.imuBias.ConstantBias() # init with zero bias
200 
201  imu_params = getImuParams(kitti_calibration)
202 
203  # Set ISAM2 parameters and create ISAM2 solver object
204  isam_params = gtsam.ISAM2Params()
205  isam_params.setFactorization("CHOLESKY")
206  isam_params.relinearizeSkip = 10
207 
208  isam = gtsam.ISAM2(isam_params)
209 
210  # Create the factor graph and values object that will store new factors and
211  # values to add to the incremental graph
212  new_factors = gtsam.NonlinearFactorGraph()
213  # values storing the initial estimates of new nodes in the factor graph
214  new_values = gtsam.Values()
215 
216  # Main loop:
217  # (1) we read the measurements
218  # (2) we create the corresponding factors in the graph
219  # (3) we solve the graph to obtain and optimal estimate of robot trajectory
220  print("-- Starting main loop: inference is performed at each time step, "
221  "but we plot trajectory every 10 steps")
222 
223  j = 0
224  included_imu_measurement_count = 0
225 
226  for i in range(first_gps_pose, len(gps_measurements)):
227  # At each non=IMU measurement we initialize a new node in the graph
228  current_pose_key = X(i)
229  current_vel_key = V(i)
230  current_bias_key = B(i)
231  t = gps_measurements[i].time
232 
233  if i == first_gps_pose:
234  # Create initial estimate and prior on initial pose, velocity, and biases
235  new_values.insert(current_pose_key, current_pose_global)
236  new_values.insert(current_vel_key, current_velocity_global)
237  new_values.insert(current_bias_key, current_bias)
238 
239  new_factors.addPriorPose3(current_pose_key, current_pose_global,
240  sigma_init_x)
241  new_factors.addPriorVector(current_vel_key,
242  current_velocity_global, sigma_init_v)
243  new_factors.addPriorConstantBias(current_bias_key, current_bias,
244  sigma_init_b)
245  else:
246  t_previous = gps_measurements[i - 1].time
247 
248  # Summarize IMU data between the previous GPS measurement and now
249  current_summarized_measurement = gtsam.PreintegratedImuMeasurements(
250  imu_params, current_bias)
251 
252  while (j < len(imu_measurements)
253  and imu_measurements[j].time <= t):
254  if imu_measurements[j].time >= t_previous:
255  current_summarized_measurement.integrateMeasurement(
256  imu_measurements[j].accelerometer,
257  imu_measurements[j].gyroscope, imu_measurements[j].dt)
258  included_imu_measurement_count += 1
259  j += 1
260 
261  # Create IMU factor
262  previous_pose_key = X(i - 1)
263  previous_vel_key = V(i - 1)
264  previous_bias_key = B(i - 1)
265 
266  new_factors.push_back(
267  gtsam.ImuFactor(previous_pose_key, previous_vel_key,
268  current_pose_key, current_vel_key,
269  previous_bias_key,
270  current_summarized_measurement))
271 
272  # Bias evolution as given in the IMU metadata
273  sigma_between_b = gtsam.noiseModel.Diagonal.Sigmas(
274  np.asarray([
275  np.sqrt(included_imu_measurement_count) *
276  kitti_calibration.accelerometer_bias_sigma
277  ] * 3 + [
278  np.sqrt(included_imu_measurement_count) *
279  kitti_calibration.gyroscope_bias_sigma
280  ] * 3))
281 
282  new_factors.push_back(
283  gtsam.BetweenFactorConstantBias(previous_bias_key,
284  current_bias_key,
286  sigma_between_b))
287 
288  # Create GPS factor
289  gps_pose = Pose3(current_pose_global.rotation(),
290  gps_measurements[i].position)
291  if (i % gps_skip) == 0:
292  new_factors.addPriorPose3(current_pose_key, gps_pose,
293  noise_model_gps)
294  new_values.insert(current_pose_key, gps_pose)
295 
296  print(f"############ POSE INCLUDED AT TIME {t} ############")
297  print(gps_pose.translation(), "\n")
298  else:
299  new_values.insert(current_pose_key, current_pose_global)
300 
301  # Add initial values for velocity and bias based on the previous
302  # estimates
303  new_values.insert(current_vel_key, current_velocity_global)
304  new_values.insert(current_bias_key, current_bias)
305 
306  # Update solver
307  # =======================================================================
308  # We accumulate 2*GPSskip GPS measurements before updating the solver at
309  # first so that the heading becomes observable.
310  if i > (first_gps_pose + 2 * gps_skip):
311  print(f"############ NEW FACTORS AT TIME {t:.6f} ############")
312  new_factors.print()
313 
314  isam.update(new_factors, new_values)
315 
316  # Reset the newFactors and newValues list
317  new_factors.resize(0)
318  new_values.clear()
319 
320  # Extract the result/current estimates
321  result = isam.calculateEstimate()
322 
323  current_pose_global = result.atPose3(current_pose_key)
324  current_velocity_global = result.atVector(current_vel_key)
325  current_bias = result.atConstantBias(current_bias_key)
326 
327  print(f"############ POSE AT TIME {t} ############")
328  current_pose_global.print()
329  print("\n")
330 
331  return isam
332 
333 
334 def main():
335  """Main runner."""
336  args = parse_args()
337  kitti_calibration, imu_measurements, gps_measurements = loadKittiData()
338 
339  if not kitti_calibration.bodyTimu.equals(Pose3(), 1e-8):
340  raise ValueError(
341  "Currently only support IMUinBody is identity, i.e. IMU and body frame are the same"
342  )
343 
344  # Configure different variables
345  first_gps_pose = 1
346  gps_skip = 10
347 
348  # Configure noise models
349  noise_model_gps = noiseModel.Diagonal.Precisions(
350  np.asarray([0, 0, 0] + [1.0 / 0.07] * 3))
351 
352  sigma_init_x = noiseModel.Diagonal.Precisions(
353  np.asarray([0, 0, 0, 1, 1, 1]))
354  sigma_init_v = noiseModel.Diagonal.Sigmas(np.ones(3) * 1000.0)
355  sigma_init_b = noiseModel.Diagonal.Sigmas(
356  np.asarray([0.1] * 3 + [5.00e-05] * 3))
357 
358  isam = optimize(gps_measurements, imu_measurements, sigma_init_x,
359  sigma_init_v, sigma_init_b, noise_model_gps,
360  kitti_calibration, first_gps_pose, gps_skip)
361 
362  save_results(isam, args.output_filename, first_gps_pose, gps_measurements)
363 
364 
365 if __name__ == "__main__":
366  main()
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
static Rot3 RzRyRx(double x, double y, double z, OptionalJacobian< 3, 1 > Hx={}, OptionalJacobian< 3, 1 > Hy={}, OptionalJacobian< 3, 1 > Hz={})
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
Definition: Rot3M.cpp:84
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
void split(const G &g, const PredecessorMap< KEY > &tree, G &Ab1, G &Ab2)
Definition: graph-inl.h:245
Definition: pytypes.h:1979
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
Definition: dataset.cpp:70
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:270
Double_ range(const Point2_ &p, const Point2_ &q)
std::string format(const std::string &str, const std::vector< std::string > &find, const std::vector< std::string > &replace)
Vector3 Point3
Definition: Point3.h:38
#define X
Definition: icosphere.cpp:20
static std::shared_ptr< PreintegrationParams > MakeSharedU(double g=9.81)
size_t len(handle h)
Get the length of a Python object.
Definition: pytypes.h:2244


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:21