From b11945b15cb7eec0ce643c087454d89c314c7688 Mon Sep 17 00:00:00 2001 From: Joan Sola <jsola@iri.upc.edu> Date: Sun, 17 Apr 2022 22:01:05 +0200 Subject: [PATCH] Cleanup unnecessarily complicated code --- src/publisher_vision.cpp | 70 +++++++++------------------------------- 1 file changed, 16 insertions(+), 54 deletions(-) diff --git a/src/publisher_vision.cpp b/src/publisher_vision.cpp index 925401f..ca734f5 100644 --- a/src/publisher_vision.cpp +++ b/src/publisher_vision.cpp @@ -519,8 +519,6 @@ void PublisherVisionDebug::showTracks(cv::Mat _image, int min_feature_in_track = min_max_feat.first; int max_feature_in_track = min_max_feat.second; - // for (auto track = _tracks.begin(); track != _tracks.end(); ++track) //la map trackS - map<size_t, FeatureBasePtr> alive_features = _track_matrix.snapshot(_cap_img); if (alive_features.empty()) return; @@ -585,7 +583,9 @@ void PublisherVisionDebug::showTracks(cv::Mat _image, if (is_keyframe) { // mark features of previous keyframes - cv::circle(_image, cv::Point(ftr->second->getMeasurement(0), ftr->second->getMeasurement(1)), + cv::circle(_image, + cv::Point(ftr->second->getMeasurement(0), + ftr->second->getMeasurement(1)), tracks_.feature_kfs_.size_pix_, color, tracks_.feature_kfs_.thickness_); @@ -667,47 +667,10 @@ Eigen::Vector2d PublisherVisionDebug::projectLandmarkHp(const Eigen::Matrix<doub return pixel; } -// void PublisherVisionDebug::showLandmark(cv::Mat _image, - // const TrackMatrix& _track_matrix, - // const FeatureBasePtr& _ftr) -// { - - // // get stuff common to all landmarks - // const auto& capture = _ftr->getCapture(); - // const auto& Tcw = getTcwMatrix(capture); - // const auto& prj_mat = getProjectionMatrix(capture); - // const auto& trf_prj_mat = prj_mat * Tcw; - // // get stuff of this landmark - // const auto& lmk = getAssociatedLandmark(_track_matrix, _ftr); - // const auto& lmk_pixel = projectLandmarkHp(trf_prj_mat, lmk); - - // if (lmk != nullptr) - // { - // cv::drawMarker(_image, cv::Point(lmk_pixel(0), lmk_pixel(1)), - // CV_RGB(0, 0, 0), cv::MARKER_TILTED_CROSS, - // thickness_lmk_, 1); - - // if (show_landmarks_ID_) - // { - // unsigned int lmk_id = lmk->id(); - // int shift_text_x = 7; - // int shift_text_y = 10; - // int font_face = 1; // let's keep the default one - - // cv::putText( - // _image, - // std::to_string(lmk_id), - // cv::Point(lmk_pixel(0) - shift_text_x, - // lmk_pixel(1) - shift_text_y), - // font_face, size_text_ID_, CV_RGB(0, 0, 0)); - // } - // } -// } - -void PublisherVisionDebug::showLandmarks(cv::Mat _image, - const TrackMatrix& _track_matrix, - const CaptureBasePtr& _capture) +void PublisherVisionDebug::showLandmarks(cv::Mat _image, + const TrackMatrix& _track_matrix, + const CaptureBasePtr& _capture) { // get stuff common to all landmarks cv::Scalar color_lmks = primaryColor(landmarks_.color_); @@ -730,7 +693,9 @@ void PublisherVisionDebug::showLandmarks(cv::Mat _image, { const auto& lmk_pixel = projectLandmarkHp(trf_prj_mat, lmk); - cv::drawMarker(_image, cv::Point(lmk_pixel(0), lmk_pixel(1)), + cv::drawMarker(_image, + cv::Point(lmk_pixel(0), + lmk_pixel(1)), color_lmks, cv::MARKER_TILTED_CROSS, landmarks_.size_pix_, 1); @@ -776,26 +741,23 @@ void PublisherVisionDebug::showTracksPreprocess(cv::Mat _image, const auto& ftr_origin = it_ftr_origin->second.getCvKeyPoint(); const auto& ftr_last = it_ftr_last->second.getCvKeyPoint(); - const auto& pos_ftr_origin = std::make_tuple(ftr_origin.pt.x, ftr_origin.pt.y) ; - const auto& pos_ftr_last = std::make_tuple(ftr_last.pt.x, ftr_last.pt.y); - // cv::circle(_image, -// cv::Point(std::get<0>(pos_ftr_last), std::get<1>(pos_ftr_last)), +// ftr_origin.pt, // tracks_.feature_last_.size_pix_, // color_track_preprocess, // tracks_.feature_last_.thickness_); // // cv::circle(_image, -// cv::Point(std::get<0>(pos_ftr_origin), std::get<1>(pos_ftr_origin)), +// ftr_last.pt, // tracks_.feature_kfs_.size_pix_, // color_track_preprocess, // tracks_.feature_kfs_.thickness_); - cv::line(_image, - cv::Point(std::get<0>(pos_ftr_last), std::get<1>(pos_ftr_last)), - cv::Point(std::get<0>(pos_ftr_origin), std::get<1>(pos_ftr_origin)), - color_track_preprocess, - tracks_preprocess_.thickness_); + cv::line(_image, + ftr_origin.pt, + ftr_last.pt, + color_track_preprocess, + tracks_preprocess_.thickness_); } } } -- GitLab