36 #include <boost/program_options.hpp> 52 using namespace gtsam;
59 namespace po = boost::program_options;
62 po::options_description desc;
63 desc.add_options()(
"help,h",
"produce help message")
64 (
"data_csv_path", po::value<string>()->default_value(
"imuAndGPSdata.csv"),
65 "path to the CSV file with the IMU data")
67 po::value<string>()->default_value(
"imuFactorExampleResults.csv"),
68 "path to the result file to use")
69 (
"use_isam", po::bool_switch(),
70 "use ISAM as the optimizer");
73 po::store(po::parse_command_line(argc, argv, desc), vm);
75 if (vm.count(
"help")) {
86 Vector10 initial_state;
87 getline(file, value,
',');
88 for (
int i = 0;
i < 9;
i++) {
89 getline(file, value,
',');
90 initial_state(
i) = stof(value.c_str());
92 getline(file, value,
'\n');
93 initial_state(9) = stof(value.c_str());
98 std::shared_ptr<PreintegratedCombinedMeasurements::Params>
imuParams() {
100 double accel_noise_sigma = 0.0003924;
101 double gyro_noise_sigma = 0.000205689024915;
102 double accel_bias_rw_sigma = 0.004905;
103 double gyro_bias_rw_sigma = 0.000001454441043;
104 Matrix33 measured_acc_cov = I_3x3 *
pow(accel_noise_sigma, 2);
105 Matrix33 measured_omega_cov = I_3x3 *
pow(gyro_noise_sigma, 2);
106 Matrix33 integration_error_cov =
108 Matrix33 bias_acc_cov = I_3x3 *
pow(accel_bias_rw_sigma, 2);
109 Matrix33 bias_omega_cov = I_3x3 *
pow(gyro_bias_rw_sigma, 2);
110 Matrix66 bias_acc_omega_init =
115 p->accelerometerCovariance =
117 p->integrationCovariance =
118 integration_error_cov;
121 p->gyroscopeCovariance =
124 p->biasAccCovariance = bias_acc_cov;
125 p->biasOmegaCovariance = bias_omega_cov;
126 p->biasAccOmegaInt = bias_acc_omega_init;
131 int main(
int argc,
char* argv[]) {
136 output_filename = var_map[
"output_filename"].as<
string>();
139 FILE* fp_out = fopen(output_filename.c_str(),
"w+");
141 "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m),gt_qx," 142 "gt_qy,gt_qz,gt_qw\n");
147 ifstream
file(data_filename.c_str());
150 cout <<
"initial state:\n" << initial_state.transpose() <<
"\n\n";
155 initial_state(4), initial_state(5));
156 Point3 prior_point(initial_state.head<3>());
157 Pose3 prior_pose(prior_rotation, prior_point);
158 Vector3 prior_velocity(initial_state.tail<3>());
167 initial_values.
insert(
X(index), prior_pose);
168 initial_values.
insert(
V(index), prior_velocity);
169 initial_values.
insert(
B(index), prior_imu_bias);
173 (
Vector(6) << 0.01, 0.01, 0.01, 0.5, 0.5, 0.5)
187 std::shared_ptr<PreintegrationType> preintegrated =
188 std::make_shared<PreintegratedCombinedMeasurements>(
p, prior_imu_bias);
190 assert(preintegrated);
193 NavState prev_state(prior_pose, prior_velocity);
198 double current_position_error = 0.0, current_orientation_error = 0.0;
200 double output_time = 0.0;
205 while (
file.good()) {
208 getline(
file, value,
',');
209 int type = stoi(value.c_str());
213 for (
int i = 0;
i < 5; ++
i) {
214 getline(
file, value,
',');
215 imu(
i) = stof(value.c_str());
217 getline(
file, value,
'\n');
218 imu(5) = stof(value.c_str());
221 preintegrated->integrateMeasurement(imu.head<3>(), imu.tail<3>(), dt);
223 }
else if (type == 1) {
225 for (
int i = 0;
i < 6; ++
i) {
226 getline(
file, value,
',');
227 gps(
i) = stof(value.c_str());
229 getline(
file, value,
'\n');
230 gps(6) = stof(value.c_str());
235 auto preint_imu_combined =
239 V(index),
B(index - 1),
B(index),
240 preint_imu_combined);
241 graph.
add(imu_factor);
249 graph.
add(gps_factor);
252 prop_state = preintegrated->predict(prev_state, prev_bias);
253 initial_values.
insert(
X(index), prop_state.
pose());
254 initial_values.
insert(
V(index), prop_state.
v());
255 initial_values.
insert(
B(index), prev_bias);
268 preintegrated->resetIntegrationAndSetBias(prev_bias);
272 Vector3 position_error = result_position - gps.head<3>();
273 current_position_error = position_error.norm();
276 Quaternion gps_quat(gps(6), gps(3), gps(4), gps(5));
279 Vector3 euler_angle_error(quat_error.
x() * 2, quat_error.
y() * 2,
281 current_orientation_error = euler_angle_error.norm();
284 cout <<
"Position error:" << current_position_error <<
"\t " 285 <<
"Angular error:" << current_orientation_error <<
"\n" 288 fprintf(fp_out,
"%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n",
289 output_time, result_position(0), result_position(1),
290 result_position(2), result_quat.
x(), result_quat.
y(),
291 result_quat.
z(), result_quat.
w(), gps(0), gps(1), gps(2),
292 gps_quat.
x(), gps_quat.
y(), gps_quat.
z(), gps_quat.
w());
297 cerr <<
"ERROR parsing file\n";
302 cout <<
"Complete, results written to " << output_filename <<
"\n\n";
std::shared_ptr< PreintegratedCombinedMeasurements::Params > imuParams()
static std::shared_ptr< PreintegrationCombinedParams > MakeSharedD(double g=9.81)
EIGEN_DEVICE_FUNC CoeffReturnType x() const
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
virtual const Values & optimize()
Factor Graph consisting of non-linear factors.
const ValueType at(Key j) const
EIGEN_DEVICE_FUNC CoeffReturnType z() const
po::variables_map parseOptions(int argc, char *argv[])
Vector10 readInitialState(ifstream &file)
int main(int argc, char *argv[])
EIGEN_DEVICE_FUNC CoeffReturnType w() const
NonlinearFactorGraph graph
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
static const SmartProjectionParams params
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
const string output_filename
static Rot3 Quaternion(double w, double x, double y, double z)
Header file for GPS factor.
const Vector3 & v() const
Return velocity as Vector3. Computation-free.
EIGEN_DEVICE_FUNC void normalize()
EIGEN_DEVICE_FUNC Quaternion< Scalar > inverse() const
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EIGEN_DEVICE_FUNC CoeffReturnType y() const
gtsam::Quaternion toQuaternion() const
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
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)
void insert(Key j, const Value &val)
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Jet< T, N > pow(const Jet< T, N > &f, double g)
utility functions for loading datasets
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)