Skip to content

Commit 09cc288

Browse files
authored
Add files via upload
1 parent 3767f75 commit 09cc288

File tree

5 files changed

+25
-25
lines changed

5 files changed

+25
-25
lines changed

src/examples/floam_backend.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -7,14 +7,14 @@
77

88
int main(int argc, char** argv){
99
argparse::ArgumentParser parser("Back-end optimization of F-LOAM");
10-
parser.add_argument("--config").help("config file").required();
11-
parser.add_argument("--raw_pose").help("raw pose of the F-LOAM").required();
12-
parser.add_argument("--velo_dir").help("directory of velodyne pcd files").required();
10+
parser.add_argument("config").help("config file").required();
11+
parser.add_argument("raw_pose").help("raw pose of the F-LOAM").required();
12+
parser.add_argument("velo_dir").help("directory of velodyne pcd files").required();
1313
parser.parse_args(argc, argv);
14-
std::string yaml_file(parser.get<std::string>("--config"));
14+
std::string yaml_file(parser.get<std::string>("config"));
1515
assert(file_exist(yaml_file));
16-
std::string input_pose_file(parser.get<std::string>("--raw_pose"));
17-
std::string input_lidar_dir(parser.get<std::string>("--velo_dir"));
16+
std::string input_pose_file(parser.get<std::string>("raw_pose"));
17+
std::string input_lidar_dir(parser.get<std::string>("velo_dir"));
1818

1919
auto option = BackEndOption();
2020
YAML::Node config = YAML::LoadFile(yaml_file);

src/examples/floam_kitti.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -14,10 +14,10 @@ void writeKittiData(std::ofstream &fs, Eigen::Isometry3d &mat, bool end=false);
1414
int main(int argc, char **argv)
1515
{
1616
argparse::ArgumentParser parser("floam_kitti");
17-
parser.add_argument("--velo_dir").help("directory of velodyne pcd files").required();
18-
parser.add_argument("--output").help("file to write output poses").required();
17+
parser.add_argument("velo_dir").help("directory of velodyne pcd files").required();
18+
parser.add_argument("output").help("file to write output poses").required();
1919
parser.parse_args(argc, argv);
20-
std::string velo_dir(parser.get<std::string>("--velo_dir")), res_file(parser.get<std::string>("--output"));
20+
std::string velo_dir(parser.get<std::string>("velo_dir")), res_file(parser.get<std::string>("output"));
2121
checkpath(velo_dir);
2222
if(!file_exist(velo_dir)){
2323
throw std::runtime_error("Velodyne Directory: "+velo_dir+" does not exsit.");

src/examples/he_calib.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,9 @@
1212
int main(int argc, char** argv)
1313
{
1414
argparse::ArgumentParser parser("Hand-eye Calib");
15-
parser.add_argument("--config").help("config file for hand-eye calibration.").required();
15+
parser.add_argument("config").help("config file for hand-eye calibration.").required();
1616
parser.parse_args(argc, argv);
17-
std::string config_file(parser.get<std::string>("--config"));
17+
std::string config_file(parser.get<std::string>("config"));
1818
YAML::Node config = YAML::LoadFile(config_file);
1919
const YAML::Node &io_config = config["io"];
2020
const YAML::Node &runtime_config = config["runtime"];

src/examples/iba_global.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -406,9 +406,9 @@ class BALoss: public NOMAD::Evaluator
406406

407407
int main(int argc, char** argv){
408408
argparse::ArgumentParser parser("global optimization");
409-
parser.add_argument("--config").help("config_file").required();
409+
parser.add_argument("config").help("config_file").required();
410410
parser.parse_args(argc, argv);
411-
std::string config_file(parser.get<std::string>("--config"));
411+
std::string config_file(parser.get<std::string>("config"));
412412
YAML::Node config = YAML::LoadFile(config_file);
413413
const YAML::Node &io_config = config["io"];
414414
const YAML::Node &orb_config = config["orb"];

src/examples/orb_kitti_store.cpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -80,23 +80,23 @@ void visual_odometry(ORB_SLAM2::System* SLAM, double slow_rate, std::vector<Eige
8080

8181
int main(int argc, char** argv){
8282
argparse::ArgumentParser parser("ORB-SLAM with Keyframes storation process");
83-
parser.add_argument("--seq_dir").help("parent directory of the directory of image files.").required();
84-
parser.add_argument("--orb_yaml").help("directory of ORB yaml files").required();
85-
parser.add_argument("--orb_voc").help("Vocabulary file of DBoW2/DBow3").required();
86-
parser.add_argument("--output_pose").help("--directory to save poses of Keyframes.").required();
87-
parser.add_argument("--keyframe_dir").help("--directory to save information of KeyFrames").required();
88-
parser.add_argument("--map_file").help("--directory to save visual map").required();
83+
parser.add_argument("seq_dir").help("parent directory of the directory of image files.").required();
84+
parser.add_argument("orb_yaml").help("directory of ORB yaml files").required();
85+
parser.add_argument("orb_voc").help("Vocabulary file of DBoW2/DBow3").required();
86+
parser.add_argument("output_pose").help("--directory to save poses of Keyframes.").required();
87+
parser.add_argument("keyframe_dir").help("--directory to save information of KeyFrames").required();
88+
parser.add_argument("map_file").help("--directory to save visual map").required();
8989
parser.add_argument("--slow_rate").help("slow rate of runtime").scan<'g',double>().default_value(1.5);
9090
parser.add_argument("--img_dir").help("relative directory of images").default_value("image_0/");
9191
parser.add_argument("--timefile").help("timestamp file").default_value("times.txt");
9292
parser.parse_args(argc, argv);
9393

94-
std::string seq_dir(parser.get<std::string>("--seq_dir"));
95-
std::string orb_yml(parser.get<std::string>("--orb_yaml"));
96-
std::string orb_voc(parser.get<std::string>("--orb_voc"));
97-
std::string TwcFile(parser.get<std::string>("--output_pose")); // output
98-
std::string keyframe_dir(parser.get<std::string>("--keyframe_dir")); // output
99-
std::string mapfile(parser.get<std::string>("--map_file"));
94+
std::string seq_dir(parser.get<std::string>("seq_dir"));
95+
std::string orb_yml(parser.get<std::string>("orb_yaml"));
96+
std::string orb_voc(parser.get<std::string>("orb_voc"));
97+
std::string TwcFile(parser.get<std::string>("output_pose")); // output
98+
std::string keyframe_dir(parser.get<std::string>("keyframe_dir")); // output
99+
std::string mapfile(parser.get<std::string>("map_file"));
100100
double slow_rate = parser.get<double>("--slow_rate");
101101
checkpath(seq_dir);
102102
checkpath(keyframe_dir);

0 commit comments

Comments
 (0)