@@ -80,23 +80,23 @@ void visual_odometry(ORB_SLAM2::System* SLAM, double slow_rate, std::vector<Eige
8080
8181int 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