tracking.cpp
Go to the documentation of this file.
1 #include "ros/ros.h"
2 #include "cv.h"
3 #include "highgui.h"
4 #include "tracking.h"
5 #include <visp3/core/vpImageConvert.h>
6 #include <visp3/core/vpPixelMeterConversion.h>
7 #include <visp3/core/vpImagePoint.h>
8 #include <visp3/gui/vpDisplayX.h>
9 #include <visp3/vision/vpPose.h>
10 #include <visp3/core/vpMeterPixelConversion.h>
11 #include <visp3/core/vpTrackingException.h>
12 #include <visp3/io/vpImageIo.h>
13 #include <visp3/core/vpRect.h>
14 #include <visp3/mbt/vpMbGenericTracker.h>
15 
16 #include "logfilewriter.hpp"
17 
18 namespace tracking{
19 
20  Tracker_:: Tracker_(CmdLine& cmd, vpDetectorBase* detector, vpMbTracker* tracker,bool flush_display) :
21 
22  cmd(cmd),
23  iter_(0),
24  flashcode_center_(640/2,480/2),
25  detector_(detector),
26  tracker_(tracker),
27  flush_display_(flush_display){
28  std::cout << "starting tracker" << std::endl;
29  cvTrackingBox_init_ = false;
30  cvTrackingBox_.x = 0;
31  cvTrackingBox_.y = 0;
32  cvTrackingBox_.width = 0;
33  cvTrackingBox_.height = 0;
34 
35  // Retrieve camera parameters comming from camera_info message in order to update them after loadConfigFile()
36  tracker_->getCameraParameters(cam_); // init camera parameters
37 
41  if(cmd.using_adhoc_recovery() || cmd.log_checkpoints()){
42  for(unsigned int i=0;i<points3D_outer_.size();i++){
43  vpPoint p;
44  p.setWorldCoordinates(
45  (points3D_outer_[i].get_oX()+points3D_inner_[i].get_oX())*cmd.get_adhoc_recovery_ratio(),
46  (points3D_outer_[i].get_oY()+points3D_inner_[i].get_oY())*cmd.get_adhoc_recovery_ratio(),
47  (points3D_outer_[i].get_oZ()+points3D_inner_[i].get_oZ())*cmd.get_adhoc_recovery_ratio()
48  );
49  points3D_middle_.push_back(p);
50  }
51  }
53 
54  if(cmd.using_var_file()){
55  varfile_.open(cmd.get_var_file().c_str(),std::ios::out);
56  varfile_ << "#These are variances and other data from the model based tracker in gnuplot format" << std::endl;
57  if(cmd.using_hinkley())
58  varfile_ << "iteration\tvar_x\var_y\tvar_z\tvar_wx\tvar_wy\var_wz";
59  if(cmd.using_mbt_dynamic_range())
60  varfile_ << "\tmbt_range";
61  if(cmd.log_pose())
62  varfile_ << "\tpose_tx\tpose_ty\tpose_tz\tpose_rx\tpose_ry\tpose_rz";
63  if(cmd.log_checkpoints())
64  varfile_ << "\tcheckpoint_median";
65 
66  varfile_ << std::endl;
67  }
68 
69  if(cmd.using_hinkley()){
70  if(cmd.get_verbose())
71  std::cout << "Initialising hinkley with alpha=" << cmd.get_hinkley_alpha() << " and delta=" << cmd.get_hinkley_delta() << std::endl;
72  for(hinkley_array_t::iterator i = hink_.begin();i!=hink_.end();i++)
73  i->init(cmd.get_hinkley_alpha(),cmd.get_hinkley_delta());
74  }
75 
76  if(cmd.using_mbt_dynamic_range()){
77  vpMbEdgeTracker *tracker_me = dynamic_cast<vpMbEdgeTracker*>(tracker_);
78  if(tracker_me)
79  tracker_me->getMovingEdge(tracker_me_config_);
80  else
81  std::cout << "error: could not init moving edges on tracker that doesn't support them." << std::endl;
82  }
83 
84  tracker_->loadConfigFile(cmd.get_xml_file() ); // Load the configuration of the tracker
85  tracker_->loadModel(cmd.get_mbt_cad_file()); // load the 3d model, to read .wrl model the 3d party library coin is required, if coin is not installed .cao file can be used.
86  tracker_->setCameraParameters(cam_); // Set the good camera parameters coming from camera_info message
87  }
88 
89 #if VISP_VERSION_INT < VP_VERSION_INT(2,10,0)
91 #else
92  vpDetectorBase& Tracker_:: get_detector(){
93 #endif
94  return *detector_;
95  }
96 
97  vpMbTracker& Tracker_:: get_mbt(){
98  return *tracker_;
99  }
100 
101  std::vector<vpPoint>& Tracker_:: get_points3D_inner(){
102  return points3D_inner_;
103  }
104 
105  std::vector<vpPoint>& Tracker_:: get_points3D_outer(){
106  return points3D_outer_;
107 
108  }
109 
110  std::vector<vpPoint>& Tracker_:: get_points3D_middle(){
111  return points3D_middle_;
112  }
113 
114  std::vector<vpPoint>& Tracker_:: get_flashcode(){
115  return f_;
116  }
117 
118  vpImage<vpRGBa>& Tracker_:: get_I(){
119  return *I_;
120  }
121 
122  vpCameraParameters& Tracker_:: get_cam(){
123  return cam_;
124  }
125 
127  return cmd;
128  }
129 
130  template<>
131  const cv::Rect& Tracker_:: get_tracking_box<cv::Rect>(){
132  return cvTrackingBox_;
133  }
134 
135  template<>
136  const vpRect& Tracker_:: get_tracking_box<vpRect>(){
137  return vpTrackingBox_;
138  }
139 
141  return vpDisplay::getClick(evt.I,false);
142  }
143 
144 
146  return !input_selected(evt);
147  }
148 
150 #if VISP_VERSION_INT < VP_VERSION_INT(2,10,0)
151  //this->cam_ = evt.cam_;
152 
153  cv::Mat rgba = cv::Mat((int)evt.I.getRows(), (int)evt.I.getCols(), CV_8UC4, (void*)evt.I.bitmap);
154 
155  cv::Mat bgr = cv::Mat((int)evt.I.getRows(), (int)evt.I.getCols(), CV_8UC3);
156  cv::Mat alpha((int)evt.I.getRows(), (int)evt.I.getCols(), CV_8UC1);
157 
158  cv::Mat out[] = {bgr, alpha};
159  // rgba[0] -> bgr[2], rgba[1] -> bgr[1],
160  // rgba[2] -> bgr[0], rgba[3] -> alpha[0]
161  int from_to[] = { 0,2, 1,1, 2,0, 3,3 };
162  cv::mixChannels(&rgba, 1, out, 2, from_to, 4);
163 
164  //vpImageConvert::convert(evt.I,bgr);
165 
166  return detector_->detect(bgr,cmd.get_dmx_timeout(),0,0);
167 #else
168  vpImageConvert::convert(evt.I, Igray_);
169  detector_->detect(Igray_);
170  if (detector_->getNbObjects()) {
171  if (cmd.get_code_message().empty()) {
172  cmd.set_code_message_index(0); // we retain the largest code at index 0
173  return true;
174  }
175  else {
176  for (size_t i=0; i<detector_->getNbObjects(); i++) {
177  if (detector_->getMessage(i) == cmd.get_code_message()) {
179  ROS_WARN_STREAM("Code with message \"" << cmd.get_code_message() << "\" found");
180  return true;
181  }
182  }
183  ROS_WARN_STREAM("Code with message \"" << cmd.get_code_message() << "\" not found");
184  return false;
185  }
186  }
187  return false;
188 #endif
189  }
190 
191  /*
192  * Detect flashcode in region delimited by the outer points of the model
193  * The timeout is the default timeout times the surface ratio
194  */
196 #if VISP_VERSION_INT < VP_VERSION_INT(2,10,0)
197  //this->cam_ = evt.cam_;
198 
199  //vpImageConvert::convert(evt.I,cvI);
200  cv::Mat rgba = cv::Mat((int)evt.I.getRows(), (int)evt.I.getCols(), CV_8UC4, (void*)evt.I.bitmap);
201 
202  cv::Mat bgr = cv::Mat((int)evt.I.getRows(), (int)evt.I.getCols(), CV_8UC3);
203  cv::Mat alpha((int)evt.I.getRows(), (int)evt.I.getCols(), CV_8UC1);
204 
205  cv::Mat out[] = {bgr, alpha};
206  // rgba[0] -> bgr[2], rgba[1] -> bgr[1],
207  // rgba[2] -> bgr[0], rgba[3] -> alpha[0]
208  int from_to[] = { 0,2, 1,1, 2,0, 3,3 };
209  cv::mixChannels(&rgba, 1, out, 2, from_to, 4);
210 
212  {
213  cv::Mat subImage = cv::Mat(bgr,get_tracking_box<cv::Rect>()).clone();
214 
215  double timeout = cmd.get_dmx_timeout()*(double)(get_tracking_box<cv::Rect>().width*get_tracking_box<cv::Rect>().height)/(double)(bgr.cols*bgr.rows);
216  return detector_->detect(subImage,(unsigned int)timeout,get_tracking_box<cv::Rect>().x,get_tracking_box<cv::Rect>().y);
217  }
218  else
219  {
220  return detector_->detect(bgr,cmd.get_dmx_timeout(),0,0);
221  }
222 #else
223  // TODO, use boundig box as for ViSP < 2.10.0
224  vpImageConvert::convert(evt.I, Igray_);
225  detector_->detect(Igray_);
226  if (detector_->getNbObjects()) {
227  if (cmd.get_code_message().empty()) {
228  cmd.set_code_message_index(0); // we retain the largest code at index 0
229  return true;
230  }
231  else {
232  for (size_t i=0; i<detector_->getNbObjects(); i++) {
233  if (detector_->getMessage(i) == cmd.get_code_message()) {
235  ROS_WARN_STREAM("Code with message \"" << cmd.get_code_message() << "\" found");
236  return true;
237  }
238  }
239  ROS_WARN_STREAM("Code with message \"" << cmd.get_code_message() << "\" not found");
240  return false;
241  }
242  }
243  return false;
244 #endif
245  }
246 
248  this->cam_ = evt.cam_;
249 
250 #if VISP_VERSION_INT < VP_VERSION_INT(2,10,0)
251  std::vector<cv::Point> polygon = detector_->get_polygon();
252  double centerX = (double)(polygon[0].x+polygon[1].x+polygon[2].x+polygon[3].x)/4.;
253  double centerY = (double)(polygon[0].y+polygon[1].y+polygon[2].y+polygon[3].y)/4.;
254  vpPixelMeterConversion::convertPoint(cam_, flashcode_center_, centerX, centerY);
255 
256  for(unsigned int i=0;i<f_.size();i++){
257  double x=0, y=0;
258  vpImagePoint poly_pt(polygon[i].y,polygon[i].x);
259 
260  vpPixelMeterConversion::convertPoint(cam_, poly_pt, x, y);
261  f_[i].set_x(x);
262  f_[i].set_y(y);
263  }
264 #else
265  // TODO: add a parameter to be able to select the QRcode from it's message
266  // For the moment we get the position of the first code that is the largest in the image
267  std::vector< std::vector< vpImagePoint > > polygons = detector_->getPolygon();
268  std::vector< vpImagePoint > polygon(4);
269  if (polygons.size())
270  polygon = polygons[0];
271 
272  // TODO: remove flashcode_center_, centerX, centerY that are not used
273  //double centerX = cog.get_u();
274  //double centerY = cog.get_v();
275  //vpPixelMeterConversion::convertPoint(cam_, flashcode_center_, centerX, centerY);
276 
277  for(unsigned int i=0;i<f_.size();i++){
278  double x=0, y=0;
279 
280  vpPixelMeterConversion::convertPoint(cam_, polygon[i], x, y);
281  f_[i].set_x(x);
282  f_[i].set_y(y);
283  }
284 #endif
285 
286  I_ = _I = &(evt.I);
287  }
288 
289 
290  bool Tracker_:: model_detected(msm::front::none const&){
291  vpImageConvert::convert(*I_,Igray_);
292  vpPose pose;
293 
294  for(unsigned int i=0;i<f_.size();i++)
295  pose.addPoint(f_[i]);
296 
297  try {
298  vpHomogeneousMatrix cMo_dem;
299  vpHomogeneousMatrix cMo_lag;
300  pose.computePose(vpPose::DEMENTHON, cMo_dem);
301  pose.computePose(vpPose::LAGRANGE, cMo_lag);
302  double residual_dem = pose.computeResidual(cMo_dem);
303  double residual_lag = pose.computeResidual(cMo_lag);
304  if (residual_dem < residual_lag)
305  cMo_ = cMo_dem;
306  else
307  cMo_ = cMo_lag;
308  pose.computePose(vpPose::VIRTUAL_VS,cMo_);
309  //vpDisplay::displayFrame(*I_,cMo_,cam_,0.01,vpColor::none,2);
310  }
311  catch(vpException& e) {
312  std::cout << "Pose computation failed: " << e.getStringMessage() << std::endl;
313  return false;
314  }
315 
316  std::vector<vpImagePoint> model_inner_corner(4);
317  std::vector<vpImagePoint> model_outer_corner(4);
318  for(unsigned int i=0;i<4;i++){
319  points3D_outer_[i].project(cMo_);
320  points3D_inner_[i].project(cMo_);
322  points3D_middle_[i].project(cMo_);
323  vpMeterPixelConversion::convertPoint(cam_,points3D_outer_[i].get_x(),points3D_outer_[i].get_y(),model_outer_corner[i]);
324  vpMeterPixelConversion::convertPoint(cam_,points3D_inner_[i].get_x(),points3D_inner_[i].get_y(),model_inner_corner[i]);
325 
326  if(cmd.get_verbose()){
327  std::cout << "model inner corner: (" << model_inner_corner[i].get_i() << "," << model_inner_corner[i].get_j() << ")" << std::endl;
328  }
329  }
330 
331  try{
332  tracker_->resetTracker();
333  tracker_->loadConfigFile(cmd.get_xml_file() );
334  tracker_->loadModel(cmd.get_mbt_cad_file()); // load the 3d model, to read .wrl model the 3d party library coin is required, if coin is not installed .cao file can be used.
335  tracker_->setCameraParameters(cam_);
336  {
337  vpCameraParameters cam;
338  tracker_->getCameraParameters(cam);
339  if (cam.get_px() != 558) ROS_INFO_STREAM("detection Camera parameters: \n" << cam_);
340  }
341 
342  tracker_->initFromPose(Igray_,cMo_);
343 
344  tracker_->track(Igray_); // track the object on this image
345  tracker_->getPose(cMo_); // get the pose
346  tracker_->setCovarianceComputation(true);
347  for(int i=0;i<cmd.get_mbt_convergence_steps();i++){
348  tracker_->track(Igray_); // track the object on this image
349  tracker_->getPose(cMo_); // get the pose
350  }
351  }catch(vpException& e){
352  std::cout << "Tracking failed" << std::endl;
353  std::cout << e.getStringMessage() << std::endl;
354  return false;
355  }
356  return true;
357  }
358 
360  iter_ = evt.frame;
361  this->cam_ = evt.cam_;
362 
363  try{
364  LogFileWriter writer(varfile_); //the destructor of this class will act as a finally statement
365  vpImageConvert::convert(evt.I,Igray_);
366 
367  tracker_->track(Igray_); // track the object on this image
368  tracker_->getPose(cMo_);
369  covariance_ = tracker_->getCovarianceMatrix();
370  if(cmd.using_var_file()){
371  writer.write(iter_);
372  for(unsigned int i=0;i<covariance_.getRows();i++)
373  writer.write(covariance_[i][i]);
374  }
375  if(cmd.using_var_limit())
376  for(unsigned int i=0; i<6; i++)
377  if(covariance_[i][i]>cmd.get_var_limit())
378  return false;
379  if(cmd.using_hinkley())
380  for(unsigned int i=0; i<6; i++){
381  if(hink_[i].testDownUpwardJump(covariance_[i][i]) != vpHinkley::noJump){
382  writer.write(covariance_[i][i]);
383  if(cmd.get_verbose())
384  std::cout << "Hinkley:detected jump!" << std::endl;
385  return false;
386  }
387  }
389  writer.write(tracker_me_config_.getRange());
390 
391  for(unsigned int i=0;i<covariance_.getRows();i++) {
392  statistics.var(covariance_[i][i]);
393  }
394 
395  if(covariance_.getRows() == 6){ //if the covariance matrix is set
402  }
403 
404  if(cmd.using_var_file() && cmd.log_pose()){
405  vpPoseVector p(cMo_);
406  for(unsigned int i=0;i<p.getRows();i++)
407  writer.write(p[i]);
408  }
409 
411  for(unsigned int p=0;p<points3D_middle_.size();p++){
412  vpPoint& point3D = points3D_middle_[p];
413 
414  double _u=0.,_v=0.,_u_inner=0.,_v_inner=0.;
415  point3D.project(cMo_);
416  vpMeterPixelConversion::convertPoint(cam_,point3D.get_x(),point3D.get_y(),_u,_v);
417  vpMeterPixelConversion::convertPoint(cam_,points3D_inner_[p].get_x(),points3D_inner_[p].get_y(),_u_inner,_v_inner);
418 
419  boost::accumulators::accumulator_set<
420  unsigned char,
421  boost::accumulators::stats<
422  boost::accumulators::tag::median(boost::accumulators::with_p_square_quantile)
423  >
424  > acc;
425 
426  int region_width= std::max((int)(std::abs(_u-_u_inner)*cmd.get_adhoc_recovery_size()),1);
427  int region_height=std::max((int)(std::abs(_v-_v_inner)*cmd.get_adhoc_recovery_size()),1);
428  int u=(int)_u;
429  int v=(int)_v;
430  for(int i=std::max(u-region_width,0);
431  i<std::min(u+region_width,(int)evt.I.getWidth());
432  i++){
433  for(int j=std::max(v-region_height,0);
434  j<std::min(v+region_height,(int)evt.I.getHeight());
435  j++){
436  acc(Igray_[j][i]);
438  }
439  }
440  double checkpoints_median = boost::accumulators::median(acc);
442  writer.write(checkpoints_median);
443  if( cmd.using_adhoc_recovery() && (unsigned int)checkpoints_median>cmd.get_adhoc_recovery_treshold() )
444  return false;
445  }
446  }
447  }catch(vpException& e){
448  std::cout << "Tracking lost" << std::endl;
449  return false;
450  }
451  return true;
452  }
453 
455  this->cam_ = evt.cam_;
456 
457  std::vector<cv::Point> points;
458  I_ = _I = &(evt.I);
459  vpImageConvert::convert(evt.I,Igray_);
460 
461  boost::accumulators::accumulator_set<
462  double,
463  boost::accumulators::stats<
464  boost::accumulators::tag::mean
465  >
466  > acc;
467 
468  for(unsigned int i=0;i<points3D_outer_.size();i++){
469  points3D_outer_[i].project(cMo_);
470  points3D_inner_[i].project(cMo_);
471 
472  double u=0.,v=0.,u_inner=0.,v_inner=0;
473  vpMeterPixelConversion::convertPoint(cam_,points3D_outer_[i].get_x(),points3D_outer_[i].get_y(),u,v);
474  vpMeterPixelConversion::convertPoint(cam_,points3D_inner_[i].get_x(),points3D_inner_[i].get_y(),u_inner,v_inner);
475 
476  acc(std::abs(u-u_inner));
477  acc(std::abs(v-v_inner));
478 
479  // To avoid OpenCV exception that may occur when creating cv::boundingRect() from the points,
480  // we ensure that the coordinates of the points remain in the image.
481  u = std::max(u,0.);
482  u = std::min(u,(double)evt.I.getWidth()-1);
483  v = std::max(v,0.);
484  v = std::min(v,(double)evt.I.getHeight()-1);
485  points.push_back(cv::Point(u,v));
486  }
487 
489  int range = (const unsigned int)(boost::accumulators::mean(acc)*cmd.get_mbt_dynamic_range());
490 
491  vpMbEdgeTracker *tracker_me = dynamic_cast<vpMbEdgeTracker*>(tracker_);
492  if(tracker_me){
493  tracker_me->getMovingEdge(tracker_me_config_);
494  tracker_me_config_.setRange(range);
495  tracker_me->setMovingEdge(tracker_me_config_);
496  }else
497  std::cout << "error: could not init moving edges on tracker that doesn't support them." << std::endl;
498  }
499  cvTrackingBox_init_ = true;
500  cvTrackingBox_ = cv::boundingRect(cv::Mat(points));
501 
503  }
504 
506  return statistics;
507  }
508 
510  flush_display_ = val;
511  }
512 
514  return flush_display_;
515  }
516 
517  void
518  Tracker_::updateMovingEdgeSites(visp_tracker::MovingEdgeSitesPtr sites)
519  {
520  if (!sites)
521  return;
522 
523  std::list<vpMbtDistanceLine*> linesList;
524 
525  if(cmd.get_tracker_type() != CmdLine::KLT) // For mbt and hybrid
526  dynamic_cast<vpMbEdgeTracker*>(tracker_)->getLline(linesList, 0);
527 
528  std::list<vpMbtDistanceLine*>::iterator linesIterator = linesList.begin();
529  if (linesList.empty())
530  ROS_DEBUG_THROTTLE(10, "no distance lines");
531  bool noVisibleLine = true;
532  for (; linesIterator != linesList.end(); ++linesIterator)
533  {
534  vpMbtDistanceLine* line = *linesIterator;
535 
536 #if VISP_VERSION_INT >= VP_VERSION_INT(3,0,0) // ViSP >= 3.0.0
537  if (line && line->isVisible() && ! line->meline.empty())
538 #else
539  if (line && line->isVisible() && line->meline)
540 #endif
541  {
542 #if VISP_VERSION_INT >= VP_VERSION_INT(3,0,0) // ViSP >= 3.0.0
543  for(unsigned int a = 0 ; a < line->meline.size() ; a++)
544  {
545  if(line->meline[a] != NULL) {
546  std::list<vpMeSite>::const_iterator sitesIterator = line->meline[a]->getMeList().begin();
547  if (line->meline[a]->getMeList().empty())
548  ROS_DEBUG_THROTTLE(10, "no moving edge for a line");
549  for (; sitesIterator != line->meline[a]->getMeList().end(); ++sitesIterator)
550 #elif VISP_VERSION_INT >= VP_VERSION_INT(2,10,0) // ViSP >= 2.10.0
551  if (line->meline->getMeList().empty()) {
552  ROS_DEBUG_THROTTLE(10, "no moving edge for a line");
553  }
554  std::list<vpMeSite>::const_iterator sitesIterator = line->meline->getMeList().begin();
555 
556  for (; sitesIterator != line->meline->getMeList().end(); ++sitesIterator)
557 #else
558  if (line->meline->list.empty()) {
559  ROS_DEBUG_THROTTLE(10, "no moving edge for a line");
560  }
561  std::list<vpMeSite>::const_iterator sitesIterator = line->meline->list.begin();
562 
563  for (; sitesIterator != line->meline->list.end(); ++sitesIterator)
564 #endif
565  {
566  visp_tracker::MovingEdgeSite movingEdgeSite;
567  movingEdgeSite.x = sitesIterator->ifloat;
568  movingEdgeSite.y = sitesIterator->jfloat;
569 #if VISP_VERSION_INT < VP_VERSION_INT(2,10,0)// ViSP < 2.10.0
570  movingEdgeSite.suppress = sitesIterator->suppress;
571 #endif
572  sites->moving_edge_sites.push_back (movingEdgeSite);
573  }
574  noVisibleLine = false;
575  }
576 #if VISP_VERSION_INT >= VP_VERSION_INT(3,0,0) // ViSP >= 3.0.0
577  }
578  }
579 #endif
580 }
581 if (noVisibleLine)
582 ROS_DEBUG_THROTTLE(10, "no distance lines");
583 }
584 
585 void
586 Tracker_::updateKltPoints(visp_tracker::KltPointsPtr klt)
587 {
588  if (!klt)
589  return;
590 
591 #if VISP_VERSION_INT < VP_VERSION_INT(2,10,0)// ViSP < 2.10.0
592  vpMbHiddenFaces<vpMbtKltPolygon> *poly_lst;
593  std::map<int, vpImagePoint> *map_klt;
594 
595  if(cmd.get_tracker_type() != CmdLine::MBT) // For klt and hybrid
596  poly_lst = &dynamic_cast<vpMbKltTracker*>(tracker_)->getFaces();
597 
598  for(unsigned int i = 0 ; i < poly_lst->size() ; i++)
599  {
600  if((*poly_lst)[i])
601  {
602  map_klt = &((*poly_lst)[i]->getCurrentPoints());
603 
604  if(map_klt->size() > 3)
605  {
606  for (std::map<int, vpImagePoint>::iterator it=map_klt->begin(); it!=map_klt->end(); ++it)
607  {
608  visp_tracker::KltPoint kltPoint;
609  kltPoint.id = it->first;
610  kltPoint.i = it->second.get_i();
611  kltPoint.j = it->second.get_j();
612  klt->klt_points_positions.push_back (kltPoint);
613  }
614  }
615  }
616  }
617 #else // ViSP >= 2.10.0
618  std::list<vpMbtDistanceKltPoints*> *poly_lst;
619  std::map<int, vpImagePoint> *map_klt;
620 
621  if(cmd.get_tracker_type() != CmdLine::MBT) { // For klt and hybrid
622  poly_lst = &dynamic_cast<vpMbKltTracker*>(tracker_)->getFeaturesKlt();
623 
624  for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=poly_lst->begin(); it!=poly_lst->end(); ++it){
625  map_klt = &((*it)->getCurrentPoints());
626 
627  if((*it)->polygon->isVisible()){
628  if(map_klt->size() > 3)
629  {
630  for (std::map<int, vpImagePoint>::iterator it=map_klt->begin(); it!=map_klt->end(); ++it)
631  {
632  visp_tracker::KltPoint kltPoint;
633  kltPoint.id = it->first;
634  kltPoint.i = it->second.get_i();
635  kltPoint.j = it->second.get_j();
636  klt->klt_points_positions.push_back (kltPoint);
637  }
638  }
639  }
640  }
641  }
642 #endif
643 }
644 }
645 
std::vector< vpPoint > & get_flashcode_points_3D()
Definition: cmd_line.cpp:295
std::string get_code_message() const
Definition: cmd_line.cpp:340
vpMbTracker * tracker_
Definition: tracking.h:71
bool log_pose() const
Definition: cmd_line.cpp:355
bool using_var_file() const
Definition: cmd_line.cpp:214
boost::accumulators::accumulator_set< double, boost::accumulators::stats< boost::accumulators::tag::median(boost::accumulators::with_p_square_quantile), boost::accumulators::tag::max, boost::accumulators::tag::mean > > var
Definition: tracking.h:55
vpImage< vpRGBa > * _I
Definition: tracking.h:74
vpCameraParameters cam_
Definition: tracking.h:77
vpHomogeneousMatrix cMo_
Definition: tracking.h:75
bool input_selected(input_ready const &evt)
Definition: tracking.cpp:140
int get_dmx_timeout() const
Definition: cmd_line.cpp:242
#define ROS_DEBUG_THROTTLE(rate,...)
boost::accumulators::accumulator_set< double, boost::accumulators::stats< boost::accumulators::tag::median(boost::accumulators::with_p_square_quantile), boost::accumulators::tag::max, boost::accumulators::tag::mean > > var_z
Definition: tracking.h:55
vpMe tracker_me_config_
Definition: tracking.h:72
bool get_flush_display()
Definition: tracking.cpp:513
std::vector< vpPoint > & get_points3D_middle()
Definition: tracking.cpp:110
double get_var_limit() const
Definition: cmd_line.cpp:202
boost::accumulators::accumulator_set< double, boost::accumulators::stats< boost::accumulators::tag::median(boost::accumulators::with_p_square_quantile), boost::accumulators::tag::max, boost::accumulators::tag::mean > > var_x
Definition: tracking.h:55
std::vector< vpPoint > outer_points_3D_bcp_
Definition: tracking.h:80
bool get_verbose() const
Definition: cmd_line.cpp:238
bool model_detected(msm::front::none const &)
Definition: tracking.cpp:290
unsigned int get_adhoc_recovery_treshold() const
Definition: cmd_line.cpp:332
boost::accumulators::accumulator_set< double, boost::accumulators::stats< boost::accumulators::tag::median(boost::accumulators::with_p_square_quantile), boost::accumulators::tag::max, boost::accumulators::tag::mean > > var_y
Definition: tracking.h:55
std::vector< vpPoint > & get_inner_points_3D()
Definition: cmd_line.cpp:299
std::vector< vpPoint > & get_flashcode()
Definition: tracking.cpp:114
std::string get_xml_file() const
Definition: cmd_line.cpp:279
CmdLine & get_cmd()
Definition: tracking.cpp:126
TFSIMD_FORCE_INLINE const tfScalar & y() const
vpImage< vpRGBa > & get_I()
Definition: tracking.cpp:118
vpImage< vpRGBa > * I_
Definition: tracking.h:73
bool using_adhoc_recovery() const
Definition: cmd_line.cpp:347
Tracker_(CmdLine &cmd, vpDetectorBase *detector, vpMbTracker *tracker_, bool flush_display=true)
Definition: tracking.cpp:20
double get_adhoc_recovery_ratio() const
Definition: cmd_line.cpp:328
void find_flashcode_pos(input_ready const &evt)
Definition: tracking.cpp:247
vpRect vpTrackingBox_
Definition: tracking.h:85
vpMbTracker & get_mbt()
Definition: tracking.cpp:97
vpImage< vpRGBa > & I
Definition: events.h:11
std::vector< vpPoint > points3D_inner_
Definition: tracking.h:81
bool using_hinkley() const
Definition: cmd_line.cpp:174
std::vector< vpPoint > & get_points3D_outer()
Definition: tracking.cpp:105
boost::accumulators::accumulator_set< double, boost::accumulators::stats< boost::accumulators::tag::median(boost::accumulators::with_p_square_quantile), boost::accumulators::tag::max, boost::accumulators::tag::mean > > var_wz
Definition: tracking.h:55
vpDetectorBase & get_detector()
Definition: tracking.cpp:92
void track_model(input_ready const &evt)
Definition: tracking.cpp:454
boost::accumulators::accumulator_set< double, boost::accumulators::stats< boost::accumulators::tag::median(boost::accumulators::with_p_square_quantile), boost::accumulators::tag::max, boost::accumulators::tag::mean > > var_wy
Definition: tracking.h:55
boost::accumulators::accumulator_set< double, boost::accumulators::stats< boost::accumulators::tag::median(boost::accumulators::with_p_square_quantile), boost::accumulators::tag::max, boost::accumulators::tag::mean > > var_wx
Definition: tracking.h:55
std::vector< vpPoint > & get_points3D_inner()
Definition: tracking.cpp:101
bool using_mbt_dynamic_range()
Definition: cmd_line.cpp:198
statistics_t & get_statistics()
Definition: tracking.cpp:505
bool flashcode_redetected(input_ready const &evt)
Definition: tracking.cpp:195
bool mbt_success(input_ready const &evt)
Definition: tracking.cpp:359
bool log_checkpoints() const
Definition: cmd_line.cpp:351
TFSIMD_FORCE_INLINE const tfScalar & x() const
#define ROS_WARN_STREAM(args)
std::vector< vpPoint > f_
Definition: tracking.h:84
vpMatrix covariance_
Definition: tracking.h:76
std::ofstream varfile_
Definition: tracking.h:62
vpCameraParameters & get_cam()
Definition: tracking.cpp:122
hinkley_array_t hink_
Definition: tracking.h:69
void set_code_message_index(const size_t &index)
Definition: cmd_line.cpp:374
int get_mbt_convergence_steps() const
Definition: cmd_line.cpp:190
std::vector< vpPoint > points3D_middle_
Definition: tracking.h:83
#define ROS_INFO_STREAM(args)
statistics_t statistics
Definition: tracking.h:89
vpDetectorBase * detector_
Definition: tracking.h:66
bool no_input_selected(input_ready const &evt)
Definition: tracking.cpp:145
bool using_var_limit() const
Definition: cmd_line.cpp:206
bool flashcode_detected(input_ready const &evt)
Definition: tracking.cpp:149
double get_hinkley_alpha() const
Definition: cmd_line.cpp:178
vpImagePoint flashcode_center_
Definition: tracking.h:61
vpCameraParameters cam_
Definition: events.h:12
double get_mbt_dynamic_range() const
Definition: cmd_line.cpp:194
vpImage< unsigned char > Igray_
Definition: tracking.h:78
void updateKltPoints(visp_tracker::KltPointsPtr klt)
Definition: tracking.cpp:586
TRACKER_TYPE get_tracker_type() const
Definition: cmd_line.cpp:314
double get_hinkley_delta() const
Definition: cmd_line.cpp:184
cv::Rect cvTrackingBox_
Definition: tracking.h:86
double get_adhoc_recovery_size() const
Definition: cmd_line.cpp:324
void set_flush_display(bool val)
Definition: tracking.cpp:509
std::string get_var_file() const
Definition: cmd_line.cpp:210
std::vector< vpPoint > & get_outer_points_3D()
Definition: cmd_line.cpp:303
std::vector< vpPoint > points3D_outer_
Definition: tracking.h:82
void updateMovingEdgeSites(visp_tracker::MovingEdgeSitesPtr sites)
Definition: tracking.cpp:518
boost::accumulators::accumulator_set< double, boost::accumulators::stats< boost::accumulators::tag::median(boost::accumulators::with_p_square_quantile), boost::accumulators::tag::max, boost::accumulators::tag::mean > > checkpoints
Definition: tracking.h:55
Definition: events.h:6
bool cvTrackingBox_init_
Definition: tracking.h:87
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