cmd_line.cpp
Go to the documentation of this file.
1 #include "cmd_line.h"
2 #include <iostream>
3 #include <fstream>
4 #include <visp3/core/vpConfig.h>
5 #include <visp3/core/vpIoTools.h>
6 #include <visp3/mbt/vpMbGenericTracker.h>
7 
9  po::options_description general("General options");
10 
11  general.add_options()
12  ("dmtxonly,d", "only detect the datamatrix")
13  ("video-camera,C", "video from camera")
14  ("video-source,s", po::value<std::string>(&video_channel_)->default_value("/dev/video1"),"video source. For example /dev/video1")
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")
28 
29  ("help", "produce help message")
30  ;
31 
32  po::options_description configuration("Configuration");
33  configuration.add_options()
34  ("flashcode-coordinates,F",
35  po::value< std::vector<double> >(&flashcode_coordinates)->multitoken()->composing(),
36  "3D coordinates of the flashcode in clockwise order")
37  ("inner-coordinates,i",
38  po::value< std::vector<double> >(&inner_coordinates)->multitoken()->composing(),
39  "3D coordinates of the inner region in clockwise order")
40  ("outer-coordinates,o",
41  po::value< std::vector<double> >(&outer_coordinates)->multitoken()->composing(),
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")
46  ("mbt-convergence-steps,S", po::value< int >(&mbt_convergence_steps_)->default_value(1)->composing(),
47  "when a new model is detected, how many tracking iterations should the tracker perform so the model matches the projection.")
48  ("hinkley-range,H",
49  po::value< std::vector<double> >(&hinkley_range_)->multitoken()->composing(),
50  "pair of alpha, delta values describing the two hinkley tresholds")
51  ("mbt-dynamic-range,R", po::value< double >(&mbt_dynamic_range_)->composing(),
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")
63  ;
64  prog_args.add(general);
65  prog_args.add(configuration);
66 }
67 void CmdLine::loadConfig(std::string& config_file){
68  std::ifstream in( config_file.c_str() );
69  po::store(po::parse_config_file(in,prog_args,false), vm_);
70  po::notify(vm_);
71  in.close();
72 
73  for(unsigned int i =0;i<flashcode_coordinates.size()/3;i++){
74  vpPoint p;
75  p.setWorldCoordinates(flashcode_coordinates[i*3],flashcode_coordinates[i*3+1],flashcode_coordinates[i*3+2]);
76  flashcode_points_3D_.push_back(p);
77  }
78 
79  for(unsigned int i =0;i<inner_coordinates.size()/3;i++){
80  vpPoint p;
81  p.setWorldCoordinates(inner_coordinates[i*3],inner_coordinates[i*3+1],inner_coordinates[i*3+2]);
82  inner_points_3D_.push_back(p);
83  }
84 
85  for(unsigned int i =0;i<outer_coordinates.size()/3;i++){
86  vpPoint p;
87  p.setWorldCoordinates(outer_coordinates[i*3],outer_coordinates[i*3+1],outer_coordinates[i*3+2]);
88  outer_points_3D_.push_back(p);
89  }
90 
91  if(get_verbose()){
92  std::cout << "Loaded " << flashcode_points_3D_.size() << " flashcode extremity points, " << inner_points_3D_.size() << " inner contour points and " << outer_points_3D_.size() << " outer contour points." << std::endl;
93  std::cout << "Tracker set to:";
94  switch(get_tracker_type()){
95  case MBT:
96  std::cout << "model based tracker";
97  break;
98  case KLT_MBT:
99  std::cout << "hybrid (mbt+klt)";
100  break;
101  case KLT:
102  std::cout << "tracker with klt points";
103  break;
104  }
105  std::cout << std::endl;
106 
107  std::cout << "Detector set to:";
108  switch(get_detector_type()){
109  case ZBAR:
110  std::cout << "QR code";
111  break;
112  case DMTX:
113  std::cout << "Datamatrix (flashcode)";
114  break;
115  }
116  std::cout << std::endl;
117 
118  }
119 
120  if(using_var_file())
121  std::cout << "Using variance file:" << get_var_file() << std::endl;
122  if (vm_.count("help")) {
123  std::cout << prog_args << std::endl;
124  should_exit_ = true;
125 
126  }
127 }
129  this->config_file = config_file;
130  common();
131  loadConfig(config_file);
132 }
134 }
135 void CmdLine:: init(std::string& config_file)
136 {
137  this->config_file = config_file;
138  common();
139  loadConfig(config_file);
140 }
141 
142 CmdLine:: CmdLine(int argc,char**argv) : should_exit_(false), code_message_index_(0) {
143  common();
144 
145  po::store(po::parse_command_line(argc, argv, prog_args), vm_);
146  po::notify(vm_);
147  if(get_verbose())
148  std::cout << "Loading config from:" << config_file << std::endl;
149 
151 
152 }
153 
154 vpCameraParameters CmdLine::get_cam_calib_params() const{
155  vpCameraParameters cam;
156  vpMbEdgeTracker tmptrack;
157  tmptrack.loadConfigFile(get_xml_file() ); // Load the configuration of the tracker
158  tmptrack.getCameraParameters(cam);
159  return cam;
160 }
161 
162 std::string CmdLine::get_log_file_pattern() const{
163  return log_file_pattern_;
164 }
165 
167  return input_file_pattern_;
168 }
169 
170 bool CmdLine:: show_plot() const{
171  return show_plot_;
172 }
173 
175  return vm_.count("hinkley-range")>0 && hinkley_range_.size()==2;
176 }
177 
179  if(!using_hinkley())
180  throw std::exception();
181  return hinkley_range_[0];
182 }
183 
185  if(!using_hinkley())
186  throw std::exception();
187  return hinkley_range_[1];
188 }
189 
191  return mbt_convergence_steps_;
192 }
193 
195  return mbt_dynamic_range_;
196 }
197 
199  return vm_.count("mbt-dynamic-range")>0;
200 }
201 
202 double CmdLine:: get_var_limit() const{
203  return var_limit_;
204 }
205 
207  return vm_.count("variance-limit")>0;
208 }
209 
210 std::string CmdLine:: get_var_file() const{
211  return var_file_;
212 }
213 
215  return vm_.count("variance-file")>0;
216 }
217 
219  return vm_.count("video-output-path")>0;
220 }
221 
222 bool CmdLine:: dmtx_only() const{
223  return vm_.count("dmtxonly")>0;
224 }
225 
227  return should_exit_;
228 }
229 
230 std::string CmdLine:: get_video_channel() const{
231  return video_channel_;
232 }
233 
234 bool CmdLine:: show_fps() const{
235  return show_fps_;
236 }
237 
239  return verbose_;
240 }
241 
243  return dmx_timeout_;
244 }
245 
247  return inner_ratio_;
248 }
249 
251  return outer_ratio_;
252 }
253 
255  return vm_.count("data-directory")>0;
256 }
257 
259  return vm_.count("video-camera")>0;
260 }
261 
262 std::string CmdLine:: get_data_dir() const{
263  return data_dir_;
264 }
265 
266 std::string CmdLine:: get_pattern_name() const{
267  return pattern_name_;
268 }
269 
270 std::string CmdLine:: get_mbt_cad_file() const{
271  if(vpIoTools::checkFilename(get_data_dir() + get_pattern_name() + std::string(".wrl")))
272  return get_data_dir() + get_pattern_name() + std::string(".wrl");
273  else if (vpIoTools::checkFilename(get_data_dir() + get_pattern_name() + std::string(".cao")))
274  return get_data_dir() + get_pattern_name() + std::string(".cao");
275  else
276  return get_data_dir() + get_pattern_name() + std::string(".wrl");
277 }
278 
279 std::string CmdLine:: get_xml_file() const{
280  return get_data_dir() + get_pattern_name() + std::string(".xml");
281 }
282 
283 std::string CmdLine:: get_init_file() const{
284  return get_data_dir() + get_pattern_name() + std::string(".init");
285 }
286 
288  return vm_.count("single-image")>0;
289 }
290 
292  return get_data_dir() + single_image_name_;
293 }
294 
295 std::vector<vpPoint>& CmdLine:: get_flashcode_points_3D() {
296  return flashcode_points_3D_;
297 }
298 
299 std::vector<vpPoint>& CmdLine:: get_inner_points_3D() {
300  return inner_points_3D_;
301 }
302 
303 std::vector<vpPoint>& CmdLine:: get_outer_points_3D() {
304  return outer_points_3D_;
305 }
306 
308  if(vm_["detector-type"].as<std::string>()=="zbar")
309  return CmdLine::ZBAR;
310  else
311  return CmdLine::DMTX;
312 }
313 
315  if(vm_["tracker-type"].as<std::string>()=="mbt")
316  return CmdLine::MBT;
317  else if(vm_["tracker-type"].as<std::string>()=="klt")
318  return CmdLine::KLT;
319  else
320  return CmdLine::KLT_MBT;
321 }
322 
323 
325  return adhoc_recovery_size_;
326 }
327 
329  return adhoc_recovery_ratio_;
330 }
331 
334 }
335 
338 }
339 
340 std::string CmdLine:: get_code_message() const {
341  return code_message_;
342 }
344  return code_message_index_;
345 }
346 
348  return adhoc_recovery_;
349 }
350 
352  return vm_.count("log-checkpoints")>0;
353 }
354 
355 bool CmdLine:: log_pose() const{
356  return log_pose_;
357 }
358 
359 void CmdLine:: set_data_directory(std::string &dir){
360  data_dir_ = dir;
361 }
362 
363 void CmdLine:: set_pattern_name(std::string &name){
364  pattern_name_ = name;
365 }
368 }
369 
370 void CmdLine:: set_code_message(const std::string &msg)
371 {
372  code_message_ = msg;
373 }
374 void CmdLine:: set_code_message_index(const size_t &index)
375 {
376  code_message_index_ = index;
377 }
bool show_fps_
Definition: cmd_line.h:20
std::vector< vpPoint > & get_flashcode_points_3D()
Definition: cmd_line.cpp:295
std::string get_code_message() const
Definition: cmd_line.cpp:340
std::string var_file_
Definition: cmd_line.h:39
std::string input_file_pattern_
Definition: cmd_line.h:46
bool log_pose() const
Definition: cmd_line.cpp:355
std::vector< vpPoint > inner_points_3D_
Definition: cmd_line.h:42
size_t get_code_message_index() const
Definition: cmd_line.cpp:343
bool using_var_file() const
Definition: cmd_line.cpp:214
std::string video_channel_
Definition: cmd_line.h:24
std::string get_pattern_name() const
Definition: cmd_line.cpp:266
int get_dmx_timeout() const
Definition: cmd_line.cpp:242
unsigned int adhoc_recovery_treshold_
Definition: cmd_line.h:31
std::string config_file
Definition: cmd_line.h:47
double var_limit_
Definition: cmd_line.h:27
bool adhoc_recovery_display_
Definition: cmd_line.h:29
int mbt_convergence_steps_
Definition: cmd_line.h:35
std::string single_image_name_
Definition: cmd_line.h:40
bool log_pose_
Definition: cmd_line.h:22
double get_var_limit() const
Definition: cmd_line.cpp:202
void common()
Definition: cmd_line.cpp:8
bool get_verbose() const
Definition: cmd_line.cpp:238
std::string get_input_file_pattern() const
Definition: cmd_line.cpp:166
std::string code_message_
Definition: cmd_line.h:48
unsigned int get_adhoc_recovery_treshold() const
Definition: cmd_line.cpp:332
std::vector< vpPoint > & get_inner_points_3D()
Definition: cmd_line.cpp:299
std::string get_xml_file() const
Definition: cmd_line.cpp:279
bool show_plot() const
Definition: cmd_line.cpp:170
def default_value(type_)
void init(std::string &config_file)
Definition: cmd_line.cpp:135
double inner_ratio_
Definition: cmd_line.h:25
bool show_plot_
Definition: cmd_line.h:21
double adhoc_recovery_ratio_
Definition: cmd_line.h:30
int code_message_index_
Definition: cmd_line.h:49
bool using_adhoc_recovery() const
Definition: cmd_line.cpp:347
std::vector< double > outer_coordinates
Definition: cmd_line.h:45
double get_adhoc_recovery_ratio() const
Definition: cmd_line.cpp:328
bool using_data_dir() const
Definition: cmd_line.cpp:254
bool should_exit() const
Definition: cmd_line.cpp:226
po::options_description prog_args
Definition: cmd_line.h:44
std::vector< vpPoint > outer_points_3D_
Definition: cmd_line.h:42
bool adhoc_recovery_
Definition: cmd_line.h:28
bool logging_video() const
Definition: cmd_line.cpp:218
bool should_exit_
Definition: cmd_line.h:23
bool using_hinkley() const
Definition: cmd_line.cpp:174
double mbt_dynamic_range_
Definition: cmd_line.h:36
std::string pattern_name_
Definition: cmd_line.h:38
boost::program_options::variables_map vm_
Definition: cmd_line.h:18
bool using_mbt_dynamic_range()
Definition: cmd_line.cpp:198
std::string get_video_channel() const
Definition: cmd_line.cpp:230
DETECTOR_TYPE
Definition: cmd_line.h:53
bool log_checkpoints() const
Definition: cmd_line.cpp:351
bool get_adhoc_recovery_display() const
Definition: cmd_line.cpp:336
std::string log_file_pattern_
Definition: cmd_line.h:46
std::string get_single_image_path() const
Definition: cmd_line.cpp:291
void set_pattern_name(std::string &name)
Definition: cmd_line.cpp:363
double adhoc_recovery_size_
Definition: cmd_line.h:32
int dmx_timeout_
Definition: cmd_line.h:34
bool verbose_
Definition: cmd_line.h:19
std::string data_dir_
Definition: cmd_line.h:37
std::vector< vpPoint > flashcode_points_3D_
Definition: cmd_line.h:41
void set_code_message_index(const size_t &index)
Definition: cmd_line.cpp:374
double get_inner_ratio() const
Definition: cmd_line.cpp:246
int get_mbt_convergence_steps() const
Definition: cmd_line.cpp:190
void set_show_fps(bool show_fps)
Definition: cmd_line.cpp:366
double get_outer_ratio() const
Definition: cmd_line.cpp:250
bool dmtx_only() const
Definition: cmd_line.cpp:222
vpCameraParameters get_cam_calib_params() const
Definition: cmd_line.cpp:154
std::string get_init_file() const
Definition: cmd_line.cpp:283
void set_data_directory(std::string &dir)
Definition: cmd_line.cpp:359
bool using_var_limit() const
Definition: cmd_line.cpp:206
std::string get_data_dir() const
Definition: cmd_line.cpp:262
double get_hinkley_alpha() const
Definition: cmd_line.cpp:178
bool show_fps() const
Definition: cmd_line.cpp:234
std::vector< double > inner_coordinates
Definition: cmd_line.h:45
double get_mbt_dynamic_range() const
Definition: cmd_line.cpp:194
TRACKER_TYPE
Definition: cmd_line.h:56
std::vector< double > flashcode_coordinates
Definition: cmd_line.h:45
std::string get_log_file_pattern() const
Definition: cmd_line.cpp:162
TRACKER_TYPE get_tracker_type() const
Definition: cmd_line.cpp:314
double get_hinkley_delta() const
Definition: cmd_line.cpp:184
void loadConfig(std::string &config_file)
Definition: cmd_line.cpp:67
double outer_ratio_
Definition: cmd_line.h:26
double get_adhoc_recovery_size() const
Definition: cmd_line.cpp:324
bool using_video_camera() const
Definition: cmd_line.cpp:258
std::vector< double > hinkley_range_
Definition: cmd_line.h:33
std::string get_var_file() const
Definition: cmd_line.cpp:210
void set_code_message(const std::string &msg)
Definition: cmd_line.cpp:370
std::vector< vpPoint > & get_outer_points_3D()
Definition: cmd_line.cpp:303
DETECTOR_TYPE get_detector_type() const
Definition: cmd_line.cpp:307
bool using_single_image() const
Definition: cmd_line.cpp:287
std::string get_mbt_cad_file() const
Definition: cmd_line.cpp:270


visp_auto_tracker
Author(s): Filip Novotny
autogenerated on Sat Mar 13 2021 03:20:08