use boost program_options for command line parsing
parent
4949f8bb9d
commit
a1f6e1585a
|
@ -29,12 +29,11 @@
|
||||||
* Note that for GPS correction, we're only using the position not the
|
* Note that for GPS correction, we're only using the position not the
|
||||||
* rotation. The rotation is provided in the file for ground truth comparison.
|
* rotation. The rotation is provided in the file for ground truth comparison.
|
||||||
*
|
*
|
||||||
* Usage: ./CombinedImuFactorsExample [data_csv_path] [-c]
|
* See usage: ./CombinedImuFactorsExample --help
|
||||||
* optional arguments:
|
|
||||||
* data_csv_path path to the CSV file with the IMU data.
|
|
||||||
* -c use CombinedImuFactor
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include <boost/program_options.hpp>
|
||||||
|
|
||||||
// GTSAM related includes.
|
// GTSAM related includes.
|
||||||
#include <gtsam/inference/Symbol.h>
|
#include <gtsam/inference/Symbol.h>
|
||||||
#include <gtsam/navigation/CombinedImuFactor.h>
|
#include <gtsam/navigation/CombinedImuFactor.h>
|
||||||
|
@ -56,6 +55,29 @@ using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz)
|
||||||
using symbol_shorthand::V; // Vel (xdot,ydot,zdot)
|
using symbol_shorthand::V; // Vel (xdot,ydot,zdot)
|
||||||
using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y)
|
using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y)
|
||||||
|
|
||||||
|
namespace po = boost::program_options;
|
||||||
|
|
||||||
|
po::variables_map parseOptions(int argc, char* argv[]) {
|
||||||
|
po::options_description desc;
|
||||||
|
desc.add_options()("help,h", "produce help message")(
|
||||||
|
"data_csv_path", po::value<string>()->default_value("imuAndGPSdata.csv"),
|
||||||
|
"path to the CSV file with the IMU data")(
|
||||||
|
"output_filename",
|
||||||
|
po::value<string>()->default_value("imuFactorExampleResults.csv"),
|
||||||
|
"path to the result file to use")("use_isam", po::bool_switch(),
|
||||||
|
"use ISAM as the optimizer");
|
||||||
|
|
||||||
|
po::variables_map vm;
|
||||||
|
po::store(po::parse_command_line(argc, argv, desc), vm);
|
||||||
|
|
||||||
|
if (vm.count("help")) {
|
||||||
|
cout << desc << "\n";
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
return vm;
|
||||||
|
}
|
||||||
|
|
||||||
Vector10 readInitialState(ifstream& file) {
|
Vector10 readInitialState(ifstream& file) {
|
||||||
string value;
|
string value;
|
||||||
// Format is (N,E,D,qX,qY,qZ,qW,velN,velE,velD)
|
// Format is (N,E,D,qX,qY,qZ,qW,velN,velE,velD)
|
||||||
|
@ -106,17 +128,10 @@ boost::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() {
|
||||||
|
|
||||||
int main(int argc, char* argv[]) {
|
int main(int argc, char* argv[]) {
|
||||||
string data_filename, output_filename;
|
string data_filename, output_filename;
|
||||||
if (argc == 3) {
|
po::variables_map var_map = parseOptions(argc, argv);
|
||||||
data_filename = argv[1];
|
|
||||||
output_filename = argv[2];
|
data_filename = findExampleDataFile(var_map["data_csv_path"].as<string>());
|
||||||
} else if (argc == 2) {
|
output_filename = var_map["output_filename"].as<string>();
|
||||||
data_filename = argv[1];
|
|
||||||
output_filename = "imuFactorExampleResults.csv";
|
|
||||||
} else {
|
|
||||||
printf("using default CSV file\n");
|
|
||||||
data_filename = findExampleDataFile("imuAndGPSdata.csv");
|
|
||||||
output_filename = "imuFactorExampleResults.csv";
|
|
||||||
}
|
|
||||||
|
|
||||||
// Set up output file for plotting errors
|
// Set up output file for plotting errors
|
||||||
FILE* fp_out = fopen(output_filename.c_str(), "w+");
|
FILE* fp_out = fopen(output_filename.c_str(), "w+");
|
||||||
|
@ -265,7 +280,8 @@ int main(int argc, char* argv[]) {
|
||||||
|
|
||||||
// display statistics
|
// display statistics
|
||||||
cout << "Position error:" << current_position_error << "\t "
|
cout << "Position error:" << current_position_error << "\t "
|
||||||
<< "Angular error:" << current_orientation_error << "\n" << endl;
|
<< "Angular error:" << current_orientation_error << "\n"
|
||||||
|
<< endl;
|
||||||
|
|
||||||
fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n",
|
fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n",
|
||||||
output_time, result_position(0), result_position(1),
|
output_time, result_position(0), result_position(1),
|
||||||
|
|
|
@ -31,14 +31,11 @@
|
||||||
* Note that for GPS correction, we're only using the position not the
|
* Note that for GPS correction, we're only using the position not the
|
||||||
* rotation. The rotation is provided in the file for ground truth comparison.
|
* rotation. The rotation is provided in the file for ground truth comparison.
|
||||||
*
|
*
|
||||||
* Usage: ./ImuFactorsExample [data_csv_path] [-c]
|
* See usage: ./ImuFactorsExample --help
|
||||||
* optional arguments:
|
|
||||||
* data_csv_path path to the CSV file with the IMU data.
|
|
||||||
* -c use CombinedImuFactor
|
|
||||||
* Note: Define USE_LM to use Levenberg Marquardt Optimizer
|
|
||||||
* By default ISAM2 is used
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include <boost/program_options.hpp>
|
||||||
|
|
||||||
// GTSAM related includes.
|
// GTSAM related includes.
|
||||||
#include <gtsam/inference/Symbol.h>
|
#include <gtsam/inference/Symbol.h>
|
||||||
#include <gtsam/navigation/CombinedImuFactor.h>
|
#include <gtsam/navigation/CombinedImuFactor.h>
|
||||||
|
@ -54,9 +51,6 @@
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
|
||||||
// Uncomment the following to use Levenberg Marquardt Optimizer
|
|
||||||
// #define USE_LM
|
|
||||||
|
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
|
@ -64,6 +58,29 @@ using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz)
|
||||||
using symbol_shorthand::V; // Vel (xdot,ydot,zdot)
|
using symbol_shorthand::V; // Vel (xdot,ydot,zdot)
|
||||||
using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y)
|
using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y)
|
||||||
|
|
||||||
|
namespace po = boost::program_options;
|
||||||
|
|
||||||
|
po::variables_map parseOptions(int argc, char* argv[]) {
|
||||||
|
po::options_description desc;
|
||||||
|
desc.add_options()("help,h", "produce help message")(
|
||||||
|
"data_csv_path", po::value<string>()->default_value("imuAndGPSdata.csv"),
|
||||||
|
"path to the CSV file with the IMU data")(
|
||||||
|
"output_filename",
|
||||||
|
po::value<string>()->default_value("imuFactorExampleResults.csv"),
|
||||||
|
"path to the result file to use")("use_isam", po::bool_switch(),
|
||||||
|
"use ISAM as the optimizer");
|
||||||
|
|
||||||
|
po::variables_map vm;
|
||||||
|
po::store(po::parse_command_line(argc, argv, desc), vm);
|
||||||
|
|
||||||
|
if (vm.count("help")) {
|
||||||
|
cout << desc << "\n";
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
return vm;
|
||||||
|
}
|
||||||
|
|
||||||
boost::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() {
|
boost::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() {
|
||||||
// We use the sensor specs to build the noise model for the IMU factor.
|
// We use the sensor specs to build the noise model for the IMU factor.
|
||||||
double accel_noise_sigma = 0.0003924;
|
double accel_noise_sigma = 0.0003924;
|
||||||
|
@ -102,22 +119,11 @@ int main(int argc, char* argv[]) {
|
||||||
|
|
||||||
bool use_isam = false;
|
bool use_isam = false;
|
||||||
|
|
||||||
if (argc == 4) {
|
po::variables_map var_map = parseOptions(argc, argv);
|
||||||
data_filename = argv[1];
|
|
||||||
output_filename = argv[2];
|
|
||||||
use_isam = atoi(argv[3]);
|
|
||||||
|
|
||||||
} else if (argc == 3) {
|
data_filename = findExampleDataFile(var_map["data_csv_path"].as<string>());
|
||||||
data_filename = argv[1];
|
output_filename = var_map["output_filename"].as<string>();
|
||||||
output_filename = argv[2];
|
use_isam = var_map["use_isam"].as<bool>();
|
||||||
} else if (argc == 2) {
|
|
||||||
data_filename = argv[1];
|
|
||||||
output_filename = "imuFactorExampleResults.csv";
|
|
||||||
} else {
|
|
||||||
printf("using default files\n");
|
|
||||||
data_filename = findExampleDataFile("imuAndGPSdata.csv");
|
|
||||||
output_filename = "imuFactorExampleResults.csv";
|
|
||||||
}
|
|
||||||
|
|
||||||
ISAM2* isam2;
|
ISAM2* isam2;
|
||||||
if (use_isam) {
|
if (use_isam) {
|
||||||
|
|
Loading…
Reference in New Issue