35 #include <boost/program_options.hpp> 51 using namespace gtsam;
58 namespace po = boost::program_options;
61 po::options_description desc;
62 desc.add_options()(
"help,h",
"produce help message")(
63 "data_csv_path", po::value<string>()->default_value(
"imuAndGPSdata.csv"),
64 "path to the CSV file with the IMU data")(
66 po::value<string>()->default_value(
"imuFactorExampleResults.csv"),
67 "path to the result file to use")(
"use_isam", po::bool_switch(),
68 "use ISAM as the optimizer");
71 po::store(po::parse_command_line(argc, argv, desc), vm);
73 if (vm.count(
"help")) {
84 Vector10 initial_state;
85 getline(file, value,
',');
86 for (
int i = 0;
i < 9;
i++) {
87 getline(file, value,
',');
88 initial_state(
i) = stof(value.c_str());
90 getline(file, value,
'\n');
91 initial_state(9) = stof(value.c_str());
96 boost::shared_ptr<PreintegratedCombinedMeasurements::Params>
imuParams() {
98 double accel_noise_sigma = 0.0003924;
99 double gyro_noise_sigma = 0.000205689024915;
100 double accel_bias_rw_sigma = 0.004905;
101 double gyro_bias_rw_sigma = 0.000001454441043;
102 Matrix33 measured_acc_cov = I_3x3 *
pow(accel_noise_sigma, 2);
103 Matrix33 measured_omega_cov = I_3x3 *
pow(gyro_noise_sigma, 2);
104 Matrix33 integration_error_cov =
106 Matrix33 bias_acc_cov = I_3x3 *
pow(accel_bias_rw_sigma, 2);
107 Matrix33 bias_omega_cov = I_3x3 *
pow(gyro_bias_rw_sigma, 2);
108 Matrix66 bias_acc_omega_int =
113 p->accelerometerCovariance =
115 p->integrationCovariance =
116 integration_error_cov;
119 p->gyroscopeCovariance =
122 p->biasAccCovariance = bias_acc_cov;
123 p->biasOmegaCovariance = bias_omega_cov;
124 p->biasAccOmegaInt = bias_acc_omega_int;
129 int main(
int argc,
char* argv[]) {
134 output_filename = var_map[
"output_filename"].as<
string>();
137 FILE* fp_out = fopen(output_filename.c_str(),
"w+");
139 "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m),gt_qx," 140 "gt_qy,gt_qz,gt_qw\n");
145 ifstream
file(data_filename.c_str());
148 cout <<
"initial state:\n" << initial_state.transpose() <<
"\n\n";
153 initial_state(4), initial_state(5));
154 Point3 prior_point(initial_state.head<3>());
155 Pose3 prior_pose(prior_rotation, prior_point);
156 Vector3 prior_velocity(initial_state.tail<3>());
165 initial_values.
insert(
X(index), prior_pose);
166 initial_values.
insert(
V(index), prior_velocity);
167 initial_values.
insert(
B(index), prior_imu_bias);
171 (
Vector(6) << 0.01, 0.01, 0.01, 0.5, 0.5, 0.5)
185 std::shared_ptr<PreintegrationType> preintegrated =
186 std::make_shared<PreintegratedCombinedMeasurements>(
p, prior_imu_bias);
188 assert(preintegrated);
191 NavState prev_state(prior_pose, prior_velocity);
196 double current_position_error = 0.0, current_orientation_error = 0.0;
198 double output_time = 0.0;
203 while (
file.good()) {
206 getline(
file, value,
',');
207 int type = stoi(value.c_str());
211 for (
int i = 0;
i < 5; ++
i) {
212 getline(
file, value,
',');
213 imu(
i) = stof(value.c_str());
215 getline(
file, value,
'\n');
216 imu(5) = stof(value.c_str());
219 preintegrated->integrateMeasurement(imu.head<3>(), imu.tail<3>(), dt);
221 }
else if (type == 1) {
223 for (
int i = 0;
i < 6; ++
i) {
224 getline(
file, value,
',');
225 gps(
i) = stof(value.c_str());
227 getline(
file, value,
'\n');
228 gps(6) = stof(value.c_str());
233 auto preint_imu_combined =
237 V(index),
B(index - 1),
B(index),
238 preint_imu_combined);
239 graph.
add(imu_factor);
247 graph.
add(gps_factor);
250 prop_state = preintegrated->predict(prev_state, prev_bias);
251 initial_values.
insert(
X(index), prop_state.
pose());
252 initial_values.
insert(
V(index), prop_state.
v());
253 initial_values.
insert(
B(index), prev_bias);
266 preintegrated->resetIntegrationAndSetBias(prev_bias);
270 Vector3 position_error = result_position - gps.head<3>();
271 current_position_error = position_error.norm();
277 Vector3 euler_angle_error(quat_error.
x() * 2, quat_error.
y() * 2,
279 current_orientation_error = euler_angle_error.norm();
282 cout <<
"Position error:" << current_position_error <<
"\t " 283 <<
"Angular error:" << current_orientation_error <<
"\n" 286 fprintf(fp_out,
"%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n",
287 output_time, result_position(0), result_position(1),
288 result_position(2), result_quat.
x(), result_quat.
y(),
289 result_quat.
z(), result_quat.
w(),
gps(0),
gps(1),
gps(2),
290 gps_quat.
x(), gps_quat.
y(), gps_quat.
z(), gps_quat.
w());
295 cerr <<
"ERROR parsing file\n";
300 cout <<
"Complete, results written to " << output_filename <<
"\n\n";
virtual const Values & optimize()
EIGEN_DEVICE_FUNC CoeffReturnType x() const
const Vector3 & v() const
Return velocity as Vector3. Computation-free.
Factor Graph consisting of non-linear factors.
void insert(Key j, const Value &val)
EIGEN_DEVICE_FUNC CoeffReturnType y() const
po::variables_map parseOptions(int argc, char *argv[])
Vector10 readInitialState(ifstream &file)
int main(int argc, char *argv[])
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
IsDerived< DERIVEDFACTOR > add(boost::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
NonlinearFactorGraph graph
EIGEN_DEVICE_FUNC Quaternion< Scalar > inverse() const
boost::shared_ptr< PreintegratedCombinedMeasurements::Params > imuParams()
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
EIGEN_DEVICE_FUNC CoeffReturnType w() const
EIGEN_DEVICE_FUNC CoeffReturnType z() const
string findExampleDataFile(const string &name)
const string output_filename
static Rot3 Quaternion(double w, double x, double y, double z)
Header file for GPS factor.
EIGEN_DEVICE_FUNC void normalize()
const ValueType at(Key j) const
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static SmartStereoProjectionParams params
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
The quaternion class used to represent 3D orientations and rotations.
void setVerbosityLM(const std::string &s)
Jet< T, N > pow(const Jet< T, N > &f, double g)
static boost::shared_ptr< PreintegrationCombinedParams > MakeSharedD(double g=9.81)
utility functions for loading datasets
gtsam::Quaternion toQuaternion() const
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)