Content uploaded by Daniel Adolfsson
Author content
All content in this area was uploaded by Daniel Adolfsson on Apr 20, 2023
Content may be subject to copyright.
IEEE ROBOTICS AND AUTOMATION LETTERS. PREPRINT VERSION. ACCEPTED APRIL 2023 1
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 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 cou-
pled 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 robust odometry
pipeline within a pose graph framework. By evaluation 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 generalizes across environments without needing to change
any parameters. We provide the open-source implementation at
https://github.com/dan11003/tbv slam public
Index Terms—SLAM, Localization, Radar, Introspection
I. INTRODUCTION
ROBUST localization is key to enabling safe and reli-
able 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 lo-
calization 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 environments 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
Manuscript received: January, 10, 2023; Revised March, 13, 2023; Accepted
April, 13, 2023. This paper was recommended for publication by Editor Javier
Civera upon evaluation of the Associate Editor and Reviewers’ comments.
This work was supported by Sweden’s Innovation Agency under grant number
2021-04714 (Radarize), and 2019-05878 (TAMMP).
The authors are with the MRO lab of the AASS research centre at
¨
Orebro University, Sweden. First author: Dla.Adolfsson@gmail.com,
co-authors firstname.lastname@oru.se
Digital Object Identifier (DOI): see top of this page.
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
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 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, and creating place descrip-
tors from origin-shifted scans.
•A verification step that jointly considers place similarity,
odometry uncertainty, and alignment quality computed
after registration. Verification and loop retrieval mutually
benefit each other by selecting the loop constraint with
the highest verified confidence.
We integrate these techniques with a robust odometry estima-
tor into an online SLAM framework that pushes the state of
the art in radar SLAM accuracy while generalizing between
environments without retuning parameters.
2 IEEE ROBOTICS AND AUTOMATION LETTERS. PREPRINT VERSION. ACCEPTED APRIL 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.
II. RE LATE D WO RK
Recent progress in the development of spinning 2D radar
has inspired work on odometry estimation [1], [3]–[12], place
recognition [13]–[18], topometric [2], [14] and overhead im-
agery [19] localization, and SLAM [1], [20], [21].
Essential to both SLAM and topometric localization, is
recognition of previously seen places, followed by careful
refinement of the relative pose. Hong et al. [1] use adaptive
thresholding to filter data for computing place descriptors.
Loop candidates are retrieved using M2DP [22], and con-
straints are computed by registering sets of KLT tracker
keypoints. Our work, however, brings a larger focus on the
introspective verification of loop constraints. Martini et al. [14]
proposed a teach-and-repeat framework with loop retrieval
using [13]. Registration is carried out globally–without initial
guess–by finding and minimizing the distance between the
optimal set of landmark matches as described by Cen et al [3].
In contrast, we use a fast local registration method, with an
initial guess from place recognition as an initial alignment
guess. However, we carefully verify registration success before
accepting new loop constraints.
Verification of pose estimates is essential for safety and
could have prevented an accident that occurred during an
automated driving test [23]. Today, visual, lidar, and radar
SLAM frequently adopts geometrical consistency for loop
verification. For visual SLAM, RANSAC is commonly used
for verification [24]. Thresholding based on the ICP quality
measure (i.e., the squared point-to-point distance) is more
frequently used for lidar [25], [26], and radar [27]. In these
cases, verification step runs in cascade, independently of
accepting loop retrievals. In contrast, we present a unified
approach that verifies loop retrieval and computed alignment
jointly. One family of methods proposes improved quality
measures [28]–[30] for verification. We build upon [28]. In
contrast to the formerly mentioned methods, some works addi-
tionally consider the relation between measurements, for lidar
map localization [23], radar odometry [31], and topometric
localization [14]. Martini et al. [14] and Aldera et al. [31]
use the landmark matching compatibility matrix [3] to assess
quality. Martini [14] reject place candidates based on the
quality score of the matrix. Aldera [31] detects pose estimate
failures from eigenvectors features of the compatibility matrix.
Detection is learned with supervision from an external ground
truth system. Our method use automatic generation of training
data without additional sensors.
A complementary verification technique is temporal con-
sistency, which requires consistency over consecutive frames.
The technique has been adopted in lidar [32] and visual
SLAM [33]. We focus on verifying individual frames which
enables loop detection from short overlapping segments.
Gomez-Ojeda et al. [34] use prior assumption of localization
quality, with a maximum displacement as part of loop verifica-
tion. We do not embed hard constraints but penalize candidates
that are unlikely given reasonable assumption of drift. Finally,
some methods use an early risk assessment by measuring how
range measurements could constrain registration. A low level
of constraints in one direction suggests registration was [34],
or could be unstable [35]. The measure has been used to
abstain from [1] or prioritize inclusion of loop closures [36],
or plan motion accordingly [37]. We instead rely on geometric
verification after registration.
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 align-
ment 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 Odome-
try [10] (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 com-
putes a set of radar peaks Ptand a set of oriented surface
points Mtat time t. These sets are reused for other modules.
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 Mtfrom 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 (m) 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 the set Codom
ADOLFSSON et al.: TBV RADAR SLAM – TRUST BUT VERIFY LOOP CANDIDATES 3
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, and verify multiple candidates, of which one can
be selected. For that reason, we don’t discard potential loop
candidates based on place similarity. Instead, we trust multiple
candidates to be meaningful until verified. At this point, we
select the verifiably best candidate, if such exists.
1) Scan Context: We build upon the place recognition
method Scan Context by Kim et al. [38], [39]. Their method
detects loops and relative orientation by matching the most
recently acquired scan (referred to as query q) with candidates
({c}) stored in a database using scan descriptors. Scenes are
encoded by their polar representations into 2D descriptors
Iring×sec . The 2D descriptor 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∈Cand
dsc(Iq,Ic), s.t. dsc < τ. (2)
In our implementation, query descriptors are created, matched,
and stored in the database for each keyframe.
2) Descriptor generation: As described in [21], [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 provided by the CFEAR. We
aggregate the peak detections from keyframe qand its two
neighbors 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 Pqwith ±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 by
distinguishing unoccupied from possibly occupied cells.
3) Coupled odometry/appearance matching: When retriev-
ing loop candidates, odometry uncertainty information can
be used to directly reject unlikely loop constraints. 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)
the proposed constraint is false and can be discarded. We
choose however to jointly consider the odometry uncertainty
and place similarity to obtain more robust loop-retrievals.
Accordingly, we propose a coupled place similarity / odom-
etry uncertainty search, which combines Eq. 2 and Eq. 3. Can-
didates 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 choose to estimate the likelihood in Eq. 3 using a Gaussian
distribution 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 [28] 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. Specifically,
a loop (between scan nr qand c) is verified as correct only
if the scans are correctly aligned via the relative alignment
xq,c
loop. During the learning phase, CorAl automatically gen-
erates 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
4 IEEE ROBOTICS AND AUTOMATION LETTERS. PREPRINT VERSION. ACCEPTED APRIL 2023
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 alignment
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). Average per-point
entropy is a measure of point cloud crispness – lower crispness
following registration indicates misalignment. These metrics
are described in-depth in [28]. 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 mea-
sures are obtained from the registration cost(Eq. 1), but with
a single keyframe and with the point-to-line cost function
(gP2L[10]). 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 correspondences
(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 [28] for details.
2) Assessing alignment: Once training data has been com-
puted, we train a logistic regression classifier
palign = 1/(1 + e−dalign ), dalign =βXquality ,(7)
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 between
correspondences, similar 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-C1&III-C2). 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 often 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, it is added to the set 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 C−1
i,j ei,j
| {z }
odometry constraints
+X
(i,j)∈Cloop
αρ(eT
i,j C−1
i,j ei,j )
| {z }
loop constraints
.
(9)
Y= [y1y2...yn]is the vector of optimization parame-
ters, e=yi,j −xi,j is the difference between parameter
ADOLFSSON et al.: TBV RADAR SLAM – TRUST BUT VERIFY LOOP CANDIDATES 5
and constraint, ρis the robust Cauchy loss function, 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 [5]. Loop con-
straints are optionally scaled by (α=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. EVALUATION
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 crossings.
In MulRan, places are frequently revisited multiple times
with similar speeds in the same direction and road lane. This
is not the case in the Oxford dataset where loop closure
is significantly harder, and the mapping scenario is more
realistic. From these datasets, we selected the previously most
evaluated sequences, see Tab. (I&II). The radars used are
Navtech CTS350-X, configured 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 [10], CorAl [28], 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 with online capabil-
ity. 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 (measured on a
2015 mid-range consumer desktop CPU: i7-6700K) is as
follows: Odometry: 37 ms/scan; 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 [8].
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-B2).
T.3 Origin augmentation: Additional augmentations (origin-
shifted copies with lateral offsets) are matched. Out of
these, the best match is selected (Sec. III-B2).
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-B3.
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 =
3competing 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
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
(a) T.1 (b) T.2 (c) T.3 (d) T.4 (e) T.5 (f) T.6 (g) T.8
Fig. 3: We visualize the impact of loop retrieval and verification for the methods in Sec. IV-B within the Oxford dataset. All
potential loops are colored and ordered according to loop retrieval correctness and confidence (yq,ck
loop): red (dangerous failure
– false loop with undesired high confidence), orange (safe failure – false loop but with desired low confidence), blue (safe
failure, correct loop with undesired low confidence), green (success, correct loop with desired high confidence).
6 IEEE ROBOTICS AND AUTOMATION LETTERS. PREPRINT VERSION. ACCEPTED APRIL 2023
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.
challenge. Additionally, we noted that the difference is highest
within the feature-poor Riverside sequences. This suggests
that maintaining information-rich radar data is 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 di-
rections. However, the augmentation technique (T.3) allows the
detection of additional candidates with higher lateral displace-
ment, and as expected, increases the highest top recall, yet at a
cost of lower precision. This loss of precision can however be
alleviated by including verification based on carefully assessed
alignment quality (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. However, coupling
odometry uncertainty into the candidate search (T.6) substan-
tially increases recall to over 90%, effectively constraining
the search space. Verifying candidates jointly with multiple
sources (T.6) circumvents early discarding of candidates based
on the mistakenly low confidence, thus preferred over cascaded
verification (T.7). Unified verification and loop retrieval (T.8)–
which extends (T.6) by selecting between multiple candidates–
allows for the selection of non-primary retrievals with higher
computed alignment quality and confidence. Thus, increasing
retrieval and precision in the Oxford dataset.
C. SLAM performance – comparative evaluation
We compare TBV Radar SLAM to previous methods for
radar, lidar, and visual SLAM within the Oxford and Mulran
dataset. We primarily compare methods over full trajecto-
ries i.e. Absolute Trajectory Error (ATE) AT ERM SE =
q1
nPi=n
i=1 ||transl(yest
i)−transl(ygt
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 MAROAM [21] was kindly
Type/modality Method Eval. 10-12-32
Training
16-13-09 17-13-26 18-14-14 18-15-20 10-11-46 16-11-53 18-14-46 Mean
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 [21] 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
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 [10] (Offline) [10] 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 [21] [21] 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: ATE [m], Bottom: Drift (% translation error / deg/100 m) on the Oxford dataset [43]. Methods marked with
p finished prematurely. Methods for Radar SLAM are shaded. The best and second best radar results are bold/underlined.
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
0
200
400
600
800
1000
x (m)
−800
−600
−400
−200
0
200
400
y (m)
2019-01-18-14-14-42-radar-oxford-10k
Ground truth
TBV SLAM-8
CFEAR-3
(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 [10] (odometry only)
and Ground truth. First (×) and final(□) positions are marked. Trajectories can be directly compared to [10], [20].
ADOLFSSON et al.: TBV RADAR SLAM – TRUST BUT VERIFY LOOP CANDIDATES 7
Type/Modality Method Eval. KAIST01 KAIST02 KAIST03 DCC01 DCC02 DCC03 RIV.01 RIV.02 RIV.03 Mean
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 [10] (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 [21] [21] - - - - 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
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 [10] [10] 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 [10] (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].
Methods for Radar SLAM are shaded. The best and second best radar results are marked in bold/underlined.
−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 [10] (odometry only), and Ground truth. First (×) and final(□) positions are marked.
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 [10], 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 visu-
alized in Fig. 6.(j-k). We found that TBV was able to produce
1ORU dataset download: https://tinyurl.com/radarDataset. Demo video:
https://tinyurl.com/TBV-KvarntorpVolvo.
smooth and globally consistent maps, through substantially
different environments, including challenging road conditions
– without any parameter changes.
V. CONCLUSIONS
We proposed TBV Radar SLAM – a method for robust and
accurate large-scale SLAM using a spinning 2D radar. We
showed that loop 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 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 three public datasets
and demonstrated a substantial improvement to the state of
the art, while generalizing to new environments, making
radar an attractive option to lidar for robust and accurate
localization. Some findings in our ablation study suggest that
heavy filtering is undesired as it discards important details 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.
8 IEEE ROBOTICS AND AUTOMATION LETTERS. PREPRINT VERSION. ACCEPTED APRIL 2023
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] 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.
[4] S. H. Cen and P. Newman, “Radar-only ego-motion estimation in
difficult settings via graph matching,” in ICRA, 2019, pp. 298–304.
[5] 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.
[6] 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.
[7] Y. S. Park, Y. S. Shin, and A. Kim, “PhaRaO: Direct radar odometry
using phase correlation,” in ICRA, 2020, pp. 2617–2623.
[8] P.-C. Kung, C.-C. Wang, and W.-C. Lin, “A normal distribution
transform-based radar odometry designed for scanning and automotive
radars,” 2021.
[9] K. Burnett, D. J. Yoon, A. P. Schoellig, and T. Barfoot, “Radar Odometry
Combining Probabilistic Estimation and Unsupervised Feature Learn-
ing,” in Proceedings of Robotics: Science and Systems, Virtual, July
2021.
[10] 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,” IEEE Transactions on Robotics, vol. 39, no. 2, pp. 1476–
1495, 2023.
[11] 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.
[12] 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.
[13] 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.
[14] D. De Martini, M. Gadd, and P. Newman, “kRadar++: Coarse-to-fine
FMCW scanning radar localisation,” Sensors, vol. 20, no. 21, 2020.
[15] M. Gadd, D. De Martini, and P. Newman, “Contrastive learning for
unsupervised radar place recognition,” in ICAR, 2021, pp. 344–349.
[16] M. Gadd, D. De Martini, and P. Newman, “Look around you: Sequence-
based radar place recognition with learned rotational invariance,” in 2020
IEEE/ION (PLANS), 2020, pp. 270–276.
[17] H. Yin, X. Xu, Y. Wang, and R. Xiong, “Radar-to-lidar: Heterogeneous
place recognition via joint learning,” Frontiers in Robotics and AI, 2021.
[18] 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.
[19] 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.
[20] Z. Hong, Y. Petillot, and S. Wang, “RadarSLAM: Radar based large-
scale SLAM in all weathers,” in IROS, 2020, pp. 5164–5170.
[21] D. Wang, Y. Duan, X. Fan, C. Meng, J. Ji, and Y. Zhang, “Maroam:
Map-based radar slam through two-step feature selection,” 2022.
[22] 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.
[23] 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.
[24] C. Cadena, L. Carlone, H. Carrillo, Y. Latif, D. Scaramuzza, J. Neira,
I. Reid, and J. J. Leonard, “Past, present, and future of simultaneous
localization and mapping: Toward the robust-perception age,” IEEE
Transactions on Robotics, vol. 32, no. 6, pp. 1309–1332, 2016.
[25] T. Shan, B. Englot, D. Meyers, W. Wang, C. Ratti, and D. Rus, “Lio-sam:
Tightly-coupled lidar inertial odometry via smoothing and mapping,” in
IROS, 2020, pp. 5135–5142.
[26] M. Vlaminck, H. Luong, and W. Philips, “Have i seen this place before?
a fast and robust loop detection and correction method for 3d lidar slam,”
Sensors, vol. 19, no. 1, 2019.
[27] M. Holder, S. Hellwig, and H. Winner, “Real-time pose graph SLAM
based on radar,” in IV, 2019, pp. 1145–1151.
[28] 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.
[29] H. Almqvist, M. Magnusson, T. P. Kucner, and A. J. Lilienthal, “Learn-
ing to detect misaligned point clouds,” JFR, vol. 35, no. 5, pp. 662–677,
2018.
[30] H. Yin, L. Tang, X. Ding, Y. Wang, and R. Xiong, “A failure detection
method for 3d lidar based localization,” in 2019 Chinese Automation
Congress (CAC), 2019, pp. 4559–4563.
[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] 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.
[33] C. Campos, R. Elvira, J. J. G. Rodr´
ıguez, J. M. M. Montiel, and
J. D. Tard´
os, “Orb-slam3: An accurate open-source library for visual,
visual–inertial, and multimap slam,” IEEE Transactions on Robotics,
vol. 37, no. 6, pp. 1874–1890, 2021.
[34] R. Gomez-Ojeda, F.-A. Moreno, D. Zu˜
niga-No¨
el, D. Scaramuzza, and
J. Gonzalez-Jimenez, “Pl-slam: A stereo slam system through the com-
bination of points and line segments,” IEEE Transactions on Robotics,
vol. 35, no. 3, pp. 734–746, 2019.
[35] S. Nobili, G. Tinchev, and M. Fallon, “Predicting alignment risk to
prevent localization failure,” in ICRA, 2018, pp. 1003–1010.
[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.
[37] 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.
[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,” IEEE
Robotics and Automation Letters (RA-L), vol. 8, no. 2, pp. 1029–1036,
2023.
[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.