Skip to content

Commit 3767f75

Browse files
authored
Add files via upload
1 parent 3a97ed2 commit 3767f75

File tree

5 files changed

+63
-53
lines changed

5 files changed

+63
-53
lines changed

src/examples/floam_backend.cpp

Lines changed: 13 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -2,15 +2,19 @@
22
#include "io_tools.h"
33
#include "kitti_tools.h"
44
#include <yaml-cpp/yaml.h>
5+
#include "argparse.hpp"
6+
57

68
int main(int argc, char** argv){
7-
if(argc < 4){
8-
std::cerr << "Expected args: yaml pose_txt Lidar_dir" << std::endl;
9-
}
10-
std::string yaml_file(argv[1]);
9+
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();
13+
parser.parse_args(argc, argv);
14+
std::string yaml_file(parser.get<std::string>("--config"));
1115
assert(file_exist(yaml_file));
12-
std::string input_pose_file(argv[2]);
13-
std::string input_lidar_dir(argv[3]);
16+
std::string input_pose_file(parser.get<std::string>("--raw_pose"));
17+
std::string input_lidar_dir(parser.get<std::string>("--velo_dir"));
1418

1519
auto option = BackEndOption();
1620
YAML::Node config = YAML::LoadFile(yaml_file);
@@ -58,12 +62,13 @@ int main(int argc, char** argv){
5862
optimizer.writePoses(output_isam_poses);
5963
std::cout << "isam optimized poses saved to " << output_isam_poses << std::endl;
6064
// *** Results of ISAM and Multway are too similar! ***
61-
if(use_multiway){
65+
if(use_multiway)
66+
{
6267
optimizer.MultiRegistration(odom_refine);
6368
optimizer.writePoseGraph(output_pose_graph);
6469
optimizer.UpdatePosesFromPG();
6570
optimizer.writePoses(output_mr_poses);
6671
}
67-
if(save_map){}
72+
if(save_map)
6873
optimizer.SaveMap(map_path);
6974
}

src/examples/floam_kitti.cpp

Lines changed: 10 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -4,30 +4,25 @@
44
#include <vector>
55
#include <string>
66
#include <iostream>
7-
7+
#include "argparse.hpp"
88

99
template <typename PointType>
1010
bool readPointCloud(pcl::PointCloud<PointType> &point_cloud, const std::string filename);
1111

1212
void writeKittiData(std::ofstream &fs, Eigen::Isometry3d &mat, bool end=false);
1313

14-
int main(int argc, char **argv){
15-
std::string velo_dir, res_file;
16-
std::vector<std::string> velo_files;
17-
if(argc < 3){
18-
std::cout << "\033[31;1m Got " << argc-1 << " Parameters, expect 2.\033[0m" << std::endl;
19-
throw std::invalid_argument("Expected args: kitti_velodyne_dir output_pose_file");
20-
return -1;
21-
}
22-
else
23-
{
24-
velo_dir.assign(argv[1]);
25-
res_file.assign(argv[2]);
26-
}
27-
checkpath(velo_dir);
14+
int main(int argc, char **argv)
15+
{
16+
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();
19+
parser.parse_args(argc, argv);
20+
std::string velo_dir(parser.get<std::string>("--velo_dir")), res_file(parser.get<std::string>("--output"));
21+
checkpath(velo_dir);
2822
if(!file_exist(velo_dir)){
2923
throw std::runtime_error("Velodyne Directory: "+velo_dir+" does not exsit.");
3024
}; // velodyne/ must exist
25+
std::vector<std::string> velo_files;
3126
listdir(velo_files,velo_dir);
3227
std::cout << "Found " << velo_files.size() << " velodyne files." << std::endl;
3328
std::ofstream res_stream(res_file.c_str(), std::ios::ate); // write mode | ASCII mode

src/examples/he_calib.cpp

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -7,13 +7,14 @@
77
#include "HECalib.h"
88
#include "NLHECalib.hpp"
99
#include "kitti_tools.h"
10+
#include "argparse.hpp"
1011

11-
int main(int argc, char** argv){
12-
if(argc < 2){
13-
std::cerr << "Got " << argc - 1 << " Parameters, but Expected parameters: yaml_file" << std::endl;
14-
exit(0);
15-
}
16-
std::string config_file(argv[1]);
12+
int main(int argc, char** argv)
13+
{
14+
argparse::ArgumentParser parser("Hand-eye Calib");
15+
parser.add_argument("--config").help("config file for hand-eye calibration.").required();
16+
parser.parse_args(argc, argv);
17+
std::string config_file(parser.get<std::string>("--config"));
1718
YAML::Node config = YAML::LoadFile(config_file);
1819
const YAML::Node &io_config = config["io"];
1920
const YAML::Node &runtime_config = config["runtime"];

src/examples/iba_global.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
#include "Nomad/nomad.hpp"
1414
#include "Cache/CacheBase.hpp"
1515
#include <unordered_map>
16+
#include "argparse.hpp"
1617

1718
typedef std::uint32_t IndexType; // other types cause error, why?
1819
typedef std::vector<IndexType> VecIndex;
@@ -404,11 +405,10 @@ class BALoss: public NOMAD::Evaluator
404405
};
405406

406407
int main(int argc, char** argv){
407-
if(argc < 2){
408-
std::cerr << "Require config_yaml arg" << std::endl;
409-
exit(0);
410-
}
411-
std::string config_file(argv[1]);
408+
argparse::ArgumentParser parser("global optimization");
409+
parser.add_argument("--config").help("config_file").required();
410+
parser.parse_args(argc, argv);
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: 28 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
#include <chrono>
88
#include <fstream>
99
#include <limits>
10+
#include "argparse.hpp"
1011

1112
void check_exist(std::string &file){
1213
if(!file_exist(file)){
@@ -30,7 +31,7 @@ void writeData(std::string &outfile, std::vector<Eigen::Isometry3d> Tlist){
3031
of.close();
3132
}
3233

33-
void visual_odometry(ORB_SLAM2::System* SLAM, std::vector<Eigen::Isometry3d> &Twc_list,
34+
void visual_odometry(ORB_SLAM2::System* SLAM, double slow_rate, std::vector<Eigen::Isometry3d> &Twc_list,
3435
std::vector<std::size_t> &vKFFrameId, std::vector<std::string> &vstrImageFilename, std::vector<double> &vtimestamp,
3536
const std::string &KeyFrameDir, const std::string &MapFile)
3637
{
@@ -41,9 +42,7 @@ void visual_odometry(ORB_SLAM2::System* SLAM, std::vector<Eigen::Isometry3d> &Tw
4142
double tframe = vtimestamp[i];
4243
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
4344
SLAM->TrackMonocular(img, vtimestamp[i]);
44-
char msg[100];
45-
sprintf(msg, "\033[033;1m[VO]\033[0m Frame %ld | %ld", i+1, vstrImageFilename.size());
46-
std::cout << msg << std::endl;
45+
std::printf("\033[033;1m[VO]\033[0m Frame %ld | %ld STATE: %d\n", i+1, vstrImageFilename.size(), SLAM->GetTrackingState());
4746
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
4847
double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
4948
double T=0;
@@ -52,8 +51,8 @@ void visual_odometry(ORB_SLAM2::System* SLAM, std::vector<Eigen::Isometry3d> &Tw
5251
else if(i>0)
5352
T = tframe-vtimestamp[i-1];
5453

55-
if(ttrack<T){
56-
usleep(1e6*(T-ttrack));
54+
if(ttrack<T*slow_rate){
55+
usleep(1.0E6*(T*slow_rate-ttrack));
5756
}
5857
}catch(const std::exception &e){
5958
std::cout << "Visual Odometry Fatal Error: " << e.what() << std::endl;
@@ -80,24 +79,34 @@ void visual_odometry(ORB_SLAM2::System* SLAM, std::vector<Eigen::Isometry3d> &Tw
8079
}
8180

8281
int main(int argc, char** argv){
83-
if(argc < 7){
84-
std::cout << "\033[31;1m Expected args: kitti_seq_dir orb_setting_file orb_vocabulary_file TwcFile KeyFrameDir MapFile.\033[0m" << std::endl;
85-
return -1;
86-
}
82+
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();
89+
parser.add_argument("--slow_rate").help("slow rate of runtime").scan<'g',double>().default_value(1.5);
90+
parser.add_argument("--img_dir").help("relative directory of images").default_value("image_0/");
91+
parser.add_argument("--timefile").help("timestamp file").default_value("times.txt");
92+
parser.parse_args(argc, argv);
8793

88-
std::string seq_dir = argv[1];
89-
std::string orb_yml = argv[2];
90-
std::string orb_voc = argv[3];
91-
std::string TwcFile = argv[4]; // output
92-
std::string keyframe_dir = argv[5]; // output
93-
std::string mapfile = argv[6];
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"));
100+
double slow_rate = parser.get<double>("--slow_rate");
94101
checkpath(seq_dir);
95102
checkpath(keyframe_dir);
96103
check_exist(seq_dir);
97104
check_exist(orb_yml);
98105
check_exist(orb_voc);
99-
std::string img_dir = seq_dir + "image_0/";
100-
std::string timefile = seq_dir + "times.txt";
106+
std::string img_dir = seq_dir + parser.get<std::string>("--img_dir");
107+
checkpath(img_dir);
108+
check_exist(img_dir);
109+
std::string timefile = seq_dir + parser.get<std::string>("--timefile");
101110
std::vector<std::string> vImageFiles;
102111
std::vector<double> vTimeStamps;
103112
LoadTimestamp(timefile, vTimeStamps);
@@ -113,7 +122,7 @@ int main(int argc, char** argv){
113122
std::vector<Eigen::Isometry3d> vTwc;
114123
std::vector<std::size_t> vKFFrameId;
115124
vTwc.reserve(vImageFiles.size());
116-
visual_odometry(orbSLAM, std::ref(vTwc), std::ref(vKFFrameId), std::ref(vImageFiles), std::ref(vTimeStamps), std::ref(keyframe_dir), mapfile);
125+
visual_odometry(orbSLAM, slow_rate, std::ref(vTwc), std::ref(vKFFrameId), std::ref(vImageFiles), std::ref(vTimeStamps), std::ref(keyframe_dir), mapfile);
117126
std::cout << "Total visual Frames: " << vTwc.size() << ", Key Frames: " << vKFFrameId.size() << std::endl;
118127
writeData(TwcFile, vTwc);
119128

0 commit comments

Comments
 (0)