-
Notifications
You must be signed in to change notification settings - Fork 124
/
Multi_Tracker_Example.py
474 lines (386 loc) · 18.6 KB
/
Multi_Tracker_Example.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
#!/usr/bin/env python
"""
Comparing Multiple Trackers On Manoeuvring Targets
==================================================
"""
# %%
# This example shows how multiple trackers can be compared against each other using the same
# set of detections.
# %%
# This notebook creates groundtruth with manoeuvring motion, generates detections using a sensor,
# and attempts to track the groundtruth using the
# Extended Kalman Filter (EKF), Unscented Kalman Filter (UKF),
# the Particle Filter (PF), and the Extended Sliding Innovation Filter (ESIF).
# Each of these trackers assumes a constant velocity transition model. The trackers are compared
# against each other using distance-error metrics, with the capability of displaying other metrics
# for the user to explore. The aim of this example is to display the effectiveness of
# different trackers when tasked with following a manoeuvring target with non-linear detections.
# %%
# Layout
# ^^^^^^
# The layout of this example is as follows:
#
# 1) The ground truth is created using multiple transition models
# 2) The non-linear detections are generated once per time step using a bearing-range sensor
# 3) Each tracker is initialised and run on the detections
# 4) The results are plotted, and tracking metrics displayed for the user to explore
# %%
# 1) Create Groundtruth
# ^^^^^^^^^^^^^^^^^^^^^
# Firstly, we initialise the ground truth states:
import numpy as np
import datetime
from stonesoup.types.array import StateVector, CovarianceMatrix
from stonesoup.types.state import State, GaussianState
start_time = datetime.datetime.now()
np.random.seed(2)
initial_state_mean = StateVector([[0], [0], [0], [0]])
initial_state_covariance = CovarianceMatrix(np.diag([4, 0.5, 4, 0.5]))
timestep_size = datetime.timedelta(seconds=1)
number_steps = 20
initial_state = GaussianState(initial_state_mean, initial_state_covariance)
# %%
# Next, we initialise the transition models used to generate the ground truth. Here, we say that
# the targets will mostly go straight ahead with a constant velocity, but will sometimes turn
# left or right. This is implemented using the :class:`~.SwitchMultiTargetGroundTruthSimulator`.
from stonesoup.models.transition.linear import (
CombinedLinearGaussianTransitionModel, ConstantVelocity, KnownTurnRate)
# initialise the transition models the ground truth can use
constant_velocity = CombinedLinearGaussianTransitionModel(
[ConstantVelocity(0.05), ConstantVelocity(0.05)])
turn_left = KnownTurnRate([0.05, 0.05], np.radians(20))
turn_right = KnownTurnRate([0.05, 0.05], np.radians(-20))
# create a probability matrix - how likely the ground truth will use each transition model,
# given its current model
model_probs = np.array([[0.7, 0.15, 0.15], # keep straight, turn left, turn right
[0.4, 0.6, 0.0], # go straight, keep turning left, turn right
[0.4, 0.0, 0.6]]) # go straight, turn left, keep turning right
# %%
from stonesoup.simulator.simple import SwitchMultiTargetGroundTruthSimulator
from stonesoup.types.state import GaussianState
# generate truths
n_truths = 3
xmin = 0
xmax = 40
ymin = 0
ymax = 40
preexisting_states = []
for i in range(0, n_truths):
x = np.random.randint(xmin, xmax) - 1 # x position of initial state
y = np.random.randint(ymin, ymax) - 1 # y position of initial state
y_vel = np.random.randint(-20, 20) / 10 # x velocity will start between -2 and 2
x_vel = np.random.randint(-20, 20) / 10 # y velocity will start between -2 and 2
preexisting_states.append(StateVector([x, x_vel, y, y_vel]))
# %%
# Now we have initialised everything, so we can generate the ground truth:
ground_truth_gen = SwitchMultiTargetGroundTruthSimulator(
initial_state=initial_state,
transition_models=[constant_velocity, turn_left, turn_right],
model_probs=model_probs, # put in matrix from above
number_steps=number_steps, # how long we want each track to be
timestep=timestep_size,
birth_rate=0,
death_probability=0,
preexisting_states=preexisting_states
)
# %%
# This has created ground truth that has some twists and turns in it, which we will use to
# generate detections.
# %%
# 2) Generate detections using a bearing-range sensor
# ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
#
# The next step is to create a sensor and use it to generate detections from the targets.
# The sensor we use in this example is a radar with imperfect measurements in bearing-range space.
#
# First we initialise the radar:
from stonesoup.sensor.radar import RadarBearingRange
# Create the sensor
sensor = RadarBearingRange(
ndim_state=4,
position_mapping=[0, 2], # Detecting x and y
noise_covar=np.diag([np.radians(0.2), 0.2]), # Radar doesn't take perfect measurements
clutter_model=None, # Can add clutter model in future if desired
)
# %%
# Now we place the sensor into the simulation:
from stonesoup.platform import FixedPlatform
platform = FixedPlatform(State(StateVector([20, 0, 0, 0])), position_mapping=[0, 2],
sensors=[sensor])
# %%
# Now we run the sensor and create detections:
from itertools import tee
from stonesoup.simulator.platform import PlatformDetectionSimulator
detector = PlatformDetectionSimulator(ground_truth_gen, platforms=[platform])
detector, *detectors = tee(detector, 6)
# Enables multiple trackers to run on the same detections
# %%
# We put the detections and ground truths into sets so that we can plot them:
detections = set()
ground_truth = set()
for time, dets in detector:
detections |= dets
ground_truth |= ground_truth_gen.groundtruth_paths
# %%
# And now we plot the ground truth and detections:
from stonesoup.plotter import Plotterly
plotter = Plotterly()
plotter.plot_ground_truths(ground_truth, [0, 2])
plotter.plot_measurements(detections, [0, 2])
plotter.plot_sensors(sensor)
plotter.fig
# %%
# 3) Initialise and run each tracker on the detections
# ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
# With the detections now generated, our focus turns to creating and running the trackers.
# This section of the notebook is quite long because each tracker requires an initiator, deleter,
# detector, data associator, and updater. However, all of these things are standard
# stonesoup building blocks.
#
# Firstly, we approximate the transition model of the target. Here we assume a constant
# velocity model,
# which will be wrong due to the fact that we designed the targets to sometimes turn left or right.
# We do this to test how effectively each tracking algorithm can perform against
# target behaviour that doesn't move exactly as predicted.
transition_model_estimate = CombinedLinearGaussianTransitionModel([ConstantVelocity(0.5),
ConstantVelocity(0.5)])
# Tracking algorithm incorrectly estimates the type of path the truth takes
# %%
# Next, we initialise the predictors, updaters, hypothesisers, data associators, and deleter.
# The particle filter requires a resampler as part of its updater.
# Note that the ESIF is a slight extension of the EKF and uses an EKF predictor.
from stonesoup.predictor.kalman import ExtendedKalmanPredictor, UnscentedKalmanPredictor
from stonesoup.predictor.particle import ParticlePredictor
# introduce the predictors
predictor_EKF = ExtendedKalmanPredictor(transition_model_estimate)
predictor_UKF = UnscentedKalmanPredictor(transition_model_estimate)
predictor_PF = ParticlePredictor(transition_model_estimate)
# ######################################################################
from stonesoup.resampler.particle import ESSResampler
resampler = ESSResampler()
# ######################################################################
from stonesoup.updater.kalman import ExtendedKalmanUpdater, UnscentedKalmanUpdater
from stonesoup.updater.slidinginnovation import ExtendedSlidingInnovationUpdater
from stonesoup.updater.particle import ParticleUpdater
# introduce the updaters
updater_EKF = ExtendedKalmanUpdater(sensor)
updater_UKF = UnscentedKalmanUpdater(sensor)
updater_ESIF = ExtendedSlidingInnovationUpdater(measurement_model=None,
layer_width=10 * np.diag(sensor.noise_covar))
updater_PF = ParticleUpdater(measurement_model=None, resampler=resampler)
# ######################################################################
from stonesoup.hypothesiser.distance import DistanceHypothesiser
from stonesoup.measures import Mahalanobis
# introduce the hypothesisers
hypothesiser_EKF = DistanceHypothesiser(predictor_EKF, updater_EKF,
measure=Mahalanobis(), missed_distance=4)
hypothesiser_UKF = DistanceHypothesiser(predictor_UKF, updater_UKF,
measure=Mahalanobis(), missed_distance=4)
hypothesiser_ESIF = DistanceHypothesiser(predictor_EKF, updater_ESIF,
measure=Mahalanobis(), missed_distance=4)
hypothesiser_PF = DistanceHypothesiser(predictor_PF, updater_PF,
measure=Mahalanobis(), missed_distance=4)
# ######################################################################
from stonesoup.dataassociator.neighbour import GNNWith2DAssignment
# introduce the data associators
data_associator_EKF = GNNWith2DAssignment(hypothesiser_EKF)
data_associator_UKF = GNNWith2DAssignment(hypothesiser_UKF)
data_associator_ESIF = GNNWith2DAssignment(hypothesiser_ESIF)
data_associator_PF = GNNWith2DAssignment(hypothesiser_PF)
# ######################################################################
from stonesoup.deleter.time import UpdateTimeDeleter
# create a deleter
deleter = UpdateTimeDeleter(datetime.timedelta(seconds=5), delete_last_pred=True)
# %%
# Now we introduce the initial predictors which will be used in the data associator
# in the track initiators:
init_transition_model = CombinedLinearGaussianTransitionModel(
(ConstantVelocity(1), ConstantVelocity(1)))
init_predictor_EKF = ExtendedKalmanPredictor(init_transition_model)
init_predictor_UKF = UnscentedKalmanPredictor(init_transition_model)
init_predictor_PF = ParticlePredictor(init_transition_model)
# %%
# The final step before running the trackers is to create the initiators:
from stonesoup.initiator.simple import MultiMeasurementInitiator
initiator_EKF = MultiMeasurementInitiator(
GaussianState(
np.array([[20], [0], [10], [0]]), # Prior State
np.diag([1, 1, 1, 1])),
measurement_model=None,
deleter=deleter,
data_associator=GNNWith2DAssignment(
DistanceHypothesiser(init_predictor_EKF, updater_EKF, Mahalanobis(), missed_distance=5)),
updater=updater_EKF,
min_points=2
)
# ######################################################################
initiator_UKF = MultiMeasurementInitiator(
GaussianState(
np.array([[20], [0], [10], [0]]), # Prior State
np.diag([1, 1, 1, 1])),
measurement_model=None,
deleter=deleter,
data_associator=GNNWith2DAssignment(
DistanceHypothesiser(init_predictor_UKF, updater_UKF, Mahalanobis(), missed_distance=5)),
updater=updater_UKF,
min_points=2
)
# ######################################################################
initiator_ESIF = MultiMeasurementInitiator(
GaussianState(
np.array([[20], [0], [10], [0]]), # Prior State
np.diag([1, 1, 1, 1])),
measurement_model=None,
deleter=deleter,
data_associator=GNNWith2DAssignment(
DistanceHypothesiser(init_predictor_EKF, updater_ESIF, Mahalanobis(), missed_distance=5)),
updater=updater_ESIF,
min_points=2
)
# %%
# The initiator for the particle filter works differently, so is shown below for clarity:
from stonesoup.initiator.simple import GaussianParticleInitiator
from stonesoup.types.state import GaussianState
from stonesoup.initiator.simple import SimpleMeasurementInitiator
prior_state = GaussianState(
StateVector([20, 0, 10, 0]),
np.diag([1, 1, 1, 1]) ** 2)
initiator_Part = SimpleMeasurementInitiator(prior_state, measurement_model=None,
skip_non_reversible=True)
initiator_PF = GaussianParticleInitiator(number_particles=2000,
initiator=initiator_Part,
use_fixed_covar=False)
# %%
# Now we run the trackers and store the tracks in sets for plotting:
from stonesoup.tracker.simple import MultiTargetTracker
kalman_tracker_EKF = MultiTargetTracker( # Runs the tracker
initiator=initiator_EKF,
deleter=deleter,
detector=detectors[0],
data_associator=data_associator_EKF,
updater=updater_EKF,
)
tracks_EKF = set()
for step, (time, current_tracks) in enumerate(kalman_tracker_EKF, 1):
tracks_EKF.update(current_tracks)
# Stores the tracks in a set for plotting
# #######################################################################
kalman_tracker_UKF = MultiTargetTracker(
initiator=initiator_UKF,
deleter=deleter,
detector=detectors[1],
data_associator=data_associator_UKF,
updater=updater_UKF,
)
tracks_UKF = set()
for step, (time, current_tracks) in enumerate(kalman_tracker_UKF, 1):
tracks_UKF.update(current_tracks)
# ##########################################################################
kalman_tracker_ESIF = MultiTargetTracker(
initiator=initiator_ESIF,
deleter=deleter,
detector=detectors[2],
data_associator=data_associator_EKF,
updater=updater_ESIF,
)
tracks_ESIF = set()
for step, (time, current_tracks) in enumerate(kalman_tracker_ESIF, 1):
tracks_ESIF.update(current_tracks)
# ##########################################################################
tracker_PF = MultiTargetTracker(
initiator=initiator_PF,
deleter=deleter,
detector=detectors[3],
data_associator=data_associator_PF,
updater=updater_PF,
)
tracks_PF = set()
for step, (time, current_tracks) in enumerate(tracker_PF, 1):
tracks_PF.update(current_tracks)
# %%
# Finally, we plot the results:
plotter.plot_tracks(tracks_EKF, [0, 2], track_label="EKF", line=dict(color="orange"),
uncertainty=False)
plotter.plot_tracks(tracks_UKF, [0, 2], track_label="UKF", line=dict(color="blue"),
uncertainty=False)
plotter.plot_tracks(tracks_PF, [0, 2], track_label="PF", line=dict(color="brown"),
uncertainty=False)
plotter.plot_tracks(tracks_ESIF, [0, 2], track_label="ESIF", line=dict(color="green"),
uncertainty=False)
plotter.fig
# %%
# 4) Calculate and display metrics to show effectiveness of different tracking algorithms
# ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
#
# The final part of this example is to calculate metrics that can determine how well each tracking
# algorithm followed the target. None will be perfect due to the sensor measurement noise and error
# in data association where multiple tracks meet, but some will perform better than others.
#
# This section of the example follows code from the metrics example, which is also used in
# the sensor management tutorials. More complete documentation can be found there.
#
# Firstly, we calculate the Optimal Sub-Pattern Assignment (OSPA) distance at each time
# step for each tracker. This is a measure of how far the calculated tracks are
# from the ground truth. We first initialise the metrics before plotting:
tracking_filters = ['EKF', 'UKF', 'PF', 'ESIF']
# %%
from stonesoup.metricgenerator.ospametric import OSPAMetric
ospa_generators = [OSPAMetric(c=40, p=1,
generator_name=f'{tracking_filter} OSPA metrics',
tracks_key=f'tracks_{tracking_filter}',
truths_key='truths'
)
for tracking_filter in tracking_filters]
from stonesoup.metricgenerator.tracktotruthmetrics import SIAPMetrics
from stonesoup.measures import Euclidean
siap_generators = [SIAPMetrics(position_measure=Euclidean((0, 2)),
velocity_measure=Euclidean((1, 3)),
generator_name=f'{tracking_filter} SIAP metrics',
tracks_key=f'tracks_{tracking_filter}',
truths_key='truths'
)
for tracking_filter in tracking_filters]
from stonesoup.metricgenerator.uncertaintymetric import SumofCovarianceNormsMetric
uncertainty_generators = [
SumofCovarianceNormsMetric(generator_name=f'{tracking_filter} OSPA metrics',
tracks_key=f'tracks_{tracking_filter}')
for tracking_filter in tracking_filters]
# %%
# Now we initialise the metric manager and generate the metrics:
from stonesoup.dataassociator.tracktotrack import TrackToTruth
from stonesoup.metricgenerator.manager import MultiManager
associator = TrackToTruth(association_threshold=30)
generators = ospa_generators + siap_generators + uncertainty_generators
metric_manager = MultiManager(generators, associator=associator)
metric_manager.add_data({'truths': ground_truth,
'tracks_EKF': tracks_EKF,
'tracks_UKF': tracks_UKF,
'tracks_PF': tracks_PF,
'tracks_ESIF': tracks_ESIF
})
metrics = metric_manager.generate_metrics()
# %%
# Now we can plot the OSPA distance for each tracker:
from stonesoup.plotter import MetricPlotter
fig1 = MetricPlotter()
fig1.plot_metrics(metrics, metric_names=['OSPA distances'])
# %%
# It can be seen that the EKF, UKF, and Particle Filter all behave very similarly,
# whereas the ESIF has very poor relative performance. A singular performance metric is calculated
# from this by summing the OSPA value over all timesteps:
# sum up distance error from ground truth over all timestamps
for tracking_filter in tracking_filters:
total = sum([metrics[f'{tracking_filter} OSPA metrics']['OSPA distances'].value[i].value
for i in range(0, len(metrics[f'{tracking_filter} OSPA metrics']['OSPA distances'].value))])
print(f'OSPA total value for {tracking_filter} is {total:.3f}')
# %%
# Finally, we calculate the SIAP metrics for the EKF. The same metrics can be calculated for the
# other trackers if desired. The user can copy this section of code and replace the relevant
# variable names to get the full metrics for the UKF, ESIF, and Particle Filter.
from stonesoup.metricgenerator.metrictables import SIAPTableGenerator
# generate metrics for EKF
siap_metrics = metrics['EKF SIAP metrics']
siap_averages_EKF = {siap_metrics.get(metric) for metric in siap_metrics
if metric.startswith("SIAP") and not metric.endswith(" at times")}
_ = SIAPTableGenerator(siap_averages_EKF).compute_metric()
print("\n\nSIAP metrics for EKF:")