PreprintPDF Available

Abstract and Figures

Robust SLAM in large-scale environments requires fault resilience and awareness at multiple stages, from sensing and odometry estimation to loop closure. In this work, we present TBV (Trust But Verify) Radar SLAM, a method for radar SLAM that introspectively verifies loop closure candidates. TBV Radar SLAM achieves a high correct-loop-retrieval rate by combining multiple place-recognition techniques: tightly coupled place similarity and odometry uncertainty search, creating loop descriptors from origin-shifted scans, and delaying loop selection until after verification. Robustness to false constraints is achieved by carefully verifying and selecting the most likely ones from multiple loop constraints. Importantly, the verification and selection are carried out after registration when additional sources of loop evidence can easily be computed. We integrate our loop retrieval and verification method with a fault-resilient odometry pipeline within a pose graph framework. By evaluating on public benchmarks we found that TBV Radar SLAM achieves 65% lower error than the previous state of the art. We also show that it's generalizing across environments without needing to change any parameters.
Content may be subject to copyright.
TBV Radar SLAM trust but verify loop candidates
Daniel Adolfsson, Mattias Karlsson, Vladim´
ır Kubelka, Martin Magnusson, Henrik Andreasson
Abstract Robust SLAM in large-scale environments re-
quires fault resilience and awareness at multiple stages, from
sensing and odometry estimation to loop closure. In this work,
we present TBV (Trust But Verify) Radar SLAM, a method
for radar SLAM that introspectively verifies loop closure candi-
dates. TBV Radar SLAM achieves a high correct-loop-retrieval
rate by combining multiple place-recognition techniques: tightly
coupled place similarity and odometry uncertainty search, cre-
ating loop descriptors from origin-shifted scans, and delaying
loop selection until after verification. Robustness to false con-
straints is achieved by carefully verifying and selecting the most
likely ones from multiple loop constraints. Importantly, the
verification and selection are carried out after registration when
additional sources of loop evidence can easily be computed. We
integrate our loop retrieval and verification method with a fault-
resilient odometry pipeline within a pose graph framework. By
evaluating on public benchmarks we found that TBV Radar
SLAM achieves 65% lower error than the previous state of the
art. We also show that it’s generalizing across environments
without needing to change any parameters.
I. INTRODUCTION
Robust localization is key to enabling safe and reliable
autonomous systems. Achieving robustness requires careful
design at multiple stages of a localization pipeline, from
environment-tolerant sensing and pose estimation, to place
recognition and pose refinement. At each stage, a localization
and mapping pipeline should be designed for fault awareness
to detect failures and fault resilience to mitigate failures as
they inevitably occur. Today, active exteroceptive sensors
such as lidar and radar are suitable when robust uninterrupted
localization is required. Of these two, radar perception is
significantly less affected when operating within dusty envi-
ronments or under harsh weather conditions. It is currently
debated how the sensing properties affect localization and
mapping performance [1], [2]. Compared to lidar, limited
work focuses on robust and accurate radar SLAM, and none
of the existing methods include introspective fault detection.
In this letter, we propose TBV (Trust But Verify) Radar
SLAM a 2D pose-graph localization and mapping pipeline
which integrates fault resilience and fault-aware robustness
at multiple stages. A radar-only odometry front-end adds
pose nodes to the graph. In parallel, a robust loop-detection
module adds loop closure constraints such that the SLAM
back-end can optimize the graph to correct drift. TBV Radar
SLAM uses radar odometry (further only odometry), place
descriptors, and scan alignment measures to retrieve, verify,
and select between loop constraints. We achieve a high
correct-loop-retrieval rate by combining: a tightly coupled
The authors are with the MRO lab of the AASS research centre at ¨
Orebro
University, Sweden. E-mail: firstname.lastname@oru.se
This work has received funding...
Verified
VERIFY LOOP CANDIDATES
Trusted
ODOMETRY ALIGNMENTSCAN CONTEXT
Ground Truth, Est. Trajectory, Loop Closure
Query
Fig. 1: Overview and demonstration of TBV Radar SLAM
https://tinyurl.com/TBVRadarSLAM
place similarity and odometry uncertainty search, creating
place descriptors computed from origin-shifted scans, and by
delaying loop selection until after verification. Robustness,
with a high loop detection rate, is achieved by unifying
the process of place recognition and verification. Rather
than rejecting candidates early during place recognition, we
register and verify multiple loop constraints in parallel. Our
verification combines place similarity, odometry consistency,
and an alignment quality assessment automatically learned
from odometry and scans. We integrate our loop retrieval and
verification module with a robust method for radar odometry,
into a full-fledged SLAM pipeline visualized in Fig. 1. The
contributions of this letter are:
A combination of techniques for a high rate of correct
loop retrievals, including: coupled place similarity and
odometry uncertainty search, creating place descriptors
from origin-shifted scans, and selection between multi-
ple competing loop constraints.
A unified loop retrieval and verification step that jointly
considers place similarity, odometry uncertainty, and
alignment quality after registration. Multiple loop can-
didates are retrieved, registered, and verified.
We integrate these techniques with a robust odometry
estimator into a SLAM framework that pushes state
of the art in radar SLAM accuracy while generalizing
between environments without parameter tuning.
II. REL ATED WORK
Early methods for radar SLAM employ filtering [3] and
landmark graph SLAM [4]. We instead use pose-graph
SLAM based on odometry and loop constraints obtained by
arXiv:2301.04397v1 [cs.RO] 11 Jan 2023
Loop retrieval and verification (Sec.III.B & D)
Place recognition (Sec.III.B)
Pose graph optimization
(Sec.III.E)
Verification of loop candidates (Sec.III.D)
Loop
registration
Odometry estimation (Sec.III.A)
CFEAR
Radar odometry
(Sec.III.A)
Loop
verification Pose graph
Loop
constraints
Odometry
constraints
Optimizer
Descriptor
generation
(Sec.III.C.2)
Radar
Scan Context
(Sec.III.C.1&3)
loop
candidates
Registered
Scan
pairs
Learning of
alignment
verification
(Sec.III.C)
Input radar data
Radar scans
scans database
Fig. 2: Overview of TBV Radar SLAM. The main contribution is the Loop retrieval and verification module.
registering scans. Holder et al. [5] proposed a pose graph
SLAM based on automotive radar, using GLARE [6] for
place recognition. Their method uses gyroscope and wheel
odometry to provide an initial alignment guess to Iterative
Closest Point (ICP) for scan matching. Our method uses a
pose graph back-end but relies solely on a spinning radar.
Recent progress in the development of spinning 2D radar
has quickly inspired numerous works on radar odometry
estimation [1], [7]–[19], place recognition [11], [20]–[25],
topological localization [2], [21], [25] localization in over-
head imagery [26], [27] and SLAM [1], [10], [28]. Most
similar to ours is the preliminary work by Wang et a. [28],
and the seminal work on radar SLAM by Hong et al. [1].
Hong et al. [1] estimates odometry and registers loop con-
straints using KLT tracker keypoints. For place recognition,
they use adaptive thresholding to filter data, and M2DP [29]
to compute and match descriptors. The trajectory is corrected
using pose graph optimization. Our work brings a larger
focus on the introspective verification of loop constraints.
Martini et al. [21] proposed a teach-and-repeat localization
framework using a hierarchical approach. First, a place
candidate is retrieved via nearest neighbor search within
a learned metric space using the method by Saftescu et
al. [20]. Second, sensor pose is estimated (without the need
for an initial guess) by finding and registering the (globally)
optimal set of landmark matches as described by Cen et
al. [7]. Unlike [21], we use a fast local registration method,
motivated by the access of an initial alignment guess from
the place recognition module. However, we carefully verify
registration success before accepting new loop constraints.
Verification of pose estimates is essential for safety. E.g.,
such tests could have prevented a reported accident that
occurred during an automated driving test [30]. Holder
et al. [5] verify the detected loop candidates using radar
data by the condition that ICP residuals cannot exceed a
set threshold. Rather than verifying loops as a final step
(separated from loop detection), we unify loop retrieval
and verification. Some works [21], [31] use the landmark
matching compatibility matrix [7] to assess quality. Martini
et al. [21] reject place candidates based on the quality
score of the matrix. Aldera et al. [31] learn detection of
pose estimate failures from features extracted from the
eigenvectors of the compatibility matrix. Training labels are
provided by an external ground truth system. We build on
the method CorAl [32] to detect false loop candidates or
constraints. In the lidar domain, Behley et al. [33] accept
only reappearing loop candidates that are consistent with
odometry over multiple consecutive scans, we instead focus
on verification using only individual scans.
Some methods attempt to measure how observations
would constrain registration in the current scene; a low
level of constraints in one direction suggests registration
could be unstable. The measure has been used to predict the
risk of registration failure [34], [35], abstain from closing
loops when risk is high [1], or prioritize the inclusion of
loop closures accordingly [36]. We instead use odometry
uncertainty as a prior, which we combine with additional
loop evidence computed after registration. Finally, a range of
methods aims at verifying pose estimates by detecting point
cloud misalignment [30], [32], [37]. We fuse misalignment
detection [32] together with place similarity and odometry
uncertainty to achieve robust unified loop detection and
verification.
III. TBV RADA R SLAM
An overview of TBV Radar SLAM is presented in Fig. 2.
In this section, we detail the components including CFEAR
Radar Odometry (Sec. III-A), place recognition (Sec. III-
B), verification of loop candidates (Sec. III-D), and pose
graph optimization (Sec. III-E). The self-supervised training
of alignment verification (Sec. III-C) runs once during a
learning phase and is not required for online SLAM.
A. CFEAR Radar Odometry
We use the radar odometry pipeline CFEAR Radar Odom-
etry [17] (specifically the CFEAR-3 configuration). This
method takes raw polar radar sweeps as input and estimates
sensor pose and velocity. As an intermediate step, the method
computes a set of radar peaks Ptand a set of oriented surface
points Mtat time t. These representations will be referred
to in the later stages of our pipeline. CFEAR filters the radar
data by keeping the k-strongest range bins per azimuth. The
filtered point set is compensated for motion distortion and
transformed into Cartesian space, - this is also the point set
from which we extract radar peaks (Pt). A grid method is
then used to compute a set of oriented surface points Mt
from the filtered set. Odometry is estimated by finding the
pose xtin SE(2) which minimizes the sum of surface point
distances between the current scan Mtand the |K| latest
keyframes MKjointly as
f(MK,Mt,xt) = X
k∈K X
∀{i,j}∈Ccorr
wi,j ρg(mk
j, mt
i,xt),(1)
where wi,j are surface point similarity weights, ρis the
Huber loss function, and gis the pairwise distance between
surface points in the correspondence set Ccorr . A keyframe
k K is created when the distance to the previous exceeds
1.5m. This technique reduces drift and removes excessive
scans acquired when the robot remains stationary. Upon
creation of a new keyframe, odometry constraints are created
from the relative alignment between the current pose and the
latest keyframe. Odometry constraints are added to Codom
and used to correct trajectory (via pose graph optimization)
as detailed in Sec. III-E.
B. Place recognition
We attempt to unify the stages of loop closure, from
detection to constraint verification. Accordingly, we retrieve,
register, verify multiple candidates, of which one can is
selected. For that reason, we do not discard potential loop
candidates based on place similarity. Instead, we trust multi-
ple candidates to be meaningful until verified. At this point,
we select the verifiably best loop candidate, if such exist.
1) Scan Context: We build upon the place recognition
method Scan Context by Giseop Kim et al. [38], [39]. Their
method detects loops and relative orientation by matching
the query (q) scan with candidates ({c}) stored in a database
using scan descriptors. Scenes are encoded by their polar
representations into 2D descriptors Iring×sec . The 2D de-
scriptor is in turn used to create a rotation-invariant 1D
descriptor (ring key) via a ring encoding function. Loops
are detected via a two-step search: First, the query 1D
ring key is matched with the top 10 candidates via a fast
nearest neighbor (NN) search. Second, for each of the top
candidates, a sparse optimization finds the relative rotation
that minimizes a distance metric dsc(Iq,Ic): the sum of
cosine distances between descriptors columns. The candidate
cwith the lowest score (dsc) which does not exceed the fixed
threshold τis selected as loop candidate.
c= argmin
c∈C
dsc(Iq,Ic), s.t. dsc < τ. (2)
In our implementation, query descriptors are created,
matched, and stored in the database for each keyframe rather
than for each scan.
2) Descriptor generation: As described in [28], [40],
a raw polar representation such as those produced by a
spinning 2D radar, can be used directly as a Scan Context
descriptor. However, we believe that doing so poses multiple
challenges, including sensor noise, motion distortion, scene
dynamics and translation sensitivity. Thus, we create our
descriptor from multiple filtered and motion-compensated
scans. Conveniently, such processed scans are already pro-
vided by the CFEAR. We aggregate the peak detections from
keyframe qand its two neighbours in the odometry frame.
Having the radar scan represented as a sparse point cloud
in Cartesian space allows us to address translation sensitivity
in place recognition by applying the data augmentation step
(Augmented PC) from [39] before computing place descrip-
tors. We perform data augmentation by shifting the sensor
origin, i.e. by transforming Pˆqwith ±2 and ±4 m lateral
translation offsets. The original, and the 4 augmented point
clouds, are each used to compute and match descriptors, after
which the best matching pair of query/candidate is selected.
Note that by using the aggregated sparse point cloud, rather
than the dense raw radar scan, we can efficiently compute all
augmentations and corresponding descriptors. As such, the
main computational load from the augmentation technique
is due to matching of additional descriptors and not the
computation of these. The descriptor itself is created by
populating the Scan Context Iwith radar intensity readings.
Specifically, for each grid cell I(i, j)we sum the intensity
of all coinciding point intensities (of radar peaks) divided by
1000. Empty cells are set to I(i, j) = 1, which we found
increased descriptiveness compared to I(i, j)=0.
3) Coupled odometry/appearance matching: When re-
trieving loop candidates, odometry information can be used
to filter unlikely candidates. This could be done by rejecting
unlikely loop constraints. For example, if the likelihood
of the loop constraint xq,c
loop (given the estimated odometry
trajectory vc:q
odom between cand q) is close to zero:
p(xq,c
loop |vc:q
odom)0.(3)
While this strategy may provide higher tolerance to spatial
aliasing by rejecting false positives, it does not provide
means to detect the correct candidate under such circum-
stances. For that reason, we propose a coupled place similar-
ity / odometry uncertainty search, which combines Eq. 2 and
Eq. 3. Candidates are thus selected jointly by the similarity of
appearance dsc(Iq,Ic)and the similarity of odometry dq,c
odom:
c= argmin
c∈C
dsc(Iq,Ic) + dq,c
odom,
dq,c
odom = 1 p(xq ,c
loop |vc:q
odom).
(4)
We estimate p(xq,c
loop |vc:q
odom) = exp (t2
err
2σ2).
terr =max(||transl(xq)transl(xc)|| , 0)
dist(vc:q
odom).(5)
Here, transl is the translation component, is the expected
maximum spacing between loop candidates (fixed to = 5
i.e. slightly higher than the lateral augmentation distance),
and dist(vc:q
odom)is the traversed distance between the query
and loop candidate estimated by the odometry. Note that
terr quantifies the relative final position error, thus σcan be
chosen according to expected odometry quality to penalize
unlikely loops. We refrained, however, from making strong
assumptions on odometry quality, and fixed σ= 0.05; i.e., a
pessimistic assumption of 5% relative translation error.
Note that the two-step search of Scan Context requires
that odometry uncertainty is integrated already in the 1D
NN search. We do this by extending all 1D descriptors (of
size ring = 40) with odometry similarity scores (dodom) as
an extra element. (dodom) is scaled with a factor (ring/4)
to balance odometry uncertainty and appearance similarity.
C. Automatic learning of alignment verification
To improve loop closure verification, we build upon the
system CorAl [32] which learns to detect alignment errors
between two registered scans. CorAl allows us to determine
if a loop constraint is correct by formulating loop constraint
verification as a misalignment detection problem. Specifi-
cally, a loop (between scan nr qand c) is verified as correct
only if the scans are correctly aligned via the relative align-
ment xq,c
loop. During the learning phase, CorAl automatically
generates labeled training data. The input to CorAl is pairs of
odometry estimates, radar peak detections (P), and computed
sets of oriented surface points (M). These entities are used
to extract alignment quality residuals from which alignment
quality can be assessed. After the learning phase, CorAl can
verify loops by detecting alignment errors (caused e.g. by
heavy motion distortion or incorrect convergence). CorAl
also aids in distinguishing between places that differ by small
geometric details. We generate training data by repeating the
following process for each pair of consecutive keyframes.
Positive training labels (yaligned =true) and training data
Xquality are computed using the scan alignment provided by
the odometry. For each pair, the alignment quality measures
in Eq. 6 are extracted. Negative training labels (yaligned =
false) and training data are extracted similarly. However,
before extracting the alignment quality, an error is induced in
the alignment in both translation and rotation. This allows us
to learn the detection of different types of errors. Specifically,
we distribute 12 translation errors symmetrically in either the
positive or negative x or y-axis. We use 4 small (±0.5m), 4
medium (±1m) and 4 large (±2m) errors. To these errors,
we additionally induce a clockwise rotation with matching
rotation errors: small (0.5), medium (2) or large (15).
Note that the class ratio 1:12, between positive to negative
training is alleviated during learning by assigning weights
according to the inverse of class frequency.
1) Alignment measure: We extract the following align-
ment measures between each pair of scans:
Xquality = [HjHsHoCfCoCa1]T.(6)
The joint entropy (Hj) and separate entropy (Hs) are average
per-point differential entropies, extracted from point cloud
pairs of radar peak detections (Pq,Pc). These metrics are
described in-depth in [32]. We complement these measures
with a measure of overlap Ho: (Hoverlap), defined as the
portion of peaks in Pqor Pcwith a neighboring point within
the radius rin the other point cloud.
In this work, we combine these CorAl measures with
additional ones, extracted from (Mq,Mc), i.e. from pairs of
scans represented as oriented surface points. The measures
are obtained from the registration cost(Eq. 1), but with a
single keyframe and with the point-to-line cost function
(gP2L[17]). Note that these measures are already computed
during the final iteration of the registration, and this step
brings little computational overhead. Specifically, from Eq. 1
we reuse Cf:f(Mq,Mc,xq,c), the number of correspon-
dences (overlap) Co:|Ccorr|, and average surface point set
size Ca:1/2(|Mq|+|Mc|). The intuition of combining
these quality measures is that the CorAl measures (which
use small-region data association) are specialized in detecting
small errors whereas the CFEAR measures are more suitable
for larger alignment errors. We refer to [32] for details.
2) Assessing alignment: Once training data has been
computed, we train a logistic regression classifier
palign = 1/(1 + edalign ),(7a)
dalign =βXquality ,(7b)
where β1×7are the learned model parameters. We train
on discrete alignment classification here as we consider all
visible errors to be undesired. However, dalign is passed to
our loop verification module rather than palign. We found
dalign to be more suitable, as the sigmoid output palign is
insensitive to alignment change close to 0or 1.
D. Verification of loop candidates
We allow for multiple competing loop candidates ckper
query qas illustrated in Fig. 1. Each of the Ncand = 3
best matching pairs {(q, ck)}provided by the place recog-
nition module is used to compute and verify potential loop
constraints. A constraint is computed by finding the relative
alignment xq,ck
loop that minimizes Eq. 1 i.e. the distance be-
tween correspondences, similarly to the odometry module.
As an initial guess, we use the relative orientation provided
by the place recognition module. If the loop candidate was
retrieved from a match with an augmented query scan, the
corresponding augmented lateral offset is used together with
the rotation as an initial guess. Note that the local registration
method is motivated by the access to an initial guess, required
for convergence. After registration, we extract and assess
the alignment quality dalign =βXq,ck
quality following the
procedure in Sec. (III-C.1&III-C.2). Each constraint is finally
verified by combining the Scan Context distance (dsc) with
odometry uncertainty (dodom) and alignment quality (dalig n)
with a logistic regression classifier
yq,ck
loop =1
1 + eΘXq,ck
loop
, s.t. yq,ck
loop > yth,
Xq,ck
loop = [dodom dsc dalign 1]T.
(8)
The model parameters Θcan be learned via ground truth
loop labels, or simply tuned as the 4 parameters have intuitive
meaning. yth is the sensitivity threshold we rarely observe
false positives when fixed to 0.9.
We investigated two strategies for selecting loop closures
after a successful verification: (i) We select the first candidate
retrieved from the place recognition module (Ncand = 1)
the lowest Scan Context distance score dsc. (ii) We use
Ncand = 3 candidates and select the best candidate according
to our verifier the highest probability yq,ck
loop. The intuition
for strategy (i) is that the first retrieved place candidate is of-
ten the best guess, without considering registration. However,
there are cases where one of the latter candidates is preferred.
For example, registration of query and the first candidate
may fail, or subtle scene differences that distinguish places
can be hard to detect until a more thorough local analysis of
alignment has been carried out. Thus, selecting the verifiably
better loop constraint candidate is desired. We compare these
two strategies in Sec. IV-B ( T.6 and T.8) Once a loop
constraint has been verified, the loop is added to Cloop.
E. Pose Graph Optimization
We correct the odometry by solving a sparse least squares
optimization problem. We do so by minimizing Eq. 9, using
the odometry and loop constraints Codom,Cloop :
J(Y) = X
(i,j)∈Codom
eT
i,j C1
odomei,j
| {z }
odometry constraints
+X
(i,j)∈Cloop
ρ(eT
i,j C1
loopei,j )
| {z }
loop constraints
.
(9)
Y= [y1y2...yn]is the vector of optimization parameters,
e=yi,j xi,j is the difference between parameter and con-
straint, Cis the covariance matrix. We used two strategies to
compute covariance; fixed: computed from registration error
statistics C=diag([vxx =1e-2, vyy =1e-2, vθ θ =1e-3]);
dynamic: obtained from the Hessian, approximated from the
Jacobian (C= (H)1(JTJ)1) of the registration cost
(Eq. 1). Note that the dynamically obtained Cwas tuned by
a factor γto provide realistic uncertainties, discussed in [9].
Loop constraints are scaled by an additional optional factor
for (5e-5). This factor retains the high odometry quality
through pose graph optimization, and alleviates the need for
a more accurate but computationally more expensive multi-
scan loop registration
Finally, we solve argminYJ(Y)using Levenberg-
Marquardt. Note that we do not need a robust back-end
to mitigate outlier constraints (such as dynamic covariance
scaling [41] or switchable loop constraints [42]).
IV. EVALUATIO N
We evaluate our method on the Oxford [43] and
MulRan [40] datasets. Both datasets were collected by
driving a car with a roof-mounted radar. The Oxford dataset
contains 30 repetitions of a 10 km urban route. The MulRan
dataset has a wider mix of routes; from structured urban to
partly feature poor areas such as open fields and bridge cross-
ings. In MulRan, places are generally revisited in the same
driving direction. This is not the case in Oxford where
loop closure is significantly harder. From these datasets,
we selected the previously most evaluated sequences, see
Tab. (I&II). The radars used are Navtech CTS350-X, con-
figured with 4.38 cm resolution in the Oxford dataset, and
CIR204-H, with 5.9 cm resolution in the MulRan dataset.
We use standard parameters for CFEAR-3 [17], CorAl [32],
and Scan Context [38], except where explicitly mentioned.
A. Run-time performance
After the initial generation of training data, the full
pipeline including odometry and loop closure runs in real-
time. Pose graph optimization runs in a separate thread, either
continuously as new verified loop constraints are computed,
or once at the end. Run-time performance is as follows (mea-
sured on an i7-6700K CPU). Odometry: 37 ms; Generation of
training data: 236 ms/keyframe pair; Pose graph optimization
(once in the end with only odometry as prior): 992 ms @ 4k
keyframes; Loop closure (128 ms @ Ncand = 3); Descriptor
generation: 1 ms/keyframe; Detect loops: 25 ms/keyframe;
Registration: 6 ms/candidate; Verification 19 ms/candidate.
B. Ablation study loop detection
In this section, we evaluate the effect of the various aspects
of our loop detection pipeline. Loops are classified as correct
if the difference between estimated alignment and ground
truth does not exceed 4m or 2.5. This error limit was set
slightly higher than the largest pose error that we found in
the ground truth at loop locations. While we would like to
demonstrate the full capability of our system by analysis
of smaller errors, we found ground truth accuracy to be
a limiting factor. Note that the ground truth quality has
previously been discussed as a limitation [13].
We compare the impact of each technique summarized
below. Note that a later technique in the list either adapts or
replaces the former technique.
T.1 Radar Scan Context: Polar radar data is, without pre-
processing, directly downsampled into a Scan Context
descriptor [40]. We found the OpenCV interpolation op-
tion INTER AREA to yield the best results. Verification
includes only place similarity dsc.
T.2 Aggregated point cloud map: We instead create the Scan
Context descriptor by aggregating motion-compensated
peak detections from multiple scans (Sec. III-B.2).
T.3 Origin augmentation: Additional augmentations (origin-
shifted copies with lateral offsets) are matched. Out of
these, the best match is selected (Sec. III-B.2).
T.4 Alignment loop verification: Verification includes align-
ment quality dalign from Sec. III-D.
T.5 Odometry decoupled: Verification includes dodom.
T.6 Odometry coupled:dodom is embedded into the loop
retrieval search as described in Sec. III-B.3.
T.7 Separate verification: Instead of unified verification,
loops are verified separately by alignment (dalign).
T.8 Multiple candidate selection: Based on item T.6.
Ncand = 3 competing candidates {(q , ck)}are used
(previously 1). The most likely loop (yq,ck
loop) is selected.
The impact is presented in Fig. 4a for the eight Oxford
(a) T.1 (b) T.2 (c) T.3 (d) T.4 (e) T.5 (f) T.6 (g) T.8
Fig. 3: Detected loops in the Oxford dataset using the methods in Sec. IV-B. All potential loops are colored and ordered
according to success: red (dangerous failure False Positive), orange (safe failure False Negative), blue (safe failure False
Negative), green (success True Positive). Blue-colored loops differ compared to orange in that the suggested candidates
are actually correct, but no loop is predicted as likelihood doesn’t exceed the decision boundary: (yq,ck
loop < yth).
0.0 0.2 0.4 0.6 0.8 1.0
Recall
0.0
0.2
0.4
0.6
0.8
1.0
Precision
oxford
1) Radar Scan Context
2) Aggregated point cloud map
3) Origin augmentation
4) Alignment loop verification
5) Odometry decoupled
6) Odometry coupled
7) Cascaded classifier
8) Multiple candidate selection
(a) Oxford
0.0 0.2 0.4 0.6 0.8 1.0
Recall
0.0
0.2
0.4
0.6
0.8
1.0
Precision
Mulran
1) Radar Scan Context
2) Aggregated point cloud map
3) Origin augmentation
4) Alignment loop verification
5) Odometry decoupled
6) Odometry coupled
7) Cascaded classifier
8) Multiple candidate selection
(b) MulRan
Fig. 4: Loop closure performance over all sequences.
sequences, and Fig. 4b for the nine MulRan sequences. Loop
detections are visualized in Fig. 3 for the Oxford sequence
16-13-09 with yth = 0.9. The raw Scan Context ( T.1)
achieves higher recall compared to the sparse local map (T.2).
The difference is larger in MulRan, where scans are acquired
in the same moving direction, and motion distortion is less
of a challenge. Additionally, we noted that the difference
is highest within the feature-poor Riverside sequences.
This suggests that maintaining information-rich radar data is
largely advantageous compared to using a sparse local map,
especially when features are scarce. Note however that our
local mapping technique is primarily motivated by the need
for a sparse Cartesian point cloud for efficient augmentation.
Oxford is more challenging compared to MulRan as
a majority of the revisits occur in opposite road lanes
and directions. However, the augmentation technique (T.3)
allows the detection of additional candidates with higher
lateral displacement, and as expected, increases the highest
top recall, yet at a cost of lower precision. This loss of
precision can however be alleviated via alignment loop
verification (T.4). The improvement is larger in Oxford
and we believe the more structured scenes are favorable
for alignment analysis. The decoupled odometry approach
(T.5), which extends verification by including odometry
uncertainty, gives a higher tolerance to false positives. At this
point, the decision boundary can be chosen such that almost
all candidates are correctly classified. Unified verification is
preferred over separate verification (T.7). Selecting the can-
didate with the highest probability (T.8), rather than the first
place recognition candidate (T.6) yields a clear improvement
in Oxford. We believe this improvement is because our
alignment quality aids in distinguishing between places and
detecting registration failures, especially in structured scenes.
C. SLAM performance - comparative evaluation
We compare TBV Radar SLAM to previous meth-
ods for radar, lidar, and visual SLAM within the Ox-
ford and Mulran dataset. We primarily compare methods
over full trajectories i.e. Absolute Trajectory Error (ATE)
AT ERMSE =q1
nPi=n
i=1 ||transl(xest
i)transl(xgt
i))||2.
Additionally, we provide the KITTI odometry metric [48],
which computes the relative error between 100-800 m,
e.g. error over a shorter distance. ATE metrics for method
Type/modality Method Evaluation 10-12-32Training 16-13-09 17-13-26 18-14-14 18-15-20 10-11-46 16-11-53 18-14-46 Mean
ATE
ATE
SLAM/camera ORB-SLAM2 [44] [45] 7.96 7.59 7.61 24.63 12.17 7.30 3.54 9.72 10.07
Odometry/Radar CFEAR-3 (odometry used) 7.29 23.32 15.58 20.95 20.02 16.87 15.47 28.58 18.51
SLAM/Radar RadarSLAM-Full [1] [45] 9.59 11.18 5.84 21.21 7.74 13.78 7.14 6.01 10.31
SLAM/Radar MAROAM [28] From author 13.76 6.95 8.36 10.34 10.96 12.42 12.51 7.71 10.38
SLAM/Radar TBV Radar SLAM-dyn-cov-T.8 (ours) 4.22 4.30 3.37 4.04 4.27 3.38 4.98 4.27 4.10
SLAM/Radar TBV Radar SLAM-T.8 (ours) 4.07 4.04 3.58 3.79 3.83 3.14 4.39 4.33 3.90
Drift
Drift
SLAM/Lidar SuMa (Lidar - SLAM) [46] [45] 1.1/0.3p1.2/0.4p1.1/0.3p0.9/0.1p1.0/0.2p1.1/0.3p0.9/0.3p1.0/0.1p1.03/0.3p
Odometry/Radar CFEAR-3-S50 [17] [17] 1.05/0.34 1.08/0.34 1.07/0.36 1.11/0.37 1.03/0.37 1.05/0.36 1.18/0.36 1.11/0.36 1.09/0.36
Odometry/Radar CFEAR-3 (odometry used) 1.20/0.36 1.24/0.40 1.23/0.39 1.35/0.42 1.24/0.41 1.22/0.39 1.39/0.40 1.39/0.44 1.28/0.40
SLAM/Radar RadarSLAM-Full [1] [45] 1.98/0.6 1.48/0.5 1.71/0.5 2.22/0.7 1.77/0.6 1.96/0.7 1.81/0.6 1.68/0.5 1.83/0.6
SLAM/Radar MAROAM-Full [28] [28] 1.63/0.46 1.83/0.56 1.49/0.47 1.54/0.47 1.61/0.50 1.55/0.53 1.78/0.54 1.55/0.50 1.62/0.50
SLAM/Radar TBV Radar SLAM-T.8 (ours) 1.17/0.35 1.15/0.35 1.06/0.35 1.12/0.37 1.09/0.36 1.18/0.35 1.32/0.36 1.10/0.36 1.15/0.36
TABLE I: Top: Absolute Trajectory error (ATE) [m], Bottom: Drift (% translation error / deg/100 m) on the Oxford
Radar RobotCar dataset [43]. Methods marked with p finished prematurely. Methods for Radar SLAM are shadowed.
0
200
400
600
800
1000
1200
x (m)
−800
−600
−400
−200
0
200
400
y (m)
2019-01-10-12-32-52-radar-oxford-10k
Ground truth
TBV SLAM-8
CFEAR-3
(a) 10-12-32
0
200
400
600
800
1000
1200
x (m)
−800
−600
−400
−200
0
200
400
y (m)
2019-01-16-13-09-37-radar-oxford-10k
Ground truth
TBV SLAM-8
CFEAR-3
(b) 16-13-09
0
200
400
600
800
1000
1200
x (m)
−800
−600
−400
−200
0
200
400
y (m)
2019-01-17-13-26-39-radar-oxford-10k
Ground truth
TBV SLAM-8
CFEAR-3
(c) 17-13-26
0
200
400
600
800
1000
x (m)
−800
−600
−400
−200
0
200
400
y (m)
2019-01-10-11-46-21-radar-oxford-10k
Ground truth
TBV SLAM-8
CFEAR-3
(d) 10-11-46
(e) 18-14-14
0
200
400
600
800
1000
1200
x (m)
−800
−600
−400
−200
0
200
400
y (m)
2019-01-18-15-20-12-radar-oxford-10k
Ground truth
TBV SLAM-8
CFEAR-3
(f) 18-15-20
0
200
400
600
800
1000
1200
x (m)
−800
−600
−400
−200
0
200
400
y (m)
2019-01-16-11-53-11-radar-oxford-10k
Ground truth
TBV SLAM-8
CFEAR-3
(g) 16-11-53
0
200
400
600
800
1000
1200
x (m)
−800
−600
−400
−200
0
200
400
y (m)
2019-01-18-14-46-59-radar-oxford-10k
Ground truth
TBV SLAM-8
CFEAR-3
(h) 18-14-46
Fig. 5: Oxford trajectories using the proposed method TBV Radar SLAM, compared with CFEAR-3 [17] (odometry only)
and Ground truth. Initial and final pose are marked with ×and . Trajectories can be directly compared to [10], [17].
Type/Modality Method Evaluation KAIST01 KAIST02 KAIST03 DCC01 DCC02 DCC03 RIV.01 RIV.02 RIV.03 Mean
ATE
ATE
SLAM/Lidar SuMa Full [46] [1] 38.70 31.90 46.00 13.50 17.80 29.60 - - - 22.90
Odometry/Lidar KISS-ICP (odometry) [47] 17.40 17.40 17.40 15.16 15.16 15.16 49.02 49.02 49.02 27.2
Odometry/Radar CFEAR-3 [17] (odometry used) 7.53 7.58 12.21 6.39 3.67 5.40 6.45 3.87 19.44 8.06
SLAM/Radar RadarSLAM Full [45] [1] 6.90 6.00 4.20 12.90 9.90 3.90 9.00 7.00 10.70 7.80
SLAM/Radar MAROAM Full [28] [28] - - - - 5.81 - - 4.85 - -
SLAM/Radar TBV SLAM-T.8-dyn-cov (ours) 1.71 1.42 1.52 5.41 3.29 2.61 2.66 2.49 2.52 2.63
SLAM/Radar TBV SLAM-T.8-cov (ours) 1.66 1.39 1.50 5.44 3.32 2.66 2.61 2.36 1.48 2.49
Drift
Drift
SLAM/Lidar SuMa Full [46] 2.9/0.8 2.64/0.6 2.17/0.6 2.71/0.4 4.07/0.9 2.14/0.6 1.66/0.6P1.49/0.5P1.65/0.4P2.38/0.5
Odometry/Lidar KISS-ICP (odometry) [47] 2.28/0.68 2.28/0.68 2.28/0.68 2.34/0.64 2.34/0.64 2.34/0.64 2.89/0.64 2.89/0.64 2.89/0.64 2.5/0.65
Odometry/Radar CFEAR-3-s50 [17] [17] 1.48/0.65 1.51/0.63 1.59/0.75 2.09/0.55 1.38/0.47 1.26/0.47 1.62/0.62 1.35/0.52 1.19/0.37 1.50/0.56
Odometry/Radar CFEAR-3 [17] (odometry used) 1.59/0.66 1.62/0.66 1.73/0.78 2.28/0.54 1.49/0.46 1.47/0.48 1.59/0.63 1.39/0.51 1.41/0.40 1.62/0.57
SLAM/Radar RadarSLAM-Full [45] [1] 1.75/0.5 1.76/0.4 1.72/0.4 2.39/0.4 1.90/0.4 1.56/0.2 3.40/0.9 1.79/0.3 1.95/0.5 2.02/0.4
SLAM/Radar TBV SLAM-T.8 (ours) 1.01/0.30 1.03/0.30 1.08/0.35 2.01/0.27 1.35/0.25 1.14/0.22 1.25/0.35 1.09/0.30 0.99/0.18 1.22/0.28
TABLE II: Top: Absolute Trajectory error (ATE), Bottom: Drift (% translation error / deg/100 m) on the MulRan dataset [40].
−300
−200
−100
0
100
200
300
x (m)
−600
−500
−400
−300
−200
−100
0
100
y (m)
KAIST01
Ground truth
TBV SLAM-8
CFEAR-3
(a) KAIST01
−100
0
100
200
300
400
500
x (m)
−600
−500
−400
−300
−200
−100
0
y (m)
KAIST02
Ground truth
TBV SLAM-8
CFEAR-3
(b) KAIST02
−100
0
100
200
300
400
500
600
x (m)
−600
−500
−400
−300
−200
−100
0
y (m)
KAIST03
Ground truth
TBV SLAM-8
CFEAR-3
(c) KAIST03
−100
0
100
200
300
400
x (m)
−500
−400
−300
−200
−100
0
y (m)
DCC01
Ground truth
TBV SLAM-8
CFEAR-3
(d) DCC01
0
100
200
300
400
500
x (m)
−500
−400
−300
−200
−100
0
100
y (m)
DCC02
Ground truth
TBV SLAM-8
CFEAR-3
(e) DCC02
0
100
200
300
400
500
x (m)
−500
−400
−300
−200
−100
0
y (m)
DCC03
Ground truth
TBV SLAM-8
CFEAR-3
(f) DCC03
0
100
200
x (m)
0
200
400
600
800
1000
1200
1400
1600
y (m)
Riverside01
Ground truth
TBV SLAM-8
CFEAR-3
(g) RIV.01
0
200
x (m)
−500
−250
0
250
500
750
1000
1250
y (m)
Riverside02
Ground truth
TBV SLAM-8
CFEAR-3
(h) RIV.02
−200 0
x (m)
−750
−500
−250
0
250
500
750
y (m)
Riverside03
Ground truth
TBV SLAM-8
CFEAR-3
(i) RIV.03 (j) VolvoCE - forest (k) Kvarntorp - mine
Fig. 6: TBV Radar SLAM,CFEAR-3 [17] (odometry only), and Ground truth. First (×) and final() pose are indicated.
MAROAM [28] was kindly computed and provided by Wang
et al. for this letter. We tuned our parameters on the Oxford
sequence 10-12-32 and evaluated the performance of
SLAM on all other Oxford and MulRan sequences.
The estimated trajectories are depicted in Fig. 5 and
Fig. 6(a-i). We found that TBV effortlessly closes loops
and corrects odometry in all sequences. ATE is substantially
corrected over the full trajectory, with slightly reduced drift
(Tab. I & Tab. II). TBV outperforms previous methods for
radar SLAM in terms of ATE and drift over all sequences.
Hence, we conclude that our method improves the state
of the art in radar SLAM. Surprisingly, we did not observe
any improvement from using dynamic covariance (dyn-cov)
compared to fixed. The Hessian-approximated covariance oc-
casionally under- or over-estimates the odometry uncertainty
[49] and thus deteriorates the optimization process.
D. Generalization to off-road environments
Finally, we tested TBV on the sequences Kvarntorp
and VolvoCE from the Diverse ORU Radar Dataset [16],
see footnote for a demo1.Kvarntorp is an underground
mine with partly feature poor sections, while VolvoCE is a
mixed environment with forest and open fields. Trajectories
are visualized in Fig. 6.(j-k). We found that TBV was able
to produce smooth and globally consistent maps, through
1ORU dataset download: https://tinyurl.com/radarDataset.
Demo video: https://tinyurl.com/TBV-KvarntorpVolvo.
substantially different environments, including challenging
road conditions without any parameter changes.
V. CONCLUSIONS
We proposed TBV Radar SLAM a real-time method
for robust and accurate large-scale SLAM using a spin-
ning 2D radar. We showed that loop candidate retrieval
can be largely improved by origin-shifting, coupled place
similarity/odometry uncertainty search, and selecting the
most likely loop constraint as proposed by our verification
model. A high level of loop robustness was achieved by
carefully verifying loop constraints based on multiple sources
of information, such as place similarity, consistency with
odometry uncertainty, and alignment quality assessed after
registration. We evaluated TBV on two public datasets and
demonstrated a substantial improvement to the state of the art
in radar SLAM, making radar an attractive option to lidar for
robust and accurate localization. Quantitative and qualitative
experiments demonstrated a high level of generalization
across environments. Some findings in our ablation study
suggest that heavy filtering is undesired as it discards details
that are important for place recognition. Thus, in the future,
we will explore building detailed and dense representations
of scenes, fully utilizing the geometric information richness,
uniquely provided by spinning FMCW radar.
REFERENCES
[1] Z. Hong, Y. Petillot, A. Wallace, and S. Wang, “RadarSLAM: A
robust simultaneous localization and mapping system for all weather
conditions,” IJRR, vol. 41, no. 5, pp. 519–542, 2022.
[2] K. Burnett, Y. Wu, D. J. Yoon, A. P. Schoellig, and T. D. Barfoot,
“Are we ready for radar to replace lidar in all-weather mapping and
localization?” RAL, vol. 7, no. 4, pp. 10 328–10 335, 2022.
[3] J. W. Marck, A. Mohamoud, E. vd Houwen, and R. van Heijster,
“Indoor radar SLAM: A radar application for vision and GPS denied
environments, in 2013 EuRAD, 2013, pp. 471–474.
[4] F. Schuster, C. G. Keller, M. Rapp, M. Haueis, and C. Curio,
“Landmark based radar SLAM using graph optimization,” in ITSC,
2016, pp. 2559–2564.
[5] M. Holder, S. Hellwig, and H. Winner, “Real-time pose graph SLAM
based on radar, in IV, 2019, pp. 1145–1151.
[6] M. Himstedt, J. Frost, S. Hellbach, H.-J. B¨
ohme, and E. Maehle,
“Large scale place recognition in 2d lidar scans using geometrical
landmark relations,” in IROS, 2014, pp. 5030–5035.
[7] S. H. Cen and P. Newman, “Precise ego-motion estimation with
millimeter-wave radar under diverse and challenging conditions,” in
ICRA, 2018, pp. 6045–6052.
[8] S. H. Cen and P. Newman, “Radar-only ego-motion estimation in
difficult settings via graph matching, in ICRA, 2019, pp. 298–304.
[9] D. Barnes, R. Weston, and I. Posner, “Masking by moving: Learning
distraction-free radar odometry from pose information,” in CoRL, ser.
CoRL, L. P. Kaelbling, D. Kragic, and K. Sugiura, Eds., vol. 100.
PMLR, 30 Oct–01 Nov 2020, pp. 303–316.
[10] Z. Hong, Y. Petillot, and S. Wang, “RadarSLAM: Radar based large-
scale SLAM in all weathers,” in IROS, 2020, pp. 5164–5170.
[11] D. Barnes and I. Posner, “Under the radar: Learning to predict robust
keypoints for odometry estimation and metric localisation in radar,
in ICRA, 2020, pp. 9484–9490.
[12] Y. S. Park, Y. S. Shin, and A. Kim, “PhaRaO: Direct radar odometry
using phase correlation,” in ICRA, 2020, pp. 2617–2623.
[13] P.-C. Kung, C.-C. Wang, and W.-C. Lin, “A normal distribution
transform-based radar odometry designed for scanning and automotive
radars,” 2021.
[14] K. Burnett, A. P. Schoellig, and T. D. Barfoot, “Do we need to
compensate for motion distortion and doppler effects in spinning radar
navigation?” IEEE RAL, vol. 6, no. 2, pp. 771–778, 2021.
[15] K. Burnett, D. J. Yoon, A. P. Schoellig, and T. D. Barfoot, “Radar
odometry combining probabilistic estimation and unsupervised feature
learning,” 2021.
[16] D. Adolfsson, M. Magnusson, A. Alhashimi, A. J. Lilienthal, and
H. Andreasson, “CFEAR radarodometry - conservative filtering for
efficient and accurate radar odometry, in IROS, 2021, pp. 5462–5469.
[17] D. Adolfsson, M. Magnusson, A. Alhashimi, A. J. Lilienthal, and
H. Andreasson, “Lidar-level localization with radar? The CFEAR
approach to accurate, fast and robust large-scale radar odometry in
diverse environments, T-RO, pp. 1–20, 2022.
[18] R. Aldera, M. Gadd, D. De Martini, and P. Newman, “What goes
around: Leveraging a constant-curvature motion constraint in radar
odometry, RAL, vol. 7, no. 3, pp. 7865–7872, 2022.
[19] R. Weston, M. Gadd, D. De Martini, P. Newman, and I. Posner, “Fast-
mbym: Leveraging translational invariance of the fourier transform for
efficient and accurate radar odometry, in ICRA, 2022, pp. 2186–2192.
[20] S. Saftescu, M. Gadd, D. De Martini, D. Barnes, and P. Newman,
“Kidnapped radar: Topological radar localisation using rotationally-
invariant metric learning, in ICRA, 2020, pp. 4358–4364.
[21] D. De Martini, M. Gadd, and P. Newman, “kRadar++: Coarse-to-fine
FMCW scanning radar localisation,” Sensors, vol. 20, no. 21, 2020.
[22] D. Williams, M. Gadd, D. De Martini, and P. Newman, “Fool Me
Once: Robust Selective Segmentation via Out-of-Distribution Detec-
tion with Contrastive Learning, 2021.
[23] M. Gadd, D. De Martini, and P. Newman, “Look around you:
Sequence-based radar place recognition with learned rotational invari-
ance,” in 2020 IEEE/ION (PLANS), 2020, pp. 270–276.
[24] H. Yin, X. Xu, Y. Wang, and R. Xiong, “Radar-to-lidar: Heterogeneous
place recognition via joint learning,” Frontiers in Robotics and AI,
2021.
[25] H. Yin, R. Chen, Y. Wang, and R. Xiong, “Rall: End-to-end radar
localization on lidar map using differentiable measurement model,
IEEE TITS, vol. 23, no. 7, pp. 6737–6750, 2022.
[26] T. Y. Tang, D. De Martini, D. Barnes, and P. Newman, “RSL-net:
Localising in satellite images from a radar on the ground,” RAL, vol. 5,
no. 2, pp. 1087–1094, 2020.
[27] T. Y. Tang, D. D. Martini, S. Wu, and P. Newman, “Self-supervised
learning for using overhead imagery as maps in outdoor range sensor
localization,” IJRR, vol. 40, no. 12-14, pp. 1488–1509, 2021.
[28] D. Wang, Y. Duan, X. Fan, C. Meng, J. Ji, and Y. Zhang, “Maroam:
Map-based radar slam through two-step feature selection,” 2022.
[Online]. Available: https://arxiv.org/abs/2210.13797
[29] L. He, X. Wang, and H. Zhang, “M2dp: A novel 3d point cloud
descriptor and its application in loop closure detection,” in IROS.
IEEE, 2016, pp. 231–237.
[30] N. Akai, Y. Akagi, T. Hirayama, T. Morikawa, and H. Murase, “De-
tection of localization failures using markov random fields with fully
connected latent variables for safe lidar-based automated driving, T-
ITS, vol. 23, no. 10, pp. 17 130–17 142, 2022.
[31] R. Aldera, D. D. Martini, M. Gadd, and P. Newman, “What could go
wrong? introspective radar odometry in challenging environments, in
2019 IEEE (ITSC), 2019, pp. 2835–2842.
[32] D. Adolfsson, M. Castellano-Quero, M. Magnusson, A. J. Lilienthal,
and H. Andreasson, “CorAl: Introspection for robust radar and lidar
perception in diverse environments using differential entropy, RAS,
p. 104136, 2022.
[33] J. Behley and C. Stachniss, “Efficient surfel-based SLAM using 3D
laser range data in urban environments, in Robotics: Science and
Systems, vol. 2018, 2018, p. 59.
[34] S. Nobili, G. Tinchev, and M. Fallon, “Predicting alignment risk to
prevent localization failure, in ICRA, 2018, pp. 1003–1010.
[35] M. Castellano Quero, T. P. Kucner, and M. Magnusson, “Alignability
maps for ensuring high-precision localization,” in 13th IROS Workshop
on Planning, Perception, Navigation for Intelligent Vehicles.
[36] C. E. Denniston, Y. Chang, A. Reinke, K. Ebadi, G. S. Sukhatme,
L. Carlone, B. Morrell, and A.-a. Agha-mohammadi, “Loop closure
prioritization for efficient and scalable multi-robot SLAM, 2022.
[Online]. Available: https://arxiv.org/abs/2205.12402
[37] H. Almqvist, M. Magnusson, T. P. Kucner, and A. J. Lilienthal,
“Learning to detect misaligned point clouds,” JFR, vol. 35, no. 5,
pp. 662–677, 2018.
[38] G. Kim and A. Kim, “Scan context: Egocentric spatial descriptor for
place recognition within 3D point cloud map,” in IROS, Oct. 2018.
[39] G. Kim, S. Choi, and A. Kim, “Scan context++: Structural place recog-
nition robust to rotation and lateral variations in urban environments,
IEEE Transactions on Robotics, vol. 38, no. 3, pp. 1856–1874, 2022.
[40] G. Kim, Y. S. Park, Y. Cho, J. Jeong, and A. Kim, “Mulran:
Multimodal range dataset for urban place recognition,” in ICRA, Paris,
May 2020.
[41] P. Agarwal, G. D. Tipaldi, L. Spinello, C. Stachniss, and W. Burgard,
“Robust map optimization using dynamic covariance scaling, in 2013
IEEE ICRA, 2013, pp. 62–69.
[42] N. S¨
underhauf and P. Protzel, “Switchable constraints for robust pose
graph SLAM,” in IROS, 2012, pp. 1879–1884.
[43] D. Barnes, M. Gadd, P. Murcutt, P. Newman, and I. Posner, “The
oxford radar robotcar dataset: A radar extension to the oxford robotcar
dataset,” in ICRA, 2020, pp. 6433–6438.
[44] R. Mur-Artal and J. D. Tard´
os, “ORB-SLAM2: An open-source SLAM
system for monocular, stereo, and RGB-D cameras, IEEE T-RO,
vol. 33, no. 5, pp. 1255–1262, 2017.
[45] Z. Hong, Y. Petillot, A. Wallace, and S. Wang, “Radar SLAM: A
robust SLAM system for all weather conditions,” 2021.
[46] J. Behley and C. Stachniss, “Efficient surfel-based SLAM using 3D
laser range data in urban environments, in Systems (RSS), 2018.
[47] I. Vizzo, T. Guadagnino, B. Mersch, L. Wiesmann, J. Behley,
and C. Stachniss, “KISS-ICP: In Defense of Point-to-Point
ICP Simple, Accurate, and Robust Registration If Done the
Right Way, arXiv preprint, 2022. [Online]. Available: https:
//arxiv.org/pdf/2209.15397.pdf
[48] A. Geiger, P. Lenz, and R. Urtasun, “Are we ready for autonomous
driving? the KITTI vision benchmark suite,” in Pattern Recognition
(CVPR), 2012.
[49] D. Landry, F. Pomerleau, and P. Gigu`
ere, “Cello-3d: Estimating the
covariance of icp in the real world, in ICRA, 2019, pp. 8190–8196.
ResearchGate has not been able to resolve any citations for this publication.
Article
Full-text available
Robust and accurate pose estimation of a robotic platform, so-called sensor-based odometry, is an essential part of many robotic applications. While many sensor odometry systems made progress by adding more complexity to the ego-motion estimation process, we move in the opposite direction. By removing a majority of parts and focusing on the core elements, we obtain a surprisingly effective system that is simple to realize and can operate under various environmental conditions using different LiDAR sensors. Our odometry estimation approach relies on point-to-point ICP combined with adaptive thresholding for correspondence matching, a robust kernel, a simple but widely applicable motion compensation approach, and a point cloud subsampling strategy. This yields a system with only a few parameters that in most cases do not even have to be tuned to a specific LiDAR sensor. Our system performs on par with state-of-the-art methods under various operating conditions using different platforms using the same parameters: automotive platforms, UAV-based operation, vehicles like segways, or handheld LiDARs. We do not require integrating IMU data and solely rely on 3D point clouds obtained from a wide range of 3D LiDAR sensors, thus, enabling a broad spectrum of different applications and operating conditions. Our open-source system operates faster than the sensor frame rate in all presented datasets and is designed for real-world scenarios.
Article
Full-text available
Most of the recent automated driving systems assume the accurate functioning of localization. Unanticipated errors cause localization failures and result in failures in automated driving. An exact localization failure detection is necessary to ensure safety in automated driving; however, detection of the localization failures is challenging because sensor measurement is assumed to be independent of each other in the localization process. Owing to the assumption, the entire relation of the sensor measurement is ignored. Consequently, it is difficult to recognize the misalignment between the sensor measurement and the map when partial sensor measurement overlaps with the map. This paper proposes a method for the detection of localization failures using Markov random fields with fully connected latent variables. The full connection enables to take the entire relation into account and contributes to the exact misalignment recognition. Additionally, this paper presents localization failure probability calculation and efficient distance field representation methods. We evaluate the proposed method using two types of datasets. The first dataset is the SemanticKITTI dataset, whereby four methods are compared with the proposed method. The comparison results reveal that the proposed method achieves the most accurate failure detection. The second dataset is created based on log data acquired from the demonstrations that we conducted in Japanese public roads. The dataset includes several localization failure scenes. We apply the failure detection methods to the dataset and confirm that the proposed method achieves exact and immediate failure detection.
Conference Paper
Full-text available
This paper presents an accurate, highly efficient and learning free method for large-scale radar odometry estimation. By using a simple filtering technique that keeps the strongest returns, we produce a clean radar data representation and reconstruct surface normals for efficient and accurate scan matching. Registration is carried out by minimizing a point-to-line metric and robustness to outliers is achieved using a Huber loss. Drift is additionally reduced by jointly registering the latest scan to a history of keyframes. We found that our odometry pipeline generalize well to different sensor models and datasets without changing a single parameter. We evaluate our method in three widely different environments and demonstrate an improvement over spatially cross validated state-of-the-art with an overall translation error of 1.76% in a public urban radar odometry benchmark, running merely on a single laptop CPU thread at 55 Hz.
Article
This article presents an accurate, highly efficient, and learning-free method for large-scale odometry estimation using spinning radar, empirically found to generalize well across very diverse environments—outdoors, from urban to woodland, and indoors in warehouses and mines—without changing parameters. Our method integrates motion compensation within a sweep with one-to-many scan registration that minimizes distances between nearby oriented surface points and mitigates outliers with a robust loss function. Extending our previous approach conservative filtering for efficient and accurate radar odometry (CFEAR), we present an in-depth investigation on a wider range of datasets, quantifying the importance of filtering, resolution, registration cost and loss functions, keyframe history, and motion compensation. We present a new solving strategy and configuration that overcomes previous issues with sparsity and bias, and improves our state-of-the-art by 38%, thus, surprisingly, outperforming radar simultaneous localization and mapping (SLAM) and approaching lidar SLAM. The most accurate configuration achieves 1.09% error at 5 Hz on the Oxford benchmark, and the fastest achieves 1.79% error at 160 Hz.
Article
This letter presents a method that leverages vehicle motion constraints to refine data associations in a point-based radar odometry system. By using the strong prior on how a non-holonomic robot is constrained to move smoothly through its environment, we develop the necessary framework to estimate ego-motion from a single landmark association rather than considering all of these correspondences at once. This allows for informed outlier detection of poor matches that are a dominant source of pose estimate error. By refining the subset of matched landmarks, we see an absolute decrease of 2.15% (from 4.68% to 2.53%) in translational error, approximately halving the error in odometry (reducing by 45.94%) than when using the full set of correspondences. This contribution is relevant to other point-based odometry implementations that rely on a range sensor and provides a lightweight and interpretable means of incorporating vehicle dynamics for ego-motion estimation.
Article
We present an extensive comparison between three topometric localization systems: radar-only, lidar-only, and a cross-modal radar-to-lidar system across varying seasonal and weather conditions using the Boreas dataset. Contrary to our expectations, our experiments showed that our lidar-only pipeline achieved the best localization accuracy even during a snowstorm. Our results seem to suggest that the sensitivity of lidar localization to moderate precipitation has been exaggerated in prior works. However, our radar-only pipeline was able to achieve competitive accuracy with a much smaller map. Furthermore, radar localization and radar sensors still have room to improve and may yet prove valuable in extreme weather or as a redundant backup system.
Article
Multi-robot SLAM systems in GPS-denied environments require loop closures to maintain a drift-free centralized map. With an increasing number of robots and size of the environment, checking and computing the transformation for all the loop closure candidates becomes computationally infeasible. In this work, we describe a loop closure module that is able to prioritize which loop closures to compute based on the underlying pose graph, the proximity to known beacons, and the characteristics of the point clouds. We validate this system in the context of the DARPA Subterranean Challenge and on numerous challenging underground datasets and demonstrate the ability of this system to generate and maintain a map with low error. We find that our proposed techniques are able to select effective loop closures which results in 51% mean reduction in median error when compared to an odometric solution and 75% mean reduction in median error when compared to a baseline version of this system with no prioritization. We also find our proposed system is able to find a lower error in the mission time of one hour when compared to a system that processes every possible loop closure in four and a half hours. The code and dataset for this work can be found https://github.com/NeBula-Autonomy/LAMP
Article
This paper presents CorAl: a principled, intuitive, and generalizable method to measure the quality of alignment between pairs of point clouds, which learns to detect alignment errors in a self-supervised manner. CorAl compares the differential entropy in the point clouds separately with the entropy in their union to account for entropy inherent to the scene. By making use of dual entropy measurements, we obtain a quality metric that is highly sensitive to small alignment errors and still generalizes well to unseen environments. In this work, we extend our previous work on lidar-only CorAl to radar data by proposing a two-step filtering technique that produces highquality point clouds from noisy radar scans. Thus we target robust perception in two ways: by introducing a method that introspectively assesses alignment quality, and applying it to inherently robust sensor modalities. We show that our filtering technique combined with CorAl can be applied to the problem of alignment classification, and detect small alignment errors in urban settings with up to 98% accuracy, and with up to 96% if trained only in a different environment. Our lidar and radar experiments demonstrate that CorAl outperforms previous methods both on the ETH lidar benchmark, which includes several indoor and outdoor environments, and the large-scale Oxford and MulRan radar data sets for urban traffic scenarios, and also enables a high degree of generalization across substantially different environments without the need of retraining.
Article
A Simultaneous Localization and Mapping (SLAM) system must be robust to support long-term mobile vehicle and robot applications. However, camera and LiDAR based SLAM systems can be fragile when facing challenging illumination or weather conditions which degrade the utility of imagery and point cloud data. Radar, whose operating electromagnetic spectrum is less affected by environmental changes, is promising although its distinct sensor model and noise characteristics bring open challenges when being exploited for SLAM. This paper studies the use of a Frequency Modulated Continuous Wave radar for SLAM in large-scale outdoor environments. We propose a full radar SLAM system, including a novel radar motion estimation algorithm that leverages radar geometry for reliable feature tracking. It also optimally compensates motion distortion and estimates pose by joint optimization. Its loop closure component is designed to be simple yet efficient for radar imagery by capturing and exploiting structural information of the surrounding environment. Extensive experiments on three public radar datasets, ranging from city streets and residential areas to countryside and highways, show competitive accuracy and reliability performance of the proposed radar SLAM system compared to the state-of-the-art LiDAR, vision and radar methods. The results show that our system is technically viable in achieving reliable SLAM in extreme weather conditions on the RADIATE Dataset, for example, heavy snow and dense fog, demonstrating the promising potential of using radar for all-weather localization and mapping.