2 Example of application of ISAM2 for GPS-aided navigation on the KITTI VISION BENCHMARK SUITE 7 from typing
import List, Tuple
11 from gtsam
import ISAM2, Pose3, noiseModel
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):
35 """An instance of an IMU measurement.""" 36 def __init__(self, time: float, dt: float, accelerometer: gtsam.Point3,
37 gyroscope: gtsam.Point3):
45 """An instance of a GPS measurement.""" 46 def __init__(self, time: float, position: gtsam.Point3):
52 """Helper to load the IMU data.""" 58 print(
"-- Reading IMU measurements from file")
59 with open(imu_data_file, encoding=
'UTF-8')
as imu_data:
60 data = imu_data.readlines()
62 time, dt, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z = map(
63 float, data[i].
split(
' '))
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)
69 return imu_measurements
73 """Helper to load the GPS data.""" 79 print(
"-- Reading GPS measurements from file")
80 with open(gps_data_file, encoding=
'UTF-8')
as gps_data:
81 data = gps_data.readlines()
83 time, x, y, z = map(float, data[i].
split(
','))
85 gps_measurements.append(gps_measurement)
87 return gps_measurements
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]]:
96 Load the KITTI Dataset. 103 with open(imu_metadata_file, encoding=
'UTF-8')
as imu_metadata:
104 print(
"-- Reading sensor metadata")
105 line = imu_metadata.readline()
106 line = imu_metadata.readline().strip()
107 data =
list(map(float, line.split(
' ')))
109 print(
"IMU metadata:", data)
114 return kitti_calibration, imu_measurements, gps_measurements
118 """Get the IMU parameters from the KITTI calibration data.""" 119 w_coriolis = np.zeros(3)
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)
127 integration_error_cov = np.eye(3) * np.power(
128 kitti_calibration.integration_sigma, 2)
132 imu_params.setAccelerometerCovariance(measured_acc_cov)
134 imu_params.setIntegrationCovariance(integration_error_cov)
136 imu_params.setGyroscopeCovariance(measured_omega_cov)
137 imu_params.setOmegaCoriolis(w_coriolis)
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`.""" 146 print(
"Writing results to file...")
147 with open(output_filename,
'w', encoding=
'UTF-8')
as fp_out:
149 "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m)\n")
151 result = isam.calculateEstimate()
152 for i
in range(first_gps_pose,
len(gps_measurements)):
157 pose = result.atPose3(pose_key)
158 velocity = result.atVector(vel_key)
159 bias = result.atConstantBias(bias_key)
161 pose_quat = pose.rotation().toQuaternion()
162 gps = gps_measurements[i].position
164 print(f
"State at #{i}")
165 print(f
"Pose:\n{pose}")
166 print(f
"Velocity:\n{velocity}")
167 print(f
"Bias:\n{bias}")
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]))
176 """Parse command line arguments.""" 177 parser = argparse.ArgumentParser()
178 parser.add_argument(
"--output_filename",
179 default=
"IMUKittiExampleGPSResults.csv")
180 return parser.parse_args()
183 def optimize(gps_measurements: List[GpsMeasurement],
184 imu_measurements: List[ImuMeasurement],
189 kitti_calibration: KittiCalibration, first_gps_pose: int,
191 """Run ISAM2 optimization on the measurements.""" 195 gps_measurements[first_gps_pose].position)
198 current_velocity_global = np.zeros(3)
205 isam_params.setFactorization(
"CHOLESKY")
206 isam_params.relinearizeSkip = 10
220 print(
"-- Starting main loop: inference is performed at each time step, " 221 "but we plot trajectory every 10 steps")
224 included_imu_measurement_count = 0
226 for i
in range(first_gps_pose,
len(gps_measurements)):
228 current_pose_key =
X(i)
229 current_vel_key =
V(i)
230 current_bias_key = B(i)
231 t = gps_measurements[i].time
233 if i == first_gps_pose:
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)
239 new_factors.addPriorPose3(current_pose_key, current_pose_global,
241 new_factors.addPriorVector(current_vel_key,
242 current_velocity_global, sigma_init_v)
243 new_factors.addPriorConstantBias(current_bias_key, current_bias,
246 t_previous = gps_measurements[i - 1].time
250 imu_params, current_bias)
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
262 previous_pose_key =
X(i - 1)
263 previous_vel_key =
V(i - 1)
264 previous_bias_key = B(i - 1)
266 new_factors.push_back(
268 current_pose_key, current_vel_key,
270 current_summarized_measurement))
275 np.sqrt(included_imu_measurement_count) *
276 kitti_calibration.accelerometer_bias_sigma
278 np.sqrt(included_imu_measurement_count) *
279 kitti_calibration.gyroscope_bias_sigma
282 new_factors.push_back(
283 gtsam.BetweenFactorConstantBias(previous_bias_key,
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,
294 new_values.insert(current_pose_key, gps_pose)
296 print(f
"############ POSE INCLUDED AT TIME {t} ############")
297 print(gps_pose.translation(),
"\n")
299 new_values.insert(current_pose_key, current_pose_global)
303 new_values.insert(current_vel_key, current_velocity_global)
304 new_values.insert(current_bias_key, current_bias)
310 if i > (first_gps_pose + 2 * gps_skip):
311 print(f
"############ NEW FACTORS AT TIME {t:.6f} ############")
314 isam.update(new_factors, new_values)
317 new_factors.resize(0)
321 result = isam.calculateEstimate()
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)
327 print(f
"############ POSE AT TIME {t} ############")
328 current_pose_global.print()
337 kitti_calibration, imu_measurements, gps_measurements =
loadKittiData()
339 if not kitti_calibration.bodyTimu.equals(
Pose3(), 1e-8):
341 "Currently only support IMUinBody is identity, i.e. IMU and body frame are the same" 349 noise_model_gps = noiseModel.Diagonal.Precisions(
350 np.asarray([0, 0, 0] + [1.0 / 0.07] * 3))
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))
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)
362 save_results(isam, args.output_filename, first_gps_pose, gps_measurements)
365 if __name__ ==
"__main__":
void print(const Matrix &A, const string &s, ostream &stream)
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.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
void split(const G &g, const PredecessorMap< KEY > &tree, G &Ab1, G &Ab2)
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
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)
static std::shared_ptr< PreintegrationParams > MakeSharedU(double g=9.81)
size_t len(handle h)
Get the length of a Python object.