Filter#
Each TrackedObject uses a predictive filter
to smooth its estimated position and velocity over time. The filter_factory
argument on Tracker decides which filter is built
for every new track.
Norfair ships with two Kalman filter factories (plus
NoFilterFactory to disable filtering):
OptimizedKalmanFilterFactory— the default. A NumPy-only constant-velocity Kalman filter tuned for speed. Use this unless you need custom dynamics.FilterPyKalmanFilterFactory— backed by thefilterpylibrary. Slower but makes it easy to swap in a customfilterpyKalman filter if you need a different motion model.
Both expose the same knobs (R — measurement noise, Q — process noise) so
you can trade smoothness against responsiveness without changing tracker code:
- Higher
Ror lowerQ→ the filter trusts the estimate more → smoother, but slower to react to real motion. - Lower
Ror higherQ→ the filter trusts the measurement more → twitchier but more responsive.
Example#
1 2 3 4 5 6 7 8 9 | |
To disable filtering entirely (e.g. for debugging raw detections end-to-end),
pass a NoFilterFactory instead.
API#
Predictive filter factories used by Tracker to estimate object motion.
FilterFactory
#
Bases: ABC
Abstract base class for predictive-filter factories.
Subclasses must implement :meth:create_filter, which returns a new
filter instance for each tracked object.
Source code in norfair/filter.py
43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 | |
create_filter(initial_detection)
abstractmethod
#
Return a new filter seeded with initial_detection.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
initial_detection
|
NDArray[float64]
|
Array of shape |
required |
Returns:
| Type | Description |
|---|---|
Filter
|
A freshly initialized filter instance for the new tracked object. |
Source code in norfair/filter.py
50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 | |
FilterPyKalmanFilterFactory
#
Bases: FilterFactory
Factory for filterpy-backed Kalman filters.
Use this factory to either tweak the parameters of the KalmanFilter that the tracker uses, or to fully customize the predictive filter implementation (as long as the methods and properties are compatible).
In the first case, only the default parameters need to be tweaked at tracker creation time::
1 | |
In the second case, create your own subclass of
FilterPyKalmanFilterFactory and override :meth:create_filter to
return your customized filter.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
R
|
float
|
Multiplier for the sensor measurement noise matrix. Defaults to
|
4.0
|
Q
|
float
|
Multiplier for the process uncertainty. Defaults to |
0.1
|
P
|
float
|
Multiplier for the initial covariance matrix estimation, only in
the entries that correspond to position (not speed) variables.
Defaults to |
10.0
|
Notes
The generated Kalman filter uses a state vector of length 2 * dim_z
laid out as [pos[0], ..., pos[dim_z-1], vel[0], ..., vel[dim_z-1]],
where dim_z = num_points * dim_points is the flattened measurement
dimensionality. This layout is assumed by the rest of the tracker and
should be preserved when subclassing.
When the innovation covariance matrix S is singular or
ill-conditioned (condition number > 1e12), the filter automatically
falls back to a pseudo-inverse to maintain numerical stability.
See Also
Source code in norfair/filter.py
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 | |
create_filter(initial_detection)
#
Return a new Kalman filter seeded with initial_detection.
The returned filter is used by each new
TrackedObject to estimate speed
and future positions so detections can be matched along the
trajectory.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
initial_detection
|
NDArray[float64]
|
Array of shape |
required |
Returns:
| Type | Description |
|---|---|
KalmanFilter
|
A freshly initialized Kalman filter. |
Source code in norfair/filter.py
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 | |
NoFilterFactory
#
Bases: FilterFactory
Factory producing a null filter with no velocity estimation.
Lets the user try Norfair without any predictive filtering: tracking is performed only by comparing the position of previous detections to those in the current frame.
The throughput of this class in FPS is similar to that of
OptimizedKalmanFilterFactory,
so this class exists only for comparative purposes and is not advised
for real-world tracking.
Source code in norfair/filter.py
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 | |
create_filter(initial_detection)
#
Return a :class:NoFilter seeded with initial_detection.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
initial_detection
|
NDArray[float64]
|
Array of shape |
required |
Returns:
| Type | Description |
|---|---|
NoFilter
|
A null filter whose position state is set to |
Source code in norfair/filter.py
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 | |
OptimizedKalmanFilterFactory
#
Bases: FilterFactory
Factory for the vectorized :class:OptimizedKalmanFilter.
Produces filters that are faster than those returned by
FilterPyKalmanFilterFactory
and exposes the most relevant tuning knobs.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
R
|
float
|
Multiplier for the sensor measurement noise matrix. Larger values make the filter trust measurements less — useful when detections are noisy. |
4.0
|
Q
|
float
|
Multiplier for the process uncertainty. Larger values let the filter react faster to real motion changes but increase jitter; smaller values produce smoother but laggier tracks. |
0.1
|
pos_variance
|
float
|
Multiplier for the initial covariance matrix estimation in the entries that correspond to position (not speed) variables. |
10
|
pos_vel_covariance
|
float
|
Multiplier for the initial covariance matrix estimation in the entries that correspond to the covariance between position and velocity. |
0
|
vel_variance
|
float
|
Multiplier for the initial covariance matrix estimation in the entries that correspond to velocity (not position) variables. |
1
|
Notes
The generated filter uses the same state vector layout as
FilterPyKalmanFilterFactory:
[pos[0], ..., pos[dim_z-1], vel[0], ..., vel[dim_z-1]], with
dim_z = num_points * dim_points.
Intermediate variances are clamped to a minimum of 1e-12 to prevent
zero-division in degenerate cases (e.g. perfectly stationary targets with
near-zero measurement noise).
Source code in norfair/filter.py
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 | |
__init__(R=4.0, Q=0.1, pos_variance=10, pos_vel_covariance=0, vel_variance=1)
#
Store the factory-wide tuning parameters.
Source code in norfair/filter.py
407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 | |
create_filter(initial_detection)
#
Return an :class:OptimizedKalmanFilter seeded with initial_detection.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
initial_detection
|
NDArray[float64]
|
Array of shape |
required |
Returns:
| Type | Description |
|---|---|
OptimizedKalmanFilter
|
A freshly initialized optimized Kalman filter. |
Source code in norfair/filter.py
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 | |
See also#
- Tracker — accepts the
filter_factoryused here. - Getting Started — practical tips on
tuning
RandQwhen the tracker jitters or lags.