|
| 1 | +#include <aslam/geometric-vision/match-outlier-rejection-twopt.h> |
| 2 | +#include <aslam/matcher/match.h> |
| 3 | +#include <aslam/visualization/basic-visualization.h> |
| 4 | +#include <visualization/common-rviz-visualization.h> |
| 5 | + |
| 6 | +#include "feature-tracking/vo-outlier-rejection-pipeline.h" |
| 7 | + |
| 8 | +namespace feature_tracking { |
| 9 | + |
| 10 | +VOOutlierRejectionPipeline::VOOutlierRejectionPipeline( |
| 11 | + const aslam::Camera::ConstPtr& camera, const int cam_idx, |
| 12 | + const aslam::Quaternion& q_C_B, const vi_map::FeatureType feature_type, |
| 13 | + const FeatureTrackingOutlierSettings& outlier_settings) |
| 14 | + : camera_(camera), |
| 15 | + cam_idx_(cam_idx), |
| 16 | + q_C_B_(q_C_B), |
| 17 | + feature_type_(static_cast<int>(feature_type)), |
| 18 | + feature_type_string_(vi_map::FeatureTypeToString(feature_type)), |
| 19 | + outlier_settings_(outlier_settings), |
| 20 | + initialized_(false) {} |
| 21 | + |
| 22 | +VOOutlierRejectionPipeline::~VOOutlierRejectionPipeline() {} |
| 23 | + |
| 24 | +void VOOutlierRejectionPipeline::rejectMatchesFrame( |
| 25 | + const aslam::Quaternion& q_Bkp1_Bk, aslam::VisualFrame* frame_kp1, |
| 26 | + aslam::VisualFrame* frame_k) { |
| 27 | + CHECK_NOTNULL(frame_kp1); |
| 28 | + CHECK_NOTNULL(frame_k); |
| 29 | + CHECK_GT( |
| 30 | + frame_kp1->getTimestampNanoseconds(), frame_k->getTimestampNanoseconds()); |
| 31 | + CHECK(camera_.get() == frame_kp1->getCameraGeometry().get()); |
| 32 | + |
| 33 | + if (!initialized_) { |
| 34 | + initialized_ = true; |
| 35 | + } else if (frame_k->getTimestampNanoseconds() != k_frame_timestamp_) { |
| 36 | + LOG(WARNING) << "Frames to the outlier rejection pipeline have to be " |
| 37 | + << "sequential! Resetting outlier rejection pipeline!"; |
| 38 | + reset(); |
| 39 | + } |
| 40 | + |
| 41 | + // Maintaining a consistent locking order (i.e. temporal) is very important |
| 42 | + // to avoid potential deadlocking with other trackers running in parallel |
| 43 | + frame_k->lock(); |
| 44 | + frame_kp1->lock(); |
| 45 | + |
| 46 | + if (visualize_keypoint_detections_) { |
| 47 | + cv::Mat image; |
| 48 | + aslam_cv_visualization::drawKeypoints(*frame_kp1, &image, feature_type_); |
| 49 | + const std::string topic = feature_tracking_ros_base_topic_ + |
| 50 | + "/keypoints_raw_cam" + std::to_string(cam_idx_) + |
| 51 | + "_" + feature_type_string_; |
| 52 | + visualization::RVizVisualizationSink::publish(topic, image); |
| 53 | + } |
| 54 | + |
| 55 | + CHECK(frame_k->getNumKeypointMeasurementsOfType(feature_type_)); |
| 56 | + CHECK(frame_k->hasDescriptors()); |
| 57 | + CHECK(frame_k->hasDescriptorType(feature_type_)); |
| 58 | + CHECK(frame_kp1->getNumKeypointMeasurementsOfType(feature_type_)); |
| 59 | + CHECK(frame_kp1->hasDescriptors()); |
| 60 | + CHECK(frame_kp1->hasDescriptorType(feature_type_)); |
| 61 | + |
| 62 | + // Get the relative motion of the camera using the extrinsics of the camera. |
| 63 | + aslam::Quaternion q_Ckp1_Ck = q_C_B_ * q_Bkp1_Bk * q_C_B_.inverse(); |
| 64 | + |
| 65 | + // We have to reconstruct the matches from the track ids |
| 66 | + aslam::FrameToFrameMatches matches_kp1_k; |
| 67 | + Eigen::VectorBlock<Eigen::VectorXi> track_ids_k = |
| 68 | + frame_k->getTrackIdsOfTypeMutable(feature_type_); |
| 69 | + Eigen::VectorBlock<Eigen::VectorXi> track_ids_kp1 = |
| 70 | + frame_kp1->getTrackIdsOfTypeMutable(feature_type_); |
| 71 | + |
| 72 | + std::unordered_map<int, int> track_id_to_idx_k; |
| 73 | + for (int i = 0; i < track_ids_k.size(); i++) { |
| 74 | + if (track_ids_k(i) != -1) { |
| 75 | + CHECK(track_id_to_idx_k.emplace(track_ids_k(i), i).second) |
| 76 | + << "Can't have two keypoints in one frame with the same track id"; |
| 77 | + } |
| 78 | + } |
| 79 | + |
| 80 | + std::unordered_set<int> kp1_outlier_track_ids; |
| 81 | + for (int i = 0; i < track_ids_kp1.size(); i++) { |
| 82 | + if (track_ids_kp1(i) != -1) { |
| 83 | + // If the track was previously an outlier do not keep it |
| 84 | + // and mark it for removal also in the next frame |
| 85 | + if (k_outlier_track_ids.count(track_ids_kp1(i))) { |
| 86 | + kp1_outlier_track_ids.emplace(track_ids_kp1(i)); |
| 87 | + // Keep the detection, but remove the track id |
| 88 | + track_ids_kp1(i) = -1; |
| 89 | + continue; |
| 90 | + } |
| 91 | + |
| 92 | + auto match = track_id_to_idx_k.find(track_ids_kp1(i)); |
| 93 | + if (match != track_id_to_idx_k.end()) { |
| 94 | + matches_kp1_k.emplace_back(i, match->second); |
| 95 | + } |
| 96 | + } |
| 97 | + } |
| 98 | + |
| 99 | + VLOG_IF(10, kp1_outlier_track_ids.size() > 0) |
| 100 | + << "Removed " << kp1_outlier_track_ids.size() << " matches on camera " |
| 101 | + << cam_idx_ << " with feature type " << feature_type_string_ |
| 102 | + << " because the tracks were previously disconnected by an outlier."; |
| 103 | + |
| 104 | + // Find the inlier and outlier matches based on the rotation. |
| 105 | + aslam::FrameToFrameMatches inlier_matches_kp1_k; |
| 106 | + aslam::FrameToFrameMatches outlier_matches_kp1_k; |
| 107 | + |
| 108 | + bool ransac_success = aslam::geometric_vision:: |
| 109 | + rejectOutlierFeatureMatchesTranslationRotationSAC( |
| 110 | + *frame_kp1, *frame_k, q_Ckp1_Ck, feature_type_, matches_kp1_k, |
| 111 | + outlier_settings_.deterministic, |
| 112 | + outlier_settings_.two_pt_ransac_threshold, |
| 113 | + outlier_settings_.two_pt_ransac_max_iterations, &inlier_matches_kp1_k, |
| 114 | + &outlier_matches_kp1_k); |
| 115 | + |
| 116 | + LOG_IF(WARNING, !ransac_success) |
| 117 | + << "Match outlier rejection RANSAC failed on camera " << cam_idx_ |
| 118 | + << " with feature type " << feature_type_string_ << "."; |
| 119 | + const size_t num_outliers = outlier_matches_kp1_k.size(); |
| 120 | + VLOG_IF(5, num_outliers > 0) |
| 121 | + << "Removed " << num_outliers << " outliers of " << matches_kp1_k.size() |
| 122 | + << " matches on camera " << cam_idx_ << " with feature type " |
| 123 | + << feature_type_string_ << "."; |
| 124 | + |
| 125 | + // Remove the detected outlier tracks from the frame |
| 126 | + for (const auto& outlier_match_kp1_k : outlier_matches_kp1_k) { |
| 127 | + const int idx_kp1 = outlier_match_kp1_k.first; |
| 128 | + const int outlier_track_id = track_ids_kp1(idx_kp1); |
| 129 | + |
| 130 | + kp1_outlier_track_ids.emplace(outlier_track_id); |
| 131 | + track_ids_kp1(idx_kp1) = -1; |
| 132 | + |
| 133 | + // If the track id was not valid it means the track length is now one, |
| 134 | + // so we can remove the track completely by deleting it also from the |
| 135 | + // previous frame. |
| 136 | + if (!k_valid_track_ids_.count(outlier_track_id)) { |
| 137 | + const int idx_k = outlier_match_kp1_k.second; |
| 138 | + track_ids_k(idx_k) = -1; |
| 139 | + } |
| 140 | + } |
| 141 | + |
| 142 | + if (visualize_keypoint_matches_) { |
| 143 | + cv::Mat inlier_image; |
| 144 | + aslam_cv_visualization::drawKeypointMatches( |
| 145 | + *frame_kp1, *frame_k, inlier_matches_kp1_k, feature_type_, |
| 146 | + &inlier_image); |
| 147 | + const std::string topic = |
| 148 | + feature_tracking_ros_base_topic_ + "/keypoint_matches_camera_" + |
| 149 | + std::to_string(cam_idx_) + "_" + feature_type_string_; |
| 150 | + visualization::RVizVisualizationSink::publish(topic, inlier_image); |
| 151 | + |
| 152 | + cv::Mat outlier_image; |
| 153 | + aslam_cv_visualization::drawKeypointMatches( |
| 154 | + *frame_kp1, *frame_k, outlier_matches_kp1_k, feature_type_, |
| 155 | + &outlier_image); |
| 156 | + const std::string outlier_topic = |
| 157 | + feature_tracking_ros_base_topic_ + "/keypoint_outliers_camera_" + |
| 158 | + std::to_string(cam_idx_) + "_" + feature_type_string_; |
| 159 | + visualization::RVizVisualizationSink::publish(outlier_topic, outlier_image); |
| 160 | + } |
| 161 | + |
| 162 | + // Next frame becomes the previous frame for the next iteration, so we |
| 163 | + // renew timestamp and outlier / inlier information |
| 164 | + k_frame_timestamp_ = frame_kp1->getTimestampNanoseconds(); |
| 165 | + |
| 166 | + k_valid_track_ids_.clear(); |
| 167 | + for (const auto& inlier_match_kp1_k : inlier_matches_kp1_k) { |
| 168 | + const int idx_kp1 = inlier_match_kp1_k.first; |
| 169 | + k_valid_track_ids_.emplace(track_ids_kp1(idx_kp1)); |
| 170 | + } |
| 171 | + |
| 172 | + k_outlier_track_ids.swap(kp1_outlier_track_ids); |
| 173 | + |
| 174 | + frame_kp1->unlock(); |
| 175 | + frame_k->unlock(); |
| 176 | +} |
| 177 | + |
| 178 | +void VOOutlierRejectionPipeline::reset() { |
| 179 | + k_outlier_track_ids.clear(); |
| 180 | + k_valid_track_ids_.clear(); |
| 181 | +} |
| 182 | + |
| 183 | +} // namespace feature_tracking |
0 commit comments