35 using namespace gtsam;
71 vector<ImuMeasurement>& imu_measurements,
72 vector<GpsMeasurement>& gps_measurements) {
79 ifstream imu_metadata(imu_metadata_file.c_str());
81 printf(
"-- Reading sensor metadata\n");
83 getline(imu_metadata, line,
'\n');
86 getline(imu_metadata, line,
'\n');
87 sscanf(line.c_str(),
"%lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf",
100 printf(
"IMU metadata: %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf\n",
117 printf(
"-- Reading IMU measurements from file\n");
119 ifstream imu_data(imu_data_file.c_str());
120 getline(imu_data, line,
'\n');
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",
127 &acc_x, &acc_y, &acc_z,
128 &gyro_x, &gyro_y, &gyro_z);
131 measurement.time =
time;
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);
142 printf(
"-- Reading GPS measurements from file\n");
144 ifstream gps_data(gps_data_file.c_str());
145 getline(gps_data, line,
'\n');
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);
153 measurement.time =
time;
154 measurement.position =
Vector3(gps_x, gps_y, gps_z);
155 gps_measurements.push_back(measurement);
160 int main(
int argc,
char* argv[]) {
162 vector<ImuMeasurement> imu_measurements;
163 vector<GpsMeasurement> gps_measurements;
164 loadKittiData(kitti_calibration, imu_measurements, gps_measurements);
170 if (!body_T_imu.equals(
Pose3(), 1
e-5)) {
171 printf(
"Currently only support IMUinBody is identity, i.e. IMU and body frame are the same");
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((Vector6() << Vector3::Constant(0),
184 Vector3::Constant(1.0/0.07))
189 auto current_pose_global =
Pose3(
Rot3(), gps_measurements[first_gps_pose].
position);
191 Vector3 current_velocity_global = Vector3::Zero();
194 auto sigma_init_x = noiseModel::Diagonal::Precisions((Vector6() << Vector3::Constant(0),
195 Vector3::Constant(1.0))
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.00
e-05))
208 auto imu_params = PreintegratedImuMeasurements::Params::MakeSharedU(g);
209 imu_params->accelerometerCovariance = measured_acc_cov;
210 imu_params->integrationCovariance = integration_error_cov;
211 imu_params->gyroscopeCovariance = measured_omega_cov;
212 imu_params->omegaCoriolis = w_coriolis;
214 std::shared_ptr<PreintegratedImuMeasurements> current_summarized_measurement =
nullptr;
231 printf(
"-- Starting main loop: inference is performed at each time step, but we plot trajectory every 10 steps\n");
233 for (
size_t i = first_gps_pose;
i < gps_measurements.size() - 1;
i++) {
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;
240 if (
i == first_gps_pose) {
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);
249 double t_previous = gps_measurements[
i-1].time;
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++;
265 auto previous_pose_key =
X(
i-1);
266 auto previous_vel_key =
V(
i-1);
267 auto previous_bias_key =
B(
i-1);
270 current_pose_key, current_vel_key,
271 previous_bias_key, *current_summarized_measurement);
274 auto sigma_between_b = noiseModel::Diagonal::Sigmas((Vector6() <<
284 auto gps_pose =
Pose3(current_pose_global.rotation(), gps_measurements[
i].position);
285 if ((
i % gps_skip) == 0) {
287 new_values.
insert(current_pose_key, gps_pose);
289 printf(
"################ POSE INCLUDED AT TIME %lf ################\n", t);
290 cout << gps_pose.translation();
293 new_values.
insert(current_pose_key, current_pose_global);
297 new_values.
insert(current_vel_key, current_velocity_global);
298 new_values.
insert(current_bias_key, current_bias);
304 if (
i > (first_gps_pose + 2*gps_skip)) {
305 printf(
"################ NEW FACTORS AT TIME %lf ################\n", t);
308 isam.
update(new_factors, new_values);
317 current_pose_global = result.
at<
Pose3>(current_pose_key);
318 current_velocity_global = result.
at<
Vector3>(current_vel_key);
321 printf(
"\n################ POSE AT TIME %lf ################\n", t);
322 current_pose_global.print();
329 printf(
"\nWriting results to file...\n");
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");
334 for (
size_t i = first_gps_pose;
i < gps_measurements.size() - 1;
i++) {
335 auto pose_key =
X(
i);
337 auto bias_key =
B(
i);
344 auto gps = gps_measurements[
i].position;
346 cout <<
"State at #" <<
i << endl;
347 cout <<
"Pose:" << endl <<
pose << endl;
348 cout <<
"Velocity:" << endl << velocity << endl;
349 cout <<
"Bias:" << endl << bias << endl;
351 fprintf(fp_out,
"%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n",
352 gps_measurements[
i].
time,
354 pose_quat.x(), pose_quat.y(), pose_quat.z(), pose_quat.w(),
Factor Graph consisting of non-linear factors.
double accelerometer_sigma
double accelerometer_bias_sigma
void insert(Key j, const Value &val)
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Pose2_ Expmap(const Vector3_ &xi)
Factorization factorization
Matrix< SCALARB, Dynamic, Dynamic > B
void g(const string &key, int i)
string findExampleDataFile(const string &name)
const string output_filename
Values calculateEstimate() const
Header file for GPS factor.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
const ValueType at(Key j) const
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
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)
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)
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
gtsam::Quaternion toQuaternion() const
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation