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> 16 #include "logfilewriter.hpp" 24 flashcode_center_(640/2,480/2),
27 flush_display_(flush_display){
28 std::cout <<
"starting tracker" << std::endl;
44 p.setWorldCoordinates(
56 varfile_ <<
"#These are variances and other data from the model based tracker in gnuplot format" << std::endl;
58 varfile_ <<
"iteration\tvar_x\var_y\tvar_z\tvar_wx\tvar_wy\var_wz";
62 varfile_ <<
"\tpose_tx\tpose_ty\tpose_tz\tpose_rx\tpose_ry\tpose_rz";
72 for(hinkley_array_t::iterator i =
hink_.begin();i!=
hink_.end();i++)
77 vpMbEdgeTracker *tracker_me =
dynamic_cast<vpMbEdgeTracker*
>(
tracker_);
81 std::cout <<
"error: could not init moving edges on tracker that doesn't support them." << std::endl;
89 #if VISP_VERSION_INT < VP_VERSION_INT(2,10,0) 131 const cv::Rect& Tracker_:: get_tracking_box<cv::Rect>(){
136 const vpRect& Tracker_:: get_tracking_box<vpRect>(){
141 return vpDisplay::getClick(evt.
I,
false);
150 #if VISP_VERSION_INT < VP_VERSION_INT(2,10,0) 153 cv::Mat rgba = cv::Mat((
int)evt.
I.getRows(), (int)evt.
I.getCols(), CV_8UC4, (
void*)evt.
I.bitmap);
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);
158 cv::Mat out[] = {bgr, alpha};
161 int from_to[] = { 0,2, 1,1, 2,0, 3,3 };
162 cv::mixChannels(&rgba, 1, out, 2, from_to, 4);
168 vpImageConvert::convert(evt.
I,
Igray_);
176 for (
size_t i=0; i<
detector_->getNbObjects(); i++) {
196 #if VISP_VERSION_INT < VP_VERSION_INT(2,10,0) 200 cv::Mat rgba = cv::Mat((
int)evt.
I.getRows(), (int)evt.
I.getCols(), CV_8UC4, (
void*)evt.
I.bitmap);
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);
205 cv::Mat out[] = {bgr, alpha};
208 int from_to[] = { 0,2, 1,1, 2,0, 3,3 };
209 cv::mixChannels(&rgba, 1, out, 2, from_to, 4);
213 cv::Mat subImage = cv::Mat(bgr,get_tracking_box<cv::Rect>()).clone();
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);
224 vpImageConvert::convert(evt.
I,
Igray_);
232 for (
size_t i=0; i<
detector_->getNbObjects(); i++) {
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.;
256 for(
unsigned int i=0;i<
f_.size();i++){
258 vpImagePoint poly_pt(polygon[i].y,polygon[i].x);
260 vpPixelMeterConversion::convertPoint(
cam_, poly_pt, x, y);
267 std::vector< std::vector< vpImagePoint > > polygons =
detector_->getPolygon();
268 std::vector< vpImagePoint > polygon(4);
270 polygon = polygons[0];
277 for(
unsigned int i=0;i<
f_.size();i++){
280 vpPixelMeterConversion::convertPoint(
cam_, polygon[i], x, y);
291 vpImageConvert::convert(*
I_,
Igray_);
294 for(
unsigned int i=0;i<
f_.size();i++)
295 pose.addPoint(
f_[i]);
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)
308 pose.computePose(vpPose::VIRTUAL_VS,
cMo_);
311 catch(vpException& e) {
312 std::cout <<
"Pose computation failed: " << e.getStringMessage() << std::endl;
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++){
327 std::cout <<
"model inner corner: (" << model_inner_corner[i].get_i() <<
"," << model_inner_corner[i].get_j() <<
")" << std::endl;
337 vpCameraParameters cam;
346 tracker_->setCovarianceComputation(
true);
351 }
catch(vpException& e){
352 std::cout <<
"Tracking failed" << std::endl;
353 std::cout << e.getStringMessage() << std::endl;
365 vpImageConvert::convert(evt.
I,
Igray_);
376 for(
unsigned int i=0; i<6; i++)
380 for(
unsigned int i=0; i<6; i++){
384 std::cout <<
"Hinkley:detected jump!" << std::endl;
391 for(
unsigned int i=0;i<
covariance_.getRows();i++) {
405 vpPoseVector p(
cMo_);
406 for(
unsigned int i=0;i<p.getRows();i++)
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);
419 boost::accumulators::accumulator_set<
421 boost::accumulators::stats<
422 boost::accumulators::tag::median(boost::accumulators::with_p_square_quantile)
430 for(
int i=std::max(u-region_width,0);
431 i<std::min(u+region_width,(
int)evt.
I.getWidth());
433 for(
int j=std::max(v-region_height,0);
434 j<std::min(v+region_height,(
int)evt.
I.getHeight());
440 double checkpoints_median = boost::accumulators::median(acc);
442 writer.write(checkpoints_median);
447 }
catch(vpException& e){
448 std::cout <<
"Tracking lost" << std::endl;
457 std::vector<cv::Point> points;
459 vpImageConvert::convert(evt.
I,
Igray_);
461 boost::accumulators::accumulator_set<
463 boost::accumulators::stats<
464 boost::accumulators::tag::mean
472 double u=0.,v=0.,u_inner=0.,v_inner=0;
476 acc(std::abs(u-u_inner));
477 acc(std::abs(v-v_inner));
482 u = std::min(u,(
double)evt.
I.getWidth()-1);
484 v = std::min(v,(
double)evt.
I.getHeight()-1);
485 points.push_back(cv::Point(u,v));
491 vpMbEdgeTracker *tracker_me =
dynamic_cast<vpMbEdgeTracker*
>(
tracker_);
497 std::cout <<
"error: could not init moving edges on tracker that doesn't support them." << std::endl;
523 std::list<vpMbtDistanceLine*> linesList;
526 dynamic_cast<vpMbEdgeTracker*>(
tracker_)->getLline(linesList, 0);
528 std::list<vpMbtDistanceLine*>::iterator linesIterator = linesList.begin();
529 if (linesList.empty())
531 bool noVisibleLine =
true;
532 for (; linesIterator != linesList.end(); ++linesIterator)
534 vpMbtDistanceLine* line = *linesIterator;
536 #if VISP_VERSION_INT >= VP_VERSION_INT(3,0,0) // ViSP >= 3.0.0 537 if (line && line->isVisible() && ! line->meline.empty())
539 if (line && line->isVisible() && line->meline)
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++)
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())
549 for (; sitesIterator != line->meline[a]->getMeList().end(); ++sitesIterator)
550 #elif VISP_VERSION_INT >= VP_VERSION_INT(2,10,0)
551 if (line->meline->getMeList().empty()) {
554 std::list<vpMeSite>::const_iterator sitesIterator = line->meline->getMeList().begin();
556 for (; sitesIterator != line->meline->getMeList().end(); ++sitesIterator)
558 if (line->meline->list.empty()) {
561 std::list<vpMeSite>::const_iterator sitesIterator = line->meline->list.begin();
563 for (; sitesIterator != line->meline->list.end(); ++sitesIterator)
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;
572 sites->moving_edge_sites.push_back (movingEdgeSite);
574 noVisibleLine =
false;
576 #if VISP_VERSION_INT >= VP_VERSION_INT(3,0,0) // ViSP >= 3.0.0 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;
596 poly_lst = &dynamic_cast<vpMbKltTracker*>(
tracker_)->getFaces();
598 for(
unsigned int i = 0 ; i < poly_lst->size() ; i++)
602 map_klt = &((*poly_lst)[i]->getCurrentPoints());
604 if(map_klt->size() > 3)
606 for (std::map<int, vpImagePoint>::iterator it=map_klt->begin(); it!=map_klt->end(); ++it)
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);
617 #else // ViSP >= 2.10.0 618 std::list<vpMbtDistanceKltPoints*> *poly_lst;
619 std::map<int, vpImagePoint> *map_klt;
622 poly_lst = &
dynamic_cast<vpMbKltTracker*
>(
tracker_)->getFeaturesKlt();
624 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=poly_lst->begin(); it!=poly_lst->end(); ++it){
625 map_klt = &((*it)->getCurrentPoints());
627 if((*it)->polygon->isVisible()){
628 if(map_klt->size() > 3)
630 for (std::map<int, vpImagePoint>::iterator it=map_klt->begin(); it!=map_klt->end(); ++it)
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);
std::vector< vpPoint > & get_flashcode_points_3D()
std::string get_code_message() const
bool using_var_file() const
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
bool input_selected(input_ready const &evt)
int get_dmx_timeout() const
#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
std::vector< vpPoint > & get_points3D_middle()
double get_var_limit() const
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
std::vector< vpPoint > outer_points_3D_bcp_
bool model_detected(msm::front::none const &)
unsigned int get_adhoc_recovery_treshold() const
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
std::vector< vpPoint > & get_inner_points_3D()
std::vector< vpPoint > & get_flashcode()
std::string get_xml_file() const
TFSIMD_FORCE_INLINE const tfScalar & y() const
vpImage< vpRGBa > & get_I()
bool using_adhoc_recovery() const
Tracker_(CmdLine &cmd, vpDetectorBase *detector, vpMbTracker *tracker_, bool flush_display=true)
double get_adhoc_recovery_ratio() const
void find_flashcode_pos(input_ready const &evt)
std::vector< vpPoint > points3D_inner_
bool using_hinkley() const
std::vector< vpPoint > & get_points3D_outer()
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
vpDetectorBase & get_detector()
void track_model(input_ready const &evt)
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
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
std::vector< vpPoint > & get_points3D_inner()
bool using_mbt_dynamic_range()
statistics_t & get_statistics()
bool flashcode_redetected(input_ready const &evt)
bool mbt_success(input_ready const &evt)
bool log_checkpoints() const
TFSIMD_FORCE_INLINE const tfScalar & x() const
#define ROS_WARN_STREAM(args)
std::vector< vpPoint > f_
vpCameraParameters & get_cam()
void set_code_message_index(const size_t &index)
int get_mbt_convergence_steps() const
std::vector< vpPoint > points3D_middle_
#define ROS_INFO_STREAM(args)
vpDetectorBase * detector_
bool no_input_selected(input_ready const &evt)
bool using_var_limit() const
bool flashcode_detected(input_ready const &evt)
double get_hinkley_alpha() const
vpImagePoint flashcode_center_
double get_mbt_dynamic_range() const
vpImage< unsigned char > Igray_
void updateKltPoints(visp_tracker::KltPointsPtr klt)
TRACKER_TYPE get_tracker_type() const
double get_hinkley_delta() const
double get_adhoc_recovery_size() const
void set_flush_display(bool val)
std::string get_var_file() const
std::vector< vpPoint > & get_outer_points_3D()
std::vector< vpPoint > points3D_outer_
void updateMovingEdgeSites(visp_tracker::MovingEdgeSitesPtr sites)
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
std::string get_mbt_cad_file() const