Skip to content

Filter#

FilterPyKalmanFilterFactory #

Bases: FilterFactory

This class can be used either to change some parameters of the KalmanFilter that the tracker uses, or to fully customize the predictive filter implementation to use (as long as the methods and properties are compatible).

The former case only requires changing the default parameters upon tracker creation: tracker = Tracker(..., filter_factory=FilterPyKalmanFilterFactory(R=100)), while the latter requires creating your own class extending FilterPyKalmanFilterFactory, and rewriting its create_filter method to return your own customized filter.

Parameters:

Name Type Description Default
R float

Multiplier for the sensor measurement noise matrix, by default 4.0

4.0
Q float

Multiplier for the process uncertainty, by default 0.1

0.1
P float

Multiplier for the initial covariance matrix estimation, only in the entries that correspond to position (not speed) variables, by default 10.0

10.0
See Also

filterpy.KalmanFilter.

Source code in norfair/filter.py
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
class FilterPyKalmanFilterFactory(FilterFactory):
    """
    This class can be used either to change some 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 to use (as long as the methods and properties are compatible).

    The former case only requires changing the default parameters upon tracker creation: `tracker = Tracker(..., filter_factory=FilterPyKalmanFilterFactory(R=100))`,
    while the latter requires creating your own class extending `FilterPyKalmanFilterFactory`, and rewriting its `create_filter` method to return your own customized filter.

    Parameters
    ----------
    R : float, optional
        Multiplier for the sensor measurement noise matrix, by default 4.0
    Q : float, optional
        Multiplier for the process uncertainty, by default 0.1
    P : float, optional
        Multiplier for the initial covariance matrix estimation, only in the entries that correspond to position (not speed) variables, by default 10.0

    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: np.ndarray) -> KalmanFilter:
        """
        This method returns a new predictive filter instance with the current setup, to be used by each new [`TrackedObject`][norfair.tracker.TrackedObject] that is created.
        This predictive filter will be used to estimate speed and future positions of the object, to better match the detections during its trajectory.

        Parameters
        ----------
        initial_detection : np.ndarray
            numpy array of shape `(number of points per object, 2)`, corresponding to the [`Detection.points`][norfair.tracker.Detection] of the tracked object being born,
            which shall be used as initial position estimation for it.

        Returns
        -------
        KalmanFilter
            The 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] = np.expand_dims(initial_detection.flatten(), 0).T
        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) #

This method returns a new predictive filter instance with the current setup, to be used by each new TrackedObject that is created. This predictive filter will be used to estimate speed and future positions of the object, to better match the detections during its trajectory.

Parameters:

Name Type Description Default
initial_detection ndarray

numpy array of shape (number of points per object, 2), corresponding to the Detection.points of the tracked object being born, which shall be used as initial position estimation for it.

required

Returns:

Type Description
KalmanFilter

The kalman filter

Source code in norfair/filter.py
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
def create_filter(self, initial_detection: np.ndarray) -> KalmanFilter:
    """
    This method returns a new predictive filter instance with the current setup, to be used by each new [`TrackedObject`][norfair.tracker.TrackedObject] that is created.
    This predictive filter will be used to estimate speed and future positions of the object, to better match the detections during its trajectory.

    Parameters
    ----------
    initial_detection : np.ndarray
        numpy array of shape `(number of points per object, 2)`, corresponding to the [`Detection.points`][norfair.tracker.Detection] of the tracked object being born,
        which shall be used as initial position estimation for it.

    Returns
    -------
    KalmanFilter
        The 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] = np.expand_dims(initial_detection.flatten(), 0).T
    filter.x[dim_z:] = 0

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

    return filter

OptimizedKalmanFilterFactory #

Bases: FilterFactory

Creates faster Filters than FilterPyKalmanFilterFactory.

It allows the user to create Kalman Filter optimized for tracking and set its parameters.

Parameters:

Name Type Description Default
R float

Multiplier for the sensor measurement noise matrix.

4.0
Q float

Multiplier for the process uncertainty.

0.1
pos_variance float

Multiplier for the initial covariance matrix estimation, only in the entries that correspond to position (not speed) variables.

10
pos_vel_covariance float

Multiplier for the initial covariance matrix estimation, only in the entries that correspond to the covariance between position and speed.

0
vel_variance float

Multiplier for the initial covariance matrix estimation, only in the entries that correspond to velocity (not position) variables.

1
Source code in norfair/filter.py
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
class OptimizedKalmanFilterFactory(FilterFactory):
    """
    Creates faster Filters than [`FilterPyKalmanFilterFactory`][norfair.filter.FilterPyKalmanFilterFactory].

    It allows the user to create Kalman Filter optimized for tracking and set its parameters.

    Parameters
    ----------
    R : float, optional
        Multiplier for the sensor measurement noise matrix.
    Q : float, optional
        Multiplier for the process uncertainty.
    pos_variance : float, optional
        Multiplier for the initial covariance matrix estimation, only in the entries that correspond to position (not speed) variables.
    pos_vel_covariance : float, optional
        Multiplier for the initial covariance matrix estimation, only in the entries that correspond to the covariance between position and speed.
    vel_variance : float, optional
        Multiplier for the initial covariance matrix estimation, only in the entries that correspond to velocity (not position) variables.
    """

    def __init__(
        self,
        R: float = 4.0,
        Q: float = 0.1,
        pos_variance: float = 10,
        pos_vel_covariance: float = 0,
        vel_variance: float = 1,
    ):
        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: np.ndarray):
        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