37 using namespace gtsam;
73 vector<ImuMeasurement>& imu_measurements,
74 vector<GpsMeasurement>& gps_measurements) {
81 string imu_metadata_file =
83 ifstream imu_metadata(imu_metadata_file.c_str());
85 printf(
"-- Reading sensor metadata\n");
87 getline(imu_metadata, line,
'\n');
90 getline(imu_metadata, line,
'\n');
91 sscanf(line.c_str(),
"%lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf",
101 printf(
"IMU metadata: %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf\n",
114 printf(
"-- Reading IMU measurements from file\n");
116 ifstream imu_data(imu_data_file.c_str());
117 getline(imu_data, line,
'\n');
119 double time = 0,
dt = 0, acc_x = 0, acc_y = 0, acc_z = 0, gyro_x = 0,
120 gyro_y = 0, gyro_z = 0;
121 while (!imu_data.eof()) {
122 getline(imu_data, line,
'\n');
123 sscanf(line.c_str(),
"%lf %lf %lf %lf %lf %lf %lf %lf", &
time, &
dt,
124 &acc_x, &acc_y, &acc_z, &gyro_x, &gyro_y, &gyro_z);
127 measurement.time =
time;
129 measurement.accelerometer =
Vector3(acc_x, acc_y, acc_z);
130 measurement.gyroscope =
Vector3(gyro_x, gyro_y, gyro_z);
131 imu_measurements.push_back(measurement);
138 printf(
"-- Reading GPS measurements from file\n");
140 ifstream gps_data(gps_data_file.c_str());
141 getline(gps_data, line,
'\n');
143 double time = 0, gps_x = 0, gps_y = 0, gps_z = 0;
144 while (!gps_data.eof()) {
145 getline(gps_data, line,
'\n');
146 sscanf(line.c_str(),
"%lf,%lf,%lf,%lf", &
time, &gps_x, &gps_y, &gps_z);
149 measurement.time =
time;
150 measurement.position =
Vector3(gps_x, gps_y, gps_z);
151 gps_measurements.push_back(measurement);
156 int main(
int argc,
char* argv[]) {
158 vector<ImuMeasurement> imu_measurements;
159 vector<GpsMeasurement> gps_measurements;
160 loadKittiData(kitti_calibration, imu_measurements, gps_measurements);
168 if (!body_T_imu.equals(
Pose3(), 1
e-5)) {
170 "Currently only support IMUinBody is identity, i.e. IMU and body frame " 177 size_t first_gps_pose = 1;
178 size_t gps_skip = 10;
180 auto w_coriolis = Vector3::Zero();
183 auto noise_model_gps = noiseModel::Diagonal::Precisions(
184 (Vector6() << Vector3::Constant(0), Vector3::Constant(1.0 / 0.07))
189 auto current_pose_global =
192 Vector3 current_velocity_global = Vector3::Zero();
195 auto sigma_init_x = noiseModel::Diagonal::Precisions(
196 (Vector6() << Vector3::Constant(0), Vector3::Constant(1.0)).finished());
197 auto sigma_init_v = noiseModel::Diagonal::Sigmas(Vector3::Constant(1000.0));
198 auto sigma_init_b = noiseModel::Diagonal::Sigmas(
199 (Vector6() << Vector3::Constant(0.100), Vector3::Constant(5.00
e-05))
203 Matrix33 measured_acc_cov =
205 Matrix33 measured_omega_cov =
208 Matrix33 integration_error_cov =
211 auto imu_params = PreintegratedImuMeasurements::Params::MakeSharedU(g);
212 imu_params->accelerometerCovariance =
214 imu_params->integrationCovariance =
215 integration_error_cov;
216 imu_params->gyroscopeCovariance =
218 imu_params->omegaCoriolis = w_coriolis;
220 std::shared_ptr<PreintegratedImuMeasurements> current_summarized_measurement =
241 "-- Starting main loop: inference is performed at each time step, but we " 242 "plot trajectory every 10 steps\n");
244 size_t included_imu_measurement_count = 0;
246 for (
size_t i = first_gps_pose;
i < gps_measurements.size() - 1;
i++) {
248 auto current_pose_key =
X(
i);
249 auto current_vel_key =
V(
i);
250 auto current_bias_key =
B(
i);
251 double t = gps_measurements[
i].time;
253 if (
i == first_gps_pose) {
255 new_values.
insert(current_pose_key, current_pose_global);
256 new_values.
insert(current_vel_key, current_velocity_global);
257 new_values.
insert(current_bias_key, current_bias);
259 current_pose_key, current_pose_global, sigma_init_x);
261 current_vel_key, current_velocity_global, sigma_init_v);
263 current_bias_key, current_bias, sigma_init_b);
265 double t_previous = gps_measurements[
i - 1].time;
268 current_summarized_measurement =
269 std::make_shared<PreintegratedImuMeasurements>(imu_params,
272 while (j < imu_measurements.size() && imu_measurements[
j].time <=
t) {
273 if (imu_measurements[j].
time >= t_previous) {
274 current_summarized_measurement->integrateMeasurement(
275 imu_measurements[j].accelerometer, imu_measurements[j].gyroscope,
276 imu_measurements[j].
dt);
277 included_imu_measurement_count++;
283 auto previous_pose_key =
X(
i - 1);
284 auto previous_vel_key =
V(
i - 1);
285 auto previous_bias_key =
B(
i - 1);
288 previous_pose_key, previous_vel_key, current_pose_key,
289 current_vel_key, previous_bias_key, *current_summarized_measurement);
292 auto sigma_between_b = noiseModel::Diagonal::Sigmas(
293 (Vector6() << Vector3::Constant(
294 sqrt(included_imu_measurement_count) *
296 Vector3::Constant(
sqrt(included_imu_measurement_count) *
305 Pose3(current_pose_global.rotation(), gps_measurements[
i].position);
306 if ((
i % gps_skip) == 0) {
308 current_pose_key, gps_pose, noise_model_gps);
309 new_values.
insert(current_pose_key, gps_pose);
311 printf(
"############ POSE INCLUDED AT TIME %.6lf ############\n",
313 cout << gps_pose.translation();
316 new_values.
insert(current_pose_key, current_pose_global);
321 new_values.
insert(current_vel_key, current_velocity_global);
322 new_values.
insert(current_bias_key, current_bias);
328 if (
i > (first_gps_pose + 2 * gps_skip)) {
329 printf(
"############ NEW FACTORS AT TIME %.6lf ############\n",
333 isam.
update(new_factors, new_values);
342 current_pose_global = result.
at<
Pose3>(current_pose_key);
343 current_velocity_global = result.
at<
Vector3>(current_vel_key);
346 printf(
"\n############ POSE AT TIME %lf ############\n", t);
347 current_pose_global.print();
354 printf(
"\nWriting results to file...\n");
357 "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m)\n");
360 for (
size_t i = first_gps_pose;
i < gps_measurements.size() - 1;
i++) {
361 auto pose_key =
X(
i);
363 auto bias_key =
B(
i);
370 auto gps = gps_measurements[
i].position;
372 cout <<
"State at #" <<
i << endl;
373 cout <<
"Pose:" << endl <<
pose << endl;
374 cout <<
"Velocity:" << endl << velocity << endl;
375 cout <<
"Bias:" << endl << bias << endl;
377 fprintf(fp_out,
"%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n",
379 pose_quat.x(), pose_quat.y(), pose_quat.z(), pose_quat.w(), gps(0),
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Factor Graph consisting of non-linear factors.
double accelerometer_sigma
double accelerometer_bias_sigma
const ValueType at(Key j) const
Pose2_ Expmap(const Vector3_ &xi)
Factorization factorization
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const std::optional< FastMap< Key, int > > &constrainedKeys={}, const std::optional< FastList< Key > > &noRelinKeys={}, const std::optional< FastList< Key > > &extraReelimKeys={}, bool force_relinearize=false)
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
void g(const string &key, int i)
const string output_filename
static Point2 measurement(323.0, 240.0)
Header file for GPS factor.
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
void loadKittiData(KittiCalibration &kitti_calibration, vector< ImuMeasurement > &imu_measurements, vector< GpsMeasurement > &gps_measurements)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
NonlinearISAM isam(relinearizeInterval)
int main(int argc, char *argv[])
double gyroscope_bias_sigma
Velocity3 velocity(const NavState &X, OptionalJacobian< 3, 9 > H)
gtsam::Quaternion toQuaternion() const
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
void print(const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
virtual void resize(size_t size)
void insert(Key j, const Value &val)
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Jet< T, N > sqrt(const Jet< T, N > &f)
Jet< T, N > pow(const Jet< T, N > &f, double g)
Contains data from the IMU mesaurements.
Point3 position(const NavState &X, OptionalJacobian< 3, 9 > H)
utility functions for loading datasets
Values calculateEstimate() const