44#include < aslam/tracker/feature-tracker-gyro.h>
55#include < aslam/tracker/feature-tracker.h>
66#include < aslam/visualization/basic-visualization.h>
7- #include < maplab-common/conversions.h>
87#include < sensors/external-features.h>
98#include < visualization/common-rviz-visualization.h>
109
1110#include " feature-tracking/vo-feature-tracking-pipeline.h"
1211
13- DEFINE_double (
14- feature_tracker_two_pt_ransac_threshold, 1.0 - cos(0.5 * kDegToRad ),
15- "Threshold for the 2-pt RANSAC used for feature tracking outlier "
16- "removal. The error is defined as (1 - cos(alpha)) where alpha is "
17- "the angle between the predicted and measured bearing vectors.");
18-
19- DEFINE_double (
20- feature_tracker_two_pt_ransac_max_iterations, 200 ,
21- " Max iterations for the 2-pt RANSAC used for feature tracking "
22- " outlier removal." );
23-
24- DEFINE_bool (
25- feature_tracker_deterministic, false ,
26- " If true, deterministic RANSAC outlier rejection is used." );
27- DEFINE_bool (
28- detection_visualize_keypoints, false ,
29- " Visualize the raw keypoint detections to a ros topic." );
30-
3112namespace feature_tracking {
3213
3314VOFeatureTrackingPipeline::VOFeatureTrackingPipeline (
3415 const aslam::NCamera::ConstPtr& ncamera,
3516 const FeatureTrackingExtractorSettings& extractor_settings,
36- const FeatureTrackingDetectorSettings& detector_settings)
17+ const FeatureTrackingDetectorSettings& detector_settings,
18+ const FeatureTrackingOutlierSettings& outlier_settings)
3719 : first_nframe_initialized_(false ),
3820 extractor_settings_ (extractor_settings),
39- detector_settings_(detector_settings) {
21+ detector_settings_(detector_settings),
22+ outlier_settings_(outlier_settings) {
4023 initialize (ncamera);
4124}
4225
@@ -141,21 +124,19 @@ void VOFeatureTrackingPipeline::trackFeaturesSingleCamera(
141124 // Initialize keypoints and descriptors in frame_kp1
142125 detectors_extractors_[camera_idx]->detectAndExtractFeatures (frame_kp1);
143126
144- if (FLAGS_detection_visualize_keypoints) {
145- cv::Mat image;
146- cv::cvtColor (frame_kp1->getRawImage (), image, cv::COLOR_GRAY2BGR);
127+ // The default detector / tracker with always insert descriptors of type
128+ // kBinary = 0 for both BRISK and FREAK
129+ constexpr int descriptor_type =
130+ static_cast <int >(vi_map::FeatureType::kBinary );
147131
148- aslam_cv_visualization::drawKeypoints (*CHECK_NOTNULL (frame_kp1), &image);
132+ if (visualize_keypoint_detections_) {
133+ cv::Mat image;
134+ aslam_cv_visualization::drawKeypoints (*frame_kp1, &image, descriptor_type);
149135 const std::string topic = feature_tracking_ros_base_topic_ +
150136 " /keypoints_raw_cam" + std::to_string (camera_idx);
151137 visualization::RVizVisualizationSink::publish (topic, image);
152138 }
153139
154- // The default detector / tracker with always insert descriptors of type
155- // kBinary = 0 for both BRISK and FREAK
156- constexpr int descriptor_type =
157- static_cast <int >(vi_map::FeatureType::kBinary );
158-
159140 CHECK (frame_k->hasKeypointMeasurements ());
160141 CHECK (frame_k->hasDescriptors ());
161142 CHECK (frame_k->hasDescriptorType (descriptor_type));
@@ -172,31 +153,17 @@ void VOFeatureTrackingPipeline::trackFeaturesSingleCamera(
172153 aslam::FrameToFrameMatches matches_kp1_k;
173154 trackers_[camera_idx]->track (q_Ckp1_Ck, *frame_k, frame_kp1, &matches_kp1_k);
174155
175- // The tracker will return the indices with respect to the tracked feature
176- // block, so here we renormalize them so that the rest of the code can deal
177- // with them agnostically, since the descriptors are no longer needed.
178- size_t start_k, size_k, start_kp1, size_kp1;
179- frame_k->getDescriptorBlockTypeStartAndSize (
180- descriptor_type, &start_k, &size_k);
181- frame_kp1->getDescriptorBlockTypeStartAndSize (
182- descriptor_type, &start_kp1, &size_kp1);
183-
184- for (aslam::FrameToFrameMatch& match_kp1_k : matches_kp1_k) {
185- match_kp1_k.setKeypointIndexInFrameA (match_kp1_k.getKeypointIndexInFrameA () + start_kp1);
186- match_kp1_k.setKeypointIndexInFrameB (match_kp1_k.getKeypointIndexInFrameB () + start_k);
187- }
188-
189156 // Remove outlier matches.
190157 statistics::StatsCollector stat_ransac (" Twopt RANSAC (1 image) in ms" );
191158 timing::Timer timer_ransac (
192159 " VOFeatureTrackingPipeline: trackFeaturesSingleCamera - ransac" );
193160 bool ransac_success = aslam::geometric_vision::
194161 rejectOutlierFeatureMatchesTranslationRotationSAC (
195- *frame_kp1, *frame_k, q_Ckp1_Ck, matches_kp1_k,
196- FLAGS_feature_tracker_deterministic ,
197- FLAGS_feature_tracker_two_pt_ransac_threshold ,
198- FLAGS_feature_tracker_two_pt_ransac_max_iterations ,
199- inlier_matches_kp1_k, outlier_matches_kp1_k);
162+ *frame_kp1, *frame_k, q_Ckp1_Ck, descriptor_type, matches_kp1_k,
163+ outlier_settings_. deterministic ,
164+ outlier_settings_. two_pt_ransac_threshold ,
165+ outlier_settings_. two_pt_ransac_max_iterations , inlier_matches_kp1_k ,
166+ outlier_matches_kp1_k);
200167
201168 LOG_IF (WARNING, !ransac_success)
202169 << " Match outlier rejection RANSAC failed on camera " << camera_idx
@@ -207,25 +174,29 @@ void VOFeatureTrackingPipeline::trackFeaturesSingleCamera(
207174 << " matches on camera " << camera_idx << " ." ;
208175
209176 // Assign track ids.
177+ // TODO(smauq): See about clearning this one up, maybe even move this function
178+ // up from aslam into here.
210179 timing::Timer timer_track_manager (
211180 " VOFeatureTrackingPipeline: trackFeaturesSingleCamera - track manager" );
212181 track_managers_[camera_idx]->applyMatchesToFrames (
213182 *inlier_matches_kp1_k, frame_kp1, frame_k);
214183
215184 if (visualize_keypoint_matches_) {
216- cv::Mat image;
217- aslam_cv_visualization::visualizeMatches (
218- *frame_kp1, *frame_k, *inlier_matches_kp1_k, &image);
185+ cv::Mat inlier_image;
186+ aslam_cv_visualization::drawKeypointMatches (
187+ *frame_kp1, *frame_k, *inlier_matches_kp1_k, descriptor_type,
188+ &inlier_image);
219189 const std::string topic = feature_tracking_ros_base_topic_ +
220190 " /keypoint_matches_camera_" +
221191 std::to_string (camera_idx);
222- visualization::RVizVisualizationSink::publish (topic, image );
192+ visualization::RVizVisualizationSink::publish (topic, inlier_image );
223193
224194 cv::Mat outlier_image;
225- aslam_cv_visualization::visualizeMatches (
226- *frame_kp1, *frame_k, *outlier_matches_kp1_k, &outlier_image);
195+ aslam_cv_visualization::drawKeypointMatches (
196+ *frame_kp1, *frame_k, *outlier_matches_kp1_k, descriptor_type,
197+ &outlier_image);
227198 const std::string outlier_topic = feature_tracking_ros_base_topic_ +
228- " /keypoint_outlier_matches_camera_ " +
199+ " /keypoint_outliers_camera_ " +
229200 std::to_string (camera_idx);
230201 visualization::RVizVisualizationSink::publish (outlier_topic, outlier_image);
231202 }
0 commit comments