36 #include <boost/program_options.hpp> 
   53 using namespace gtsam;
 
   60 namespace po = boost::program_options;
 
   63   po::options_description 
desc;
 
   64   desc.add_options()(
"help,h", 
"produce help message")  
 
   65       (
"data_csv_path", po::value<string>()->default_value(
"imuAndGPSdata.csv"),
 
   66        "path to the CSV file with the IMU data")  
 
   68        po::value<string>()->default_value(
"imuFactorExampleResults.csv"),
 
   69        "path to the result file to use")  
 
   70       (
"use_isam", po::bool_switch(),
 
   71        "use ISAM as the optimizer");  
 
   74   po::store(po::parse_command_line(argc, argv, 
desc), vm);
 
   76   if (vm.count(
"help")) {
 
   89   for (
int i = 0; 
i < 9; 
i++) {
 
   91     initial_state(
i) = stof(
value.c_str());
 
   94   initial_state(9) = stof(
value.c_str());
 
   99 std::shared_ptr<PreintegratedCombinedMeasurements::Params> 
imuParams() {
 
  101   double accel_noise_sigma = 0.0003924;
 
  102   double gyro_noise_sigma = 0.000205689024915;
 
  103   double accel_bias_rw_sigma = 0.004905;
 
  104   double gyro_bias_rw_sigma = 0.000001454441043;
 
  105   Matrix33 measured_acc_cov = I_3x3 * 
pow(accel_noise_sigma, 2);
 
  106   Matrix33 measured_omega_cov = I_3x3 * 
pow(gyro_noise_sigma, 2);
 
  107   Matrix33 integration_error_cov =
 
  109   Matrix33 bias_acc_cov = I_3x3 * 
pow(accel_bias_rw_sigma, 2);
 
  110   Matrix33 bias_omega_cov = I_3x3 * 
pow(gyro_bias_rw_sigma, 2);
 
  111   Matrix66 bias_acc_omega_init =
 
  116   p->accelerometerCovariance =
 
  118   p->integrationCovariance =
 
  119       integration_error_cov;  
 
  122   p->gyroscopeCovariance =
 
  125   p->biasAccCovariance = bias_acc_cov;      
 
  126   p->biasOmegaCovariance = bias_omega_cov;  
 
  127   p->biasAccOmegaInt = bias_acc_omega_init;
 
  132 int main(
int argc, 
char* argv[]) {
 
  142           "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m),gt_qx," 
  143           "gt_qy,gt_qz,gt_qw\n");
 
  148   ifstream 
file(data_filename.c_str());
 
  151   cout << 
"initial state:\n" << initial_state.transpose() << 
"\n\n";
 
  156                                          initial_state(4), initial_state(5));
 
  157   Point3 prior_point(initial_state.head<3>());
 
  158   Pose3 prior_pose(prior_rotation, prior_point);
 
  159   Vector3 prior_velocity(initial_state.tail<3>());
 
  168   initial_values.
insert(
X(index), prior_pose);
 
  169   initial_values.
insert(
V(index), prior_velocity);
 
  170   initial_values.
insert(
B(index), prior_imu_bias);
 
  174       (
Vector(6) << 0.01, 0.01, 0.01, 0.5, 0.5, 0.5)
 
  188   std::shared_ptr<PreintegrationType> preintegrated =
 
  189       std::make_shared<PreintegratedCombinedMeasurements>(
p, prior_imu_bias);
 
  191   assert(preintegrated);
 
  194   NavState prev_state(prior_pose, prior_velocity);
 
  199   double current_position_error = 0.0, current_orientation_error = 0.0;
 
  201   double output_time = 0.0;
 
  206   while (
file.good()) {
 
  214       for (
int i = 0; 
i < 5; ++
i) {
 
  216         imu(
i) = stof(
value.c_str());
 
  219       imu(5) = stof(
value.c_str());
 
  222       preintegrated->integrateMeasurement(imu.head<3>(), imu.tail<3>(), 
dt);
 
  224     } 
else if (
type == 1) {  
 
  226       for (
int i = 0; 
i < 6; ++
i) {
 
  228         gps(
i) = stof(
value.c_str());
 
  231       gps(6) = stof(
value.c_str());
 
  236       auto preint_imu_combined =
 
  240                                    V(index), 
B(index - 1), 
B(index),
 
  241                                    preint_imu_combined);
 
  253       prop_state = preintegrated->predict(prev_state, prev_bias);
 
  254       initial_values.
insert(
X(index), prop_state.
pose());
 
  255       initial_values.
insert(
V(index), prop_state.
v());
 
  256       initial_values.
insert(
B(index), prev_bias);
 
  259       params.setVerbosityLM(
"SUMMARY");
 
  269       preintegrated->resetIntegrationAndSetBias(prev_bias);
 
  273       Vector3 position_error = result_position - gps.head<3>();
 
  274       current_position_error = position_error.norm();
 
  277       Quaternion gps_quat(gps(6), gps(3), gps(4), gps(5));
 
  278       Quaternion quat_error = result_quat * gps_quat.inverse();
 
  279       quat_error.normalize();
 
  280       Vector3 euler_angle_error(quat_error.x() * 2, quat_error.y() * 2,
 
  282       current_orientation_error = euler_angle_error.norm();
 
  285       cout << 
"Position error:" << current_position_error << 
"\t " 
  286            << 
"Angular error:" << current_orientation_error << 
"\n" 
  289       fprintf(fp_out, 
"%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n",
 
  290               output_time, result_position(0), result_position(1),
 
  291               result_position(2), result_quat.x(), result_quat.y(),
 
  292               result_quat.z(), result_quat.w(), gps(0), gps(1), gps(2),
 
  293               gps_quat.x(), gps_quat.y(), gps_quat.z(), gps_quat.w());
 
  298       cerr << 
"ERROR parsing file\n";