Skip to content

Commit d9b0b23

Browse files
committed
Added outlier rejection for externally tracked features
1 parent 599e696 commit d9b0b23

File tree

7 files changed

+308
-9
lines changed

7 files changed

+308
-9
lines changed

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 #
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_
Lines changed: 183 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,183 @@
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

algorithms/online-map-builders/include/online-map-builders/stream-map-builder.h

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33

44
#include <Eigen/Dense>
55
#include <algorithm>
6+
#include <feature-tracking/vo-outlier-rejection-pipeline.h>
67
#include <landmark-triangulation/pose-interpolator.h>
78
#include <map-resources/resource-conversion.h>
89
#include <memory>
@@ -201,6 +202,12 @@ class StreamMapBuilder {
201202
common::TemporalBuffer<vi_map::ExternalFeaturesMeasurement::ConstPtr>>
202203
external_features_measurement_temporal_buffers_;
203204
int64_t external_features_sync_tolerance_ns_;
205+
std::unordered_map<aslam::SensorId, pose_graph::VertexId>
206+
external_features_previous_vertex_ids_;
207+
std::unordered_map<
208+
aslam::SensorId,
209+
std::unique_ptr<feature_tracking::VOOutlierRejectionPipeline>>
210+
external_features_outlier_rejection_pipelines_;
204211

205212
static constexpr size_t kKeepNMostRecentImages = 10u;
206213
};

algorithms/online-map-builders/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,4 +16,5 @@
1616
<depend>vi_map</depend>
1717
<depend>vi_map_helpers</depend>
1818
<depend>vio_common</depend>
19+
<depend>feature_tracking</depend>
1920
</package>

algorithms/online-map-builders/src/stream-map-builder.cc

Lines changed: 54 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,3 @@
1-
#include "online-map-builders/stream-map-builder.h"
2-
31
#include <aslam/common/stl-helpers.h>
42
#include <aslam/common/time.h>
53
#include <aslam/frames/visual-frame.h>
@@ -13,6 +11,8 @@
1311
#include <vio-common/map-update.h>
1412
#include <vio-common/vio-types.h>
1513

14+
#include "online-map-builders/stream-map-builder.h"
15+
1616
DEFINE_bool(
1717
map_builder_save_image_as_resources, false,
1818
"Store the images associated with the visual frames to the map resource "
@@ -1081,12 +1081,12 @@ void StreamMapBuilder::notifyExternalFeaturesMeasurementBuffer() {
10811081
if (!queries_.getClosestVertexIdByTimestamp(
10821082
timestamp_ns_measurement, external_features_sync_tolerance_ns_,
10831083
&closest_vertex_id, &delta_ns)) {
1084-
LOG(WARNING)
1084+
/*LOG(WARNING)
10851085
<< "[StreamMapBuilder] Could not attach external features "
10861086
<< "measurement, because the timestamp is not close enough to "
10871087
<< "a vertex in the pose graph (delta = " << delta_ns << "ns > "
10881088
<< external_features_sync_tolerance_ns_
1089-
<< "ns)! timestamp_ns: " << timestamp_ns_measurement << ".";
1089+
<< "ns)! timestamp_ns: " << timestamp_ns_measurement << ".";*/
10901090
continue;
10911091
}
10921092

@@ -1099,10 +1099,9 @@ void StreamMapBuilder::notifyExternalFeaturesMeasurementBuffer() {
10991099
<< " of external feature sensor " << external_features_sensor_id
11001100
<< " is not attached to ";
11011101

1102-
const size_t target_camera_index =
1103-
external_features_sensor.getTargetCameraIndex();
1102+
const size_t cam_idx = external_features_sensor.getTargetCameraIndex();
11041103
aslam::VisualFrame::Ptr frame =
1105-
closest_vertex.getVisualFrameShared(target_camera_index);
1104+
closest_vertex.getVisualFrameShared(cam_idx);
11061105

11071106
frame->lock();
11081107

@@ -1164,6 +1163,54 @@ void StreamMapBuilder::notifyExternalFeaturesMeasurementBuffer() {
11641163

11651164
closest_vertex.expandVisualObservationContainersIfNecessary();
11661165

1166+
// Perform outlier rejection on the externally added tracks
1167+
// TODO(smauq): add parameter in config file for this
1168+
auto it_vertex_id = external_features_previous_vertex_ids_.find(
1169+
external_features_sensor_id);
1170+
if (it_vertex_id == external_features_previous_vertex_ids_.end()) {
1171+
aslam::Camera::ConstPtr camera = closest_vertex.getCamera(cam_idx);
1172+
aslam::Quaternion q_C_B =
1173+
closest_vertex.getNCameras()->get_T_C_B(cam_idx).getRotation();
1174+
const feature_tracking::FeatureTrackingOutlierSettings outlier_settings;
1175+
1176+
external_features_outlier_rejection_pipelines_.emplace(
1177+
external_features_sensor_id,
1178+
new feature_tracking::VOOutlierRejectionPipeline(
1179+
camera, cam_idx, q_C_B, external_features_sensor.getFeatureType(),
1180+
outlier_settings));
1181+
external_features_previous_vertex_ids_.emplace(
1182+
external_features_sensor_id, closest_vertex_id);
1183+
} else {
1184+
CHECK(external_features_outlier_rejection_pipelines_.count(
1185+
external_features_sensor_id));
1186+
feature_tracking::VOOutlierRejectionPipeline& outlier_pipeline =
1187+
*external_features_outlier_rejection_pipelines_
1188+
[external_features_sensor_id];
1189+
1190+
if (!map_->hasVertex(it_vertex_id->second)) {
1191+
outlier_pipeline.reset();
1192+
LOG(WARNING) << "Skipping outlier removal because previous vertex is "
1193+
<< "no longer in map due to submapping.";
1194+
} else {
1195+
vi_map::Vertex& prev_vertex = map_->getVertex(it_vertex_id->second);
1196+
1197+
aslam::VisualFrame::Ptr prev_frame =
1198+
prev_vertex.getVisualFrameShared(cam_idx);
1199+
1200+
// TODO(smauq): Interpolate here would improve accuracy
1201+
aslam::Quaternion q_Bkp1_Bk =
1202+
closest_vertex.get_T_M_I().getRotation().inverse() *
1203+
prev_vertex.get_T_M_I().getRotation();
1204+
1205+
outlier_pipeline.rejectMatchesFrame(
1206+
q_Bkp1_Bk, frame.get(), prev_frame.get());
1207+
}
1208+
1209+
// Current vertex is now the previously seen one
1210+
external_features_previous_vertex_ids_[external_features_sensor_id] =
1211+
closest_vertex_id;
1212+
}
1213+
11671214
// Make info message more verbose
11681215
VLOG(3) << "[StreamMapBuilder] Attached a new external features "
11691216
<< "measurement for vertex " << closest_vertex_id;

0 commit comments

Comments
 (0)