Skip to content

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 the filterpy library. Slower but makes it easy to swap in a custom filterpy Kalman 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 R or lower Q → the filter trusts the estimate more → smoother, but slower to react to real motion.
  • Lower R or higher Q → the filter trusts the measurement more → twitchier but more responsive.

Example#

1
2
3
4
5
6
7
8
9
from norfair import Tracker
from norfair.filter import OptimizedKalmanFilterFactory

tracker = Tracker(
    distance_function="euclidean",
    distance_threshold=50,
    # Increase R to reduce jitter on noisy detectors.
    filter_factory=OptimizedKalmanFilterFactory(R=8.0, Q=0.1),
)

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
class FilterFactory(ABC):
    """Abstract base class for predictive-filter factories.

    Subclasses must implement :meth:`create_filter`, which returns a new
    filter instance for each tracked object.
    """

    @abstractmethod
    def create_filter(self, initial_detection: NDArray[np.float64]) -> Filter:
        """Return a new filter seeded with ``initial_detection``.

        Parameters
        ----------
        initial_detection : NDArray[np.float64]
            Array of shape ``(n_points, n_dimensions)`` with the initial
            detection coordinates used to seed the filter state.

        Returns
        -------
        Filter
            A freshly initialized filter instance for the new tracked object.
        """
        ...

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 (n_points, n_dimensions) with the initial detection coordinates used to seed the filter state.

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
@abstractmethod
def create_filter(self, initial_detection: NDArray[np.float64]) -> Filter:
    """Return a new filter seeded with ``initial_detection``.

    Parameters
    ----------
    initial_detection : NDArray[np.float64]
        Array of shape ``(n_points, n_dimensions)`` with the initial
        detection coordinates used to seed the filter state.

    Returns
    -------
    Filter
        A freshly initialized filter instance for the new tracked object.
    """
    ...

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
tracker = Tracker(..., filter_factory=FilterPyKalmanFilterFactory(R=100))

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. Larger values make the filter trust measurements less and rely more on its own predictions — useful when detections are noisy.

4.0
Q float

Multiplier for the process uncertainty. Defaults to 0.1. Larger values let the filter react faster to real motion changes but increase jitter; smaller values produce smoother but laggier tracks.

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.

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

filterpy.KalmanFilter

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
class FilterPyKalmanFilterFactory(FilterFactory):
    """Factory for filterpy-backed Kalman filters.

    Use this factory to either tweak the parameters of the
    [KalmanFilter](https://filterpy.readthedocs.io/en/latest/kalman/KalmanFilter.html)
    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::

        tracker = Tracker(..., filter_factory=FilterPyKalmanFilterFactory(R=100))

    In the second case, create your own subclass of
    ``FilterPyKalmanFilterFactory`` and override :meth:`create_filter` to
    return your customized filter.

    Parameters
    ----------
    R : float, optional
        Multiplier for the sensor measurement noise matrix. Defaults to
        ``4.0``. Larger values make the filter trust measurements less
        and rely more on its own predictions — useful when detections
        are noisy.
    Q : float, optional
        Multiplier for the process uncertainty. Defaults to ``0.1``.
        Larger values let the filter react faster to real motion changes
        but increase jitter; smaller values produce smoother but laggier
        tracks.
    P : float, optional
        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
    --------
    [`filterpy.KalmanFilter`](https://filterpy.readthedocs.io/en/latest/kalman/KalmanFilter.html)

    """

    def __init__(self, R: float = 4.0, Q: float = 0.1, P: float = 10.0):
        self.R = R
        self.Q = Q
        self.P = P

    def create_filter(self, initial_detection: NDArray[np.float64]) -> KalmanFilter:
        """Return a new Kalman filter seeded with ``initial_detection``.

        The returned filter is used by each new
        [`TrackedObject`][norfair.tracker.TrackedObject] to estimate speed
        and future positions so detections can be matched along the
        trajectory.

        Parameters
        ----------
        initial_detection : NDArray[np.float64]
            Array of shape ``(n_points, n_dimensions)`` corresponding to
            [`Detection.points`][norfair.tracker.Detection] of the tracked
            object being born, used as the initial position estimate.

        Returns
        -------
        KalmanFilter
            A freshly initialized Kalman filter.

        """
        num_points = initial_detection.shape[0]
        dim_points = initial_detection.shape[1]
        dim_z = dim_points * num_points
        dim_x = 2 * dim_z  # We need to accommodate for velocities

        filter = KalmanFilter(dim_x=dim_x, dim_z=dim_z)

        # State transition matrix (models physics): numpy.array()
        filter.F = np.eye(dim_x)
        dt = 1  # At each step we update pos with v * dt

        filter.F[:dim_z, dim_z:] = dt * np.eye(dim_z)

        # Measurement function: numpy.array(dim_z, dim_x)
        filter.H = np.eye(
            dim_z,
            dim_x,
        )

        # Measurement uncertainty (sensor noise): numpy.array(dim_z, dim_z)
        filter.R *= self.R

        # Process uncertainty: numpy.array(dim_x, dim_x)
        # Don't decrease it too much or trackers pay too little attention to detections
        filter.Q[dim_z:, dim_z:] *= self.Q

        # Initial state: numpy.array(dim_x, 1)
        filter.x[:dim_z] = initial_detection.reshape(-1, 1)
        filter.x[dim_z:] = 0

        # Estimation uncertainty: numpy.array(dim_x, dim_x)
        filter.P[dim_z:, dim_z:] *= self.P

        return filter

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 (n_points, n_dimensions) corresponding to Detection.points of the tracked object being born, used as the initial position estimate.

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
def create_filter(self, initial_detection: NDArray[np.float64]) -> KalmanFilter:
    """Return a new Kalman filter seeded with ``initial_detection``.

    The returned filter is used by each new
    [`TrackedObject`][norfair.tracker.TrackedObject] to estimate speed
    and future positions so detections can be matched along the
    trajectory.

    Parameters
    ----------
    initial_detection : NDArray[np.float64]
        Array of shape ``(n_points, n_dimensions)`` corresponding to
        [`Detection.points`][norfair.tracker.Detection] of the tracked
        object being born, used as the initial position estimate.

    Returns
    -------
    KalmanFilter
        A freshly initialized Kalman filter.

    """
    num_points = initial_detection.shape[0]
    dim_points = initial_detection.shape[1]
    dim_z = dim_points * num_points
    dim_x = 2 * dim_z  # We need to accommodate for velocities

    filter = KalmanFilter(dim_x=dim_x, dim_z=dim_z)

    # State transition matrix (models physics): numpy.array()
    filter.F = np.eye(dim_x)
    dt = 1  # At each step we update pos with v * dt

    filter.F[:dim_z, dim_z:] = dt * np.eye(dim_z)

    # Measurement function: numpy.array(dim_z, dim_x)
    filter.H = np.eye(
        dim_z,
        dim_x,
    )

    # Measurement uncertainty (sensor noise): numpy.array(dim_z, dim_z)
    filter.R *= self.R

    # Process uncertainty: numpy.array(dim_x, dim_x)
    # Don't decrease it too much or trackers pay too little attention to detections
    filter.Q[dim_z:, dim_z:] *= self.Q

    # Initial state: numpy.array(dim_x, 1)
    filter.x[:dim_z] = initial_detection.reshape(-1, 1)
    filter.x[dim_z:] = 0

    # Estimation uncertainty: numpy.array(dim_x, dim_x)
    filter.P[dim_z:, dim_z:] *= self.P

    return filter

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
class NoFilterFactory(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`][norfair.filter.OptimizedKalmanFilterFactory],
    so this class exists only for comparative purposes and is not advised
    for real-world tracking.
    """

    def create_filter(self, initial_detection: NDArray[np.float64]):
        """Return a :class:`NoFilter` seeded with ``initial_detection``.

        Parameters
        ----------
        initial_detection : NDArray[np.float64]
            Array of shape ``(n_points, n_dimensions)`` with the initial
            detection coordinates used to seed the filter state.

        Returns
        -------
        NoFilter
            A null filter whose position state is set to ``initial_detection``.
        """
        num_points = initial_detection.shape[0]
        dim_points = initial_detection.shape[1]
        dim_z = dim_points * num_points  # flattened positions
        dim_x = 2 * dim_z  # We need to accommodate for velocities

        no_filter = NoFilter(
            dim_x,
            dim_z,
        )
        no_filter.x[:dim_z] = np.expand_dims(initial_detection.flatten(), 0).T
        return no_filter

create_filter(initial_detection) #

Return a :class:NoFilter seeded with initial_detection.

Parameters:

Name Type Description Default
initial_detection NDArray[float64]

Array of shape (n_points, n_dimensions) with the initial detection coordinates used to seed the filter state.

required

Returns:

Type Description
NoFilter

A null filter whose position state is set to initial_detection.

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
def create_filter(self, initial_detection: NDArray[np.float64]):
    """Return a :class:`NoFilter` seeded with ``initial_detection``.

    Parameters
    ----------
    initial_detection : NDArray[np.float64]
        Array of shape ``(n_points, n_dimensions)`` with the initial
        detection coordinates used to seed the filter state.

    Returns
    -------
    NoFilter
        A null filter whose position state is set to ``initial_detection``.
    """
    num_points = initial_detection.shape[0]
    dim_points = initial_detection.shape[1]
    dim_z = dim_points * num_points  # flattened positions
    dim_x = 2 * dim_z  # We need to accommodate for velocities

    no_filter = NoFilter(
        dim_x,
        dim_z,
    )
    no_filter.x[:dim_z] = np.expand_dims(initial_detection.flatten(), 0).T
    return no_filter

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
class OptimizedKalmanFilterFactory(FilterFactory):
    """Factory for the vectorized :class:`OptimizedKalmanFilter`.

    Produces filters that are faster than those returned by
    [`FilterPyKalmanFilterFactory`][norfair.filter.FilterPyKalmanFilterFactory]
    and exposes the most relevant tuning knobs.

    Parameters
    ----------
    R : float, optional
        Multiplier for the sensor measurement noise matrix. Larger values
        make the filter trust measurements less — useful when detections
        are noisy.
    Q : float, optional
        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.
    pos_variance : float, optional
        Multiplier for the initial covariance matrix estimation in the
        entries that correspond to position (not speed) variables.
    pos_vel_covariance : float, optional
        Multiplier for the initial covariance matrix estimation in the
        entries that correspond to the covariance between position and
        velocity.
    vel_variance : float, optional
        Multiplier for the initial covariance matrix estimation in the
        entries that correspond to velocity (not position) variables.

    Notes
    -----
    The generated filter uses the same state vector layout as
    [`FilterPyKalmanFilterFactory`][norfair.filter.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).
    """

    def __init__(
        self,
        R: float = 4.0,
        Q: float = 0.1,
        pos_variance: float = 10,
        pos_vel_covariance: float = 0,
        vel_variance: float = 1,
    ):
        """Store the factory-wide tuning parameters."""
        self.R = R
        self.Q = Q

        # entrances P matrix of KF
        self.pos_variance = pos_variance
        self.pos_vel_covariance = pos_vel_covariance
        self.vel_variance = vel_variance

    def create_filter(self, initial_detection: NDArray[np.float64]):
        """Return an :class:`OptimizedKalmanFilter` seeded with ``initial_detection``.

        Parameters
        ----------
        initial_detection : NDArray[np.float64]
            Array of shape ``(n_points, n_dimensions)`` with the initial
            detection coordinates used to seed the filter state.

        Returns
        -------
        OptimizedKalmanFilter
            A freshly initialized optimized Kalman filter.
        """
        num_points = initial_detection.shape[0]
        dim_points = initial_detection.shape[1]
        dim_z = dim_points * num_points  # flattened positions
        dim_x = 2 * dim_z  # We need to accommodate for velocities

        custom_filter = OptimizedKalmanFilter(
            dim_x,
            dim_z,
            pos_variance=self.pos_variance,
            pos_vel_covariance=self.pos_vel_covariance,
            vel_variance=self.vel_variance,
            q=self.Q,
            r=self.R,
        )
        custom_filter.x[:dim_z] = np.expand_dims(initial_detection.flatten(), 0).T

        return custom_filter

__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
def __init__(
    self,
    R: float = 4.0,
    Q: float = 0.1,
    pos_variance: float = 10,
    pos_vel_covariance: float = 0,
    vel_variance: float = 1,
):
    """Store the factory-wide tuning parameters."""
    self.R = R
    self.Q = Q

    # entrances P matrix of KF
    self.pos_variance = pos_variance
    self.pos_vel_covariance = pos_vel_covariance
    self.vel_variance = vel_variance

create_filter(initial_detection) #

Return an :class:OptimizedKalmanFilter seeded with initial_detection.

Parameters:

Name Type Description Default
initial_detection NDArray[float64]

Array of shape (n_points, n_dimensions) with the initial detection coordinates used to seed the filter state.

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
def create_filter(self, initial_detection: NDArray[np.float64]):
    """Return an :class:`OptimizedKalmanFilter` seeded with ``initial_detection``.

    Parameters
    ----------
    initial_detection : NDArray[np.float64]
        Array of shape ``(n_points, n_dimensions)`` with the initial
        detection coordinates used to seed the filter state.

    Returns
    -------
    OptimizedKalmanFilter
        A freshly initialized optimized Kalman filter.
    """
    num_points = initial_detection.shape[0]
    dim_points = initial_detection.shape[1]
    dim_z = dim_points * num_points  # flattened positions
    dim_x = 2 * dim_z  # We need to accommodate for velocities

    custom_filter = OptimizedKalmanFilter(
        dim_x,
        dim_z,
        pos_variance=self.pos_variance,
        pos_vel_covariance=self.pos_vel_covariance,
        vel_variance=self.vel_variance,
        q=self.Q,
        r=self.R,
    )
    custom_filter.x[:dim_z] = np.expand_dims(initial_detection.flatten(), 0).T

    return custom_filter

See also#

  • Tracker — accepts the filter_factory used here.
  • Getting Started — practical tips on tuning R and Q when the tracker jitters or lags.