4 #include <visp3/core/vpConfig.h> 5 #include <visp3/core/vpIoTools.h> 6 #include <visp3/mbt/vpMbGenericTracker.h> 9 po::options_description general(
"General options");
12 (
"dmtxonly,d",
"only detect the datamatrix")
13 (
"video-camera,C",
"video from camera")
15 (
"data-directory,D", po::value<std::string>(&
data_dir_)->default_value(
"./data/"),
"directory from which to load images")
16 (
"video-input-path,J", po::value<std::string>(&
input_file_pattern_)->default_value(
"/images/%08d.jpg"),
"input video file path relative to the data directory")
17 (
"video-output-path,L", po::value<std::string>(&
log_file_pattern_),
"output video file path relative to the data directory")
18 (
"single-image,I", po::value<std::string>(&
single_image_name_),
"load this single image (relative to data dir)")
19 (
"pattern-name,P", po::value<std::string>(&
pattern_name_)->default_value(
"pattern"),
"name of xml,init and wrl files")
20 (
"detector-type,r", po::value<std::string>()->default_value(
"zbar"),
"Type of your detector that will be used for initialisation/recovery. zbar for QRcodes and more, dmtx for flashcodes.")
21 (
"tracker-type,t", po::value<std::string>()->default_value(
"klt_mbt"),
"Type of tracker. mbt_klt for hybrid: mbt+klt, mbt for model based, klt for klt-based")
22 (
"verbose,v", po::value< bool >(&
verbose_)->default_value(
false)->composing(),
"Enable or disable additional printings")
23 (
"dmx-detector-timeout,T", po::value<int>(&
dmx_timeout_)->default_value(1000),
"timeout for datamatrix detection in ms")
24 (
"config-file,c", po::value<std::string>(&
config_file)->default_value(
"./data/config.cfg"),
"config file for the program")
25 (
"show-fps,f", po::value< bool >(&
show_fps_)->default_value(
false)->composing(),
"show framerate")
26 (
"show-plot,p", po::value< bool >(&
show_plot_)->default_value(
false)->composing(),
"show variances graph")
27 (
"code-message,m", po::value<std::string>(&
code_message_)->default_value(
""),
"Target code message")
29 (
"help",
"produce help message")
32 po::options_description configuration(
"Configuration");
33 configuration.add_options()
34 (
"flashcode-coordinates,F",
36 "3D coordinates of the flashcode in clockwise order")
37 (
"inner-coordinates,i",
39 "3D coordinates of the inner region in clockwise order")
40 (
"outer-coordinates,o",
42 "3D coordinates of the outer region in clockwise order")
43 (
"variance-file,V", po::value< std::string >(&
var_file_)->composing(),
"file to store variance values")
44 (
"variance-limit,l", po::value< double >(&
var_limit_)->composing(),
45 "above this limit the tracker will be considered lost and the pattern will be detected with the flascode")
47 "when a new model is detected, how many tracking iterations should the tracker perform so the model matches the projection.")
49 po::value< std::vector<double> >(&
hinkley_range_)->multitoken()->composing(),
50 "pair of alpha, delta values describing the two hinkley tresholds")
52 "Adapt mbt range to symbol size. The width of the outer black corner is multiplied by this value to get the mbt range. Try 0.2")
53 (
"ad-hoc-recovery,W", po::value< bool >(&
adhoc_recovery_)->default_value(
true)->composing(),
"Enable or disable ad-hoc recovery")
54 (
"ad-hoc-recovery-display,D", po::value< bool >(&
adhoc_recovery_display_)->default_value(
false)->composing(),
"Enable or disable ad-hoc recovery display")
55 (
"ad-hoc-recovery-ratio,y", po::value< double >(&
adhoc_recovery_ratio_)->default_value(0.5)->composing(),
56 "use ad-hoc recovery based on the model. The tracker will look for black pixels at ratio*[pattern size] from the center")
57 (
"ad-hoc-recovery-size,w", po::value< double >(&
adhoc_recovery_size_)->default_value(0.5)->composing(),
58 "fraction of the black outer band size. The control points (those that should be black and in that way check tracking is still there).")
59 (
"ad-hoc-recovery-threshold,Y", po::value< unsigned int >(&
adhoc_recovery_treshold_)->default_value(100)->composing(),
60 "Threshold over which the point is considered out of the black area of the object")
61 (
"log-checkpoints,g",
"log checkpoints in the log file")
62 (
"log-pose,q", po::value< bool >(&
log_pose_)->
default_value(
false)->composing(),
"log pose in the log file")
68 std::ifstream in( config_file.c_str() );
69 po::store(po::parse_config_file(in,
prog_args,
false),
vm_);
93 std::cout <<
"Tracker set to:";
96 std::cout <<
"model based tracker";
99 std::cout <<
"hybrid (mbt+klt)";
102 std::cout <<
"tracker with klt points";
105 std::cout << std::endl;
107 std::cout <<
"Detector set to:";
110 std::cout <<
"QR code";
113 std::cout <<
"Datamatrix (flashcode)";
116 std::cout << std::endl;
121 std::cout <<
"Using variance file:" <<
get_var_file() << std::endl;
122 if (
vm_.count(
"help")) {
145 po::store(po::parse_command_line(argc, argv,
prog_args),
vm_);
148 std::cout <<
"Loading config from:" <<
config_file << std::endl;
155 vpCameraParameters cam;
156 vpMbEdgeTracker tmptrack;
158 tmptrack.getCameraParameters(cam);
180 throw std::exception();
186 throw std::exception();
199 return vm_.count(
"mbt-dynamic-range")>0;
207 return vm_.count(
"variance-limit")>0;
215 return vm_.count(
"variance-file")>0;
219 return vm_.count(
"video-output-path")>0;
223 return vm_.count(
"dmtxonly")>0;
255 return vm_.count(
"data-directory")>0;
259 return vm_.count(
"video-camera")>0;
288 return vm_.count(
"single-image")>0;
308 if(
vm_[
"detector-type"].as<std::string>()==
"zbar")
315 if(
vm_[
"tracker-type"].as<std::string>()==
"mbt")
317 else if(
vm_[
"tracker-type"].as<std::string>()==
"klt")
352 return vm_.count(
"log-checkpoints")>0;
std::vector< vpPoint > & get_flashcode_points_3D()
std::string get_code_message() const
std::string input_file_pattern_
std::vector< vpPoint > inner_points_3D_
size_t get_code_message_index() const
bool using_var_file() const
std::string video_channel_
std::string get_pattern_name() const
int get_dmx_timeout() const
unsigned int adhoc_recovery_treshold_
bool adhoc_recovery_display_
int mbt_convergence_steps_
std::string single_image_name_
double get_var_limit() const
std::string get_input_file_pattern() const
std::string code_message_
unsigned int get_adhoc_recovery_treshold() const
std::vector< vpPoint > & get_inner_points_3D()
std::string get_xml_file() const
void init(std::string &config_file)
double adhoc_recovery_ratio_
bool using_adhoc_recovery() const
std::vector< double > outer_coordinates
double get_adhoc_recovery_ratio() const
bool using_data_dir() const
po::options_description prog_args
std::vector< vpPoint > outer_points_3D_
bool logging_video() const
bool using_hinkley() const
double mbt_dynamic_range_
std::string pattern_name_
boost::program_options::variables_map vm_
bool using_mbt_dynamic_range()
std::string get_video_channel() const
bool log_checkpoints() const
bool get_adhoc_recovery_display() const
std::string log_file_pattern_
std::string get_single_image_path() const
void set_pattern_name(std::string &name)
double adhoc_recovery_size_
std::vector< vpPoint > flashcode_points_3D_
void set_code_message_index(const size_t &index)
double get_inner_ratio() const
int get_mbt_convergence_steps() const
void set_show_fps(bool show_fps)
double get_outer_ratio() const
vpCameraParameters get_cam_calib_params() const
std::string get_init_file() const
void set_data_directory(std::string &dir)
bool using_var_limit() const
std::string get_data_dir() const
double get_hinkley_alpha() const
std::vector< double > inner_coordinates
double get_mbt_dynamic_range() const
std::vector< double > flashcode_coordinates
std::string get_log_file_pattern() const
TRACKER_TYPE get_tracker_type() const
double get_hinkley_delta() const
void loadConfig(std::string &config_file)
double get_adhoc_recovery_size() const
bool using_video_camera() const
std::vector< double > hinkley_range_
std::string get_var_file() const
void set_code_message(const std::string &msg)
std::vector< vpPoint > & get_outer_points_3D()
DETECTOR_TYPE get_detector_type() const
bool using_single_image() const
std::string get_mbt_cad_file() const