77#include < chrono>
88#include < fstream>
99#include < limits>
10+ #include " argparse.hpp"
1011
1112void 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
8281int 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