Skip to content

Commit b7b9608

Browse files
authored
Merge pull request #377 from ethz-asl/devel/improving_externals
Improving external feature interface and documentation
2 parents 3c4f1a5 + 8b8fb3b commit b7b9608

32 files changed

+472
-153
lines changed

.gitmodules

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -97,6 +97,3 @@
9797
[submodule "dependencies/3rdparty/libpointmatcher"]
9898
path = dependencies/3rdparty/libpointmatcher
9999
url = [email protected]:ANYbotics/libpointmatcher.git
100-
[submodule "dependencies/internal/maplab_features"]
101-
path = dependencies/internal/maplab_features
102-
url = [email protected]:ethz-asl/maplab_features.git

algorithms/feature-tracking/CMakeLists.txt

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,8 @@ cs_add_library(${PROJECT_NAME}
1111
src/feature-detection-extraction.cc
1212
src/feature-tracking-pipeline.cc
1313
src/feature-tracking-types.cc
14-
src/vo-feature-tracking-pipeline.cc)
14+
src/vo-feature-tracking-pipeline.cc
15+
src/vo-outlier-rejection-pipeline.cc)
1516

1617
##########
1718
# GTESTS #

algorithms/feature-tracking/include/feature-tracking/feature-tracking-pipeline.h

Lines changed: 1 addition & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -21,13 +21,8 @@ class FeatureTrackingPipeline {
2121

2222
protected:
2323
const std::string feature_tracking_ros_base_topic_;
24+
const bool visualize_keypoint_detections_;
2425
const bool visualize_keypoint_matches_;
25-
26-
private:
27-
virtual void initialize(const aslam::NCamera::ConstPtr& ncamera) = 0;
28-
virtual void trackFeaturesNFrame(
29-
const aslam::Transformation& T_Bk_Bkp1, aslam::VisualNFrame* nframe_k,
30-
aslam::VisualNFrame* nframe_kp1) = 0;
3126
};
3227

3328
} // namespace feature_tracking

algorithms/feature-tracking/include/feature-tracking/feature-tracking-types.h

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -75,6 +75,19 @@ struct FeatureTrackingDetectorSettings {
7575
size_t gridded_detector_num_threads_per_image;
7676
};
7777

78+
struct FeatureTrackingOutlierSettings {
79+
FeatureTrackingOutlierSettings();
80+
81+
// Threshold for the 2-pt RANSAC outlier rejection.
82+
double two_pt_ransac_threshold;
83+
// Maximum number of iterations for the outlier rejection RANSAC.
84+
size_t two_pt_ransac_max_iterations;
85+
// If the outlier rejection should be deterministic, (i.e. fixed seed).
86+
// Useful for doing experiments with repeatable results.
87+
bool deterministic;
88+
};
89+
90+
7891
} // namespace feature_tracking
7992

8093
#endif // FEATURE_TRACKING_FEATURE_TRACKING_TYPES_H_

algorithms/feature-tracking/include/feature-tracking/vo-feature-tracking-pipeline.h

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,8 @@ class VOFeatureTrackingPipeline : public FeatureTrackingPipeline {
2525
VOFeatureTrackingPipeline(
2626
const aslam::NCamera::ConstPtr& ncamera,
2727
const FeatureTrackingExtractorSettings& extractor_settings,
28-
const FeatureTrackingDetectorSettings& detector_settings);
28+
const FeatureTrackingDetectorSettings& detector_settings,
29+
const FeatureTrackingOutlierSettings& outlier_settings);
2930
virtual ~VOFeatureTrackingPipeline();
3031

3132
void initializeFirstNFrame(aslam::VisualNFrame* nframe_k);
@@ -37,10 +38,10 @@ class VOFeatureTrackingPipeline : public FeatureTrackingPipeline {
3738
aslam::FrameToFrameMatchesList* outlier_matches_kp1_k);
3839

3940
private:
40-
void initialize(const aslam::NCamera::ConstPtr& ncamera) override;
41+
void initialize(const aslam::NCamera::ConstPtr& ncamera);
4142
void trackFeaturesNFrame(
4243
const aslam::Transformation& T_Bk_Bkp1, aslam::VisualNFrame* nframe_k,
43-
aslam::VisualNFrame* nframe_kp1) override;
44+
aslam::VisualNFrame* nframe_kp1);
4445

4546
void trackFeaturesSingleCamera(
4647
const aslam::Quaternion& q_Bkp1_Bk, const size_t camera_idx,
@@ -66,6 +67,7 @@ class VOFeatureTrackingPipeline : public FeatureTrackingPipeline {
6667

6768
const FeatureTrackingExtractorSettings extractor_settings_;
6869
const FeatureTrackingDetectorSettings detector_settings_;
70+
const FeatureTrackingOutlierSettings outlier_settings_;
6971
};
7072

7173
} // namespace feature_tracking
Lines changed: 60 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,60 @@
1+
#ifndef FEATURE_TRACKING_VO_OUTLIER_REJECTION_PIPELINE_H_
2+
#define FEATURE_TRACKING_VO_OUTLIER_REJECTION_PIPELINE_H_
3+
4+
#include <sensors/external-features.h>
5+
#include <unordered_set>
6+
7+
#include "feature-tracking/feature-tracking-pipeline.h"
8+
#include "feature-tracking/feature-tracking-types.h"
9+
10+
namespace feature_tracking {
11+
12+
class VOOutlierRejectionPipeline : public FeatureTrackingPipeline {
13+
public:
14+
MAPLAB_POINTER_TYPEDEFS(VOOutlierRejectionPipeline);
15+
MAPLAB_DISALLOW_EVIL_CONSTRUCTORS(VOOutlierRejectionPipeline);
16+
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
17+
VOOutlierRejectionPipeline(
18+
const aslam::Camera::ConstPtr& camera, const int cam_idx,
19+
const aslam::Quaternion& q_C_B, const vi_map::FeatureType feature_type,
20+
const FeatureTrackingOutlierSettings& outlier_settings);
21+
virtual ~VOOutlierRejectionPipeline();
22+
23+
void rejectMatchesFrame(
24+
const aslam::Quaternion& q_Bkp1_Bk, aslam::VisualFrame* frame_kp1,
25+
aslam::VisualFrame* frame_k);
26+
27+
void reset();
28+
29+
private:
30+
aslam::Camera::ConstPtr camera_;
31+
const int cam_idx_;
32+
const aslam::Quaternion q_C_B_;
33+
const int feature_type_;
34+
const std::string feature_type_string_;
35+
36+
// Used to check that the frames being given are connected, otherwise
37+
// we have to reset the outlier and inlier information we maintain.
38+
bool initialized_;
39+
int64_t k_frame_timestamp_;
40+
41+
// We remember which tracks were marked as outliers in the previous frame
42+
// so we can continue eliminating them. This is necessary because we can't
43+
// communicate with the external feature tracker on what was discarded.
44+
// If a track stops appearing in a frame we no longer need to remember it
45+
// as an outlier, since it means the tracker has stopped tracking it. This
46+
// assumes matches are always only between two consecutive frames, but saves
47+
// a lot of memory and computation at runtime.
48+
std::unordered_set<int> k_outlier_track_ids;
49+
50+
// We remember which tracks were valid in the previous frame. This is so
51+
// that if we remove a current outlier match, we know if the observation
52+
// in the previous frame has a track length of one and can be deleted.
53+
std::unordered_set<int> k_valid_track_ids_;
54+
55+
const FeatureTrackingOutlierSettings outlier_settings_;
56+
};
57+
58+
} // namespace feature_tracking
59+
60+
#endif // FEATURE_TRACKING_VO_OUTLIER_REJECTION_PIPELINE_H_

algorithms/feature-tracking/src/feature-tracking-pipeline.cc

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,18 @@
11
#include "feature-tracking/feature-tracking-pipeline.h"
22

3+
DEFINE_bool(
4+
feature_tracker_visualize_keypoint_detections, false,
5+
"Visualize the raw keypoint detections to a ros topic.");
36
DEFINE_bool(
47
feature_tracker_visualize_keypoint_matches, false,
5-
"Flag indicating whether keypoint matches are visualized.");
8+
"Visualize the keypoint matches and the outliers.");
69

710
namespace feature_tracking {
811

912
FeatureTrackingPipeline::FeatureTrackingPipeline()
1013
: feature_tracking_ros_base_topic_("tracking/"),
14+
visualize_keypoint_detections_(
15+
FLAGS_feature_tracker_visualize_keypoint_detections),
1116
visualize_keypoint_matches_(
1217
FLAGS_feature_tracker_visualize_keypoint_matches) {}
1318

algorithms/feature-tracking/src/feature-tracking-types.cc

Lines changed: 25 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,10 @@
1-
#include "feature-tracking/feature-tracking-types.h"
2-
31
#include <gflags/gflags.h>
42
#include <glog/logging.h>
3+
#include <maplab-common/conversions.h>
54
#include <opencv2/features2d/features2d.hpp>
65

6+
#include "feature-tracking/feature-tracking-types.h"
7+
78
DEFINE_string(
89
feature_tracking_descriptor_type, "brisk",
910
"Descriptor type to compute: 'brisk' or 'freak'");
@@ -95,6 +96,19 @@ DEFINE_uint64(
9596
feature_tracking_gridded_detection_num_threads_per_image, 0u,
9697
"Number of hardware threads used for detection (0 means N_cell/2).");
9798

99+
DEFINE_double(
100+
feature_tracker_two_pt_ransac_threshold, 1.0 - cos(0.5 * kDegToRad),
101+
"Threshold for the 2-pt RANSAC used for feature tracking outlier "
102+
"removal. The error is defined as (1 - cos(alpha)) where alpha is "
103+
"the angle between the predicted and measured bearing vectors.");
104+
DEFINE_uint64(
105+
feature_tracker_two_pt_ransac_max_iterations, 200,
106+
"Max iterations for the 2-pt RANSAC used for feature tracking "
107+
"outlier removal.");
108+
DEFINE_bool(
109+
feature_tracker_deterministic, false,
110+
"If true, deterministic RANSAC outlier rejection is used.");
111+
98112
namespace feature_tracking {
99113

100114
FeatureTrackingExtractorSettings::FeatureTrackingExtractorSettings()
@@ -181,4 +195,13 @@ FeatureTrackingDetectorSettings::FeatureTrackingDetectorSettings()
181195
CHECK_GE(gridded_detector_num_grid_rows, 1u);
182196
}
183197

198+
FeatureTrackingOutlierSettings::FeatureTrackingOutlierSettings()
199+
: two_pt_ransac_threshold(FLAGS_feature_tracker_two_pt_ransac_threshold),
200+
two_pt_ransac_max_iterations(
201+
FLAGS_feature_tracker_two_pt_ransac_max_iterations),
202+
deterministic(FLAGS_feature_tracker_deterministic) {
203+
CHECK_GE(two_pt_ransac_threshold, 0.0);
204+
CHECK_LE(two_pt_ransac_threshold, 1.0);
205+
}
206+
184207
} // namespace feature_tracking

algorithms/feature-tracking/src/vo-feature-tracking-pipeline.cc

Lines changed: 27 additions & 56 deletions
Original file line numberDiff line numberDiff line change
@@ -4,39 +4,22 @@
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-
3112
namespace feature_tracking {
3213

3314
VOFeatureTrackingPipeline::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

Comments
 (0)