Skip to content

Commit

Permalink
Add files via upload
Browse files Browse the repository at this point in the history
  • Loading branch information
gitouni authored Sep 4, 2023
1 parent 3767f75 commit 09cc288
Show file tree
Hide file tree
Showing 5 changed files with 25 additions and 25 deletions.
12 changes: 6 additions & 6 deletions src/examples/floam_backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,14 +7,14 @@

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

auto option = BackEndOption();
YAML::Node config = YAML::LoadFile(yaml_file);
Expand Down
6 changes: 3 additions & 3 deletions src/examples/floam_kitti.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,10 @@ void writeKittiData(std::ofstream &fs, Eigen::Isometry3d &mat, bool end=false);
int main(int argc, char **argv)
{
argparse::ArgumentParser parser("floam_kitti");
parser.add_argument("--velo_dir").help("directory of velodyne pcd files").required();
parser.add_argument("--output").help("file to write output poses").required();
parser.add_argument("velo_dir").help("directory of velodyne pcd files").required();
parser.add_argument("output").help("file to write output poses").required();
parser.parse_args(argc, argv);
std::string velo_dir(parser.get<std::string>("--velo_dir")), res_file(parser.get<std::string>("--output"));
std::string velo_dir(parser.get<std::string>("velo_dir")), res_file(parser.get<std::string>("output"));
checkpath(velo_dir);
if(!file_exist(velo_dir)){
throw std::runtime_error("Velodyne Directory: "+velo_dir+" does not exsit.");
Expand Down
4 changes: 2 additions & 2 deletions src/examples/he_calib.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,9 @@
int main(int argc, char** argv)
{
argparse::ArgumentParser parser("Hand-eye Calib");
parser.add_argument("--config").help("config file for hand-eye calibration.").required();
parser.add_argument("config").help("config file for hand-eye calibration.").required();
parser.parse_args(argc, argv);
std::string config_file(parser.get<std::string>("--config"));
std::string config_file(parser.get<std::string>("config"));
YAML::Node config = YAML::LoadFile(config_file);
const YAML::Node &io_config = config["io"];
const YAML::Node &runtime_config = config["runtime"];
Expand Down
4 changes: 2 additions & 2 deletions src/examples/iba_global.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -406,9 +406,9 @@ class BALoss: public NOMAD::Evaluator

int main(int argc, char** argv){
argparse::ArgumentParser parser("global optimization");
parser.add_argument("--config").help("config_file").required();
parser.add_argument("config").help("config_file").required();
parser.parse_args(argc, argv);
std::string config_file(parser.get<std::string>("--config"));
std::string config_file(parser.get<std::string>("config"));
YAML::Node config = YAML::LoadFile(config_file);
const YAML::Node &io_config = config["io"];
const YAML::Node &orb_config = config["orb"];
Expand Down
24 changes: 12 additions & 12 deletions src/examples/orb_kitti_store.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,23 +80,23 @@ void visual_odometry(ORB_SLAM2::System* SLAM, double slow_rate, std::vector<Eige

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

std::string seq_dir(parser.get<std::string>("--seq_dir"));
std::string orb_yml(parser.get<std::string>("--orb_yaml"));
std::string orb_voc(parser.get<std::string>("--orb_voc"));
std::string TwcFile(parser.get<std::string>("--output_pose")); // output
std::string keyframe_dir(parser.get<std::string>("--keyframe_dir")); // output
std::string mapfile(parser.get<std::string>("--map_file"));
std::string seq_dir(parser.get<std::string>("seq_dir"));
std::string orb_yml(parser.get<std::string>("orb_yaml"));
std::string orb_voc(parser.get<std::string>("orb_voc"));
std::string TwcFile(parser.get<std::string>("output_pose")); // output
std::string keyframe_dir(parser.get<std::string>("keyframe_dir")); // output
std::string mapfile(parser.get<std::string>("map_file"));
double slow_rate = parser.get<double>("--slow_rate");
checkpath(seq_dir);
checkpath(keyframe_dir);
Expand Down

0 comments on commit 09cc288

Please sign in to comment.