No version for distro humble. Known supported distros are highlighted in the buttons above.
No version for distro jazzy. Known supported distros are highlighted in the buttons above.
No version for distro kilted. Known supported distros are highlighted in the buttons above.
No version for distro rolling. Known supported distros are highlighted in the buttons above.

autoware_kalman_filter package from autoware_core repo

autoware_core autoware_component_interface_specs autoware_geography_utils autoware_global_parameter_loader autoware_interpolation autoware_kalman_filter autoware_lanelet2_utils autoware_motion_utils autoware_node autoware_object_recognition_utils autoware_osqp_interface autoware_point_types autoware_qp_interface autoware_signal_processing autoware_trajectory autoware_vehicle_info_utils autoware_core_control autoware_simple_pure_pursuit autoware_core_localization autoware_ekf_localizer autoware_gyro_odometer autoware_localization_util autoware_ndt_scan_matcher autoware_pose_initializer autoware_stop_filter autoware_twist2accel autoware_core_map autoware_lanelet2_map_visualizer autoware_map_height_fitter autoware_map_loader autoware_map_projection_loader autoware_core_perception autoware_euclidean_cluster_object_detector autoware_ground_filter autoware_perception_objects_converter autoware_core_planning autoware_mission_planner autoware_objects_of_interest_marker_interface autoware_path_generator autoware_planning_factor_interface autoware_planning_topic_converter autoware_route_handler autoware_velocity_smoother autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_stop_line_module autoware_motion_velocity_obstacle_stop_module autoware_motion_velocity_planner autoware_motion_velocity_planner_common autoware_core_sensing autoware_crop_box_filter autoware_downsample_filters autoware_gnss_poser autoware_vehicle_velocity_converter autoware_planning_test_manager autoware_pyplot autoware_test_node autoware_test_utils autoware_testing autoware_core_vehicle

Package Summary

Tags No category tags.
Version 1.1.0
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Description
Checkout URI https://github.com/autowarefoundation/autoware_core.git
VCS Type git
VCS Version main
Last Updated 2025-06-07
Dev Status UNKNOWN
CI status No Continuous Integration
Released UNRELEASED
Tags planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

The kalman filter package

Additional Links

No additional links.

Maintainers

  • Yukihiro Saito
  • Ryu Yamamoto
  • Yamato Ando
  • Masahiro Sakamoto
  • NGUYEN Viet Anh
  • Taiki Yamada
  • Shintaro Sakoda

Authors

  • Takamasa Horibe

kalman_filter

Overview

This package contains the kalman filter with time delay and the calculation of the kalman filter.

Design

The Kalman filter is a recursive algorithm used to estimate the state of a dynamic system. The Time Delay Kalman filter is based on the standard Kalman filter and takes into account possible time delays in the measured values.

Standard Kalman Filter

System Model

Assume that the system can be represented by the following linear discrete model:

\[x_{k} = A x_{k-1} + B u_{k} \\ y_{k} = C x_{k-1}\]

where,

  • $x_k$ is the state vector at time $k$.
  • $u_k$ is the control input vector at time $k$.
  • $y_k$ is the measurement vector at time $k$.
  • $A$ is the state transition matrix.
  • $B$ is the control input matrix.
  • $C$ is the measurement matrix.

Prediction Step

The prediction step consists of updating the state and covariance matrices:

\[x_{k|k-1} = A x_{k-1|k-1} + B u_{k} \\ P_{k|k-1} = A P_{k-1|k-1} A^{T} + Q\]

where,

  • $x_{k k-1}$ is the priori state estimate.
  • $P_{k k-1}$ is the priori covariance matrix.

Update Step

When the measurement value ( y_k ) is received, the update steps are as follows:

\[K_k = P_{k|k-1} C^{T} (C P_{k|k-1} C^{T} + R)^{-1} \\ x_{k|k} = x_{k|k-1} + K_k (y_{k} - C x_{k|k-1}) \\ P_{k|k} = (I - K_k C) P_{k|k-1}\]

where,

  • $K_k$ is the Kalman gain.
  • $x_{k k}$ is the posterior state estimate.
  • $P_{k k}$ is the posterior covariance matrix.

Extension to Time Delay Kalman Filter

For the Time Delay Kalman filter, it is assumed that there may be a maximum delay of step ($d$) in the measured value. To handle this delay, we extend the state vector to:

\[(x_{k})_e = \begin{bmatrix} x_k \\ x_{k-1} \\ \vdots \\ x_{k-d+1} \end{bmatrix}\]

The corresponding state transition matrix ($A_e$) and process noise covariance matrix ($Q_e$) are also expanded:

\[A_e = \begin{bmatrix} A & 0 & 0 & \cdots & 0 \\ I & 0 & 0 & \cdots & 0 \\ 0 & I & 0 & \cdots & 0 \\ \vdots & \vdots & \vdots & \ddots & \vdots \\ 0 & 0 & 0 & \cdots & 0 \end{bmatrix}, \quad Q_e = \begin{bmatrix} Q & 0 & 0 & \cdots & 0 \\ 0 & 0 & 0 & \cdots & 0 \\ 0 & 0 & 0 & \cdots & 0 \\ \vdots & \vdots & \vdots & \ddots & \vdots \\ 0 & 0 & 0 & \cdots & 0 \end{bmatrix}\]

Prediction Step

The prediction step consists of updating the extended state and covariance matrices.

Update extension status:

\[(x_{k|k-1})_e = \begin{bmatrix} A & 0 & 0 & \cdots & 0 \\ I & 0 & 0 & \cdots & 0 \\ 0 & I & 0 & \cdots & 0 \\ \vdots & \vdots & \vdots & \ddots & \vdots \\ 0 & 0 & 0 & \cdots & 0 \end{bmatrix} \begin{bmatrix} x_{k-1|k-1} \\ x_{k-2|k-1} \\ \vdots \\ x_{k-d|k-1} \end{bmatrix}\]

Update extended covariance matrix:

\[(P_{k|k-1})_e = \begin{bmatrix} A & 0 & 0 & \cdots & 0 \\ I & 0 & 0 & \cdots & 0 \\ 0 & I & 0 & \cdots & 0 \\ \vdots & \vdots & \vdots & \ddots & \vdots \\ 0 & 0 & 0 & \cdots & 0 \end{bmatrix} \begin{bmatrix} P_{k-1|k-1}^{(1)} & P_{k-1|k-1}^{(1,2)} & \cdots & P_{k-1|k-1}^{(1,d)} \\ P_{k-1|k-1}^{(2,1)} & P_{k-1|k-1}^{(2)} & \cdots & P_{k-1|k-1}^{(2,d)} \\ \vdots & \vdots & \ddots & \vdots \\ P_{k-1|k-1}^{(d,1)} & P_{k-1|k-1}^{(d,2)} & \cdots & P_{k-1|k-1}^{(d)} \end{bmatrix} \begin{bmatrix} A^T & I & 0 & \cdots & 0 \\ 0 & 0 & I & \cdots & 0 \\ 0 & 0 & 0 & \cdots & 0 \\ \vdots & \vdots & \vdots & \ddots & \vdots \\ 0 & 0 & 0 & \cdots & 0 \end{bmatrix} + \begin{bmatrix} Q & 0 & 0 & \cdots & 0 \\ 0 & 0 & 0 & \cdots & 0 \\ 0 & 0 & 0 & \cdots & 0 \\ \vdots & \vdots & \vdots & \ddots & \vdots \\ 0 & 0 & 0 & \cdots & 0 \end{bmatrix}\]

$\Longrightarrow$

\[(P_{k|k-1})_e = \begin{bmatrix} A P_{k-1|k-1}^{(1)} A^T + Q & A P_{k-1|k-1}^{(1,2)} & \cdots & A P_{k-1|k-1}^{(1,d)} \\ P_{k-1|k-1}^{(2,1)} A^T & P_{k-1|k-1}^{(2)} & \cdots & P_{k-1|k-1}^{(2,d)} \\ \vdots & \vdots & \ddots & \vdots \\ P_{k-1|k-1}^{(d,1)} A^T & P_{k-1|k-1}^{(d,2)} & \cdots & P_{k-1|k-1}^{(d)} \end{bmatrix}\]

where,

  • $(x_{k k-1})_e$ is the priori extended state estimate.
  • $(P_{k k-1})_e$ is the priori extended covariance matrix.

Update Step

When receiving the measurement value ( $y_{k}$ ) with a delay of ( $ds$ ), the update steps are as follows:

Update kalman gain:

\[K_k = \begin{bmatrix} P_{k|k-1}^{(1)} C^T \\ P_{k|k-1}^{(2)} C^T \\ \vdots \\ P_{k|k-1}^{(ds)} C^T \\ \vdots \\ P_{k|k-1}^{(d)} C^T \end{bmatrix} (C P_{k|k-1}^{(ds)} C^T + R)^{-1}\]

Update extension status:

\[(x_{k|k})_e = \begin{bmatrix} x_{k|k-1} \\ x_{k-1|k-1} \\ \vdots \\ x_{k-d+1|k-1} \end{bmatrix} + \begin{bmatrix} K_k^{(1)} \\ K_k^{(2)} \\ \vdots \\ K_k^{(ds)} \\ \vdots \\ K_k^{(d)} \end{bmatrix} (y_k - C x_{k-ds|k-1})\]

Update extended covariance matrix:

\[(P_{k|k})_e = \left(I - \begin{bmatrix} K_k^{(1)} C \\ K_k^{(2)} C \\ \vdots \\ K_k^{(ds)} C \\ \vdots \\ K_k^{(d)} C \end{bmatrix}\right) \begin{bmatrix} P_{k|k-1}^{(1)} & P_{k|k-1}^{(1,2)} & \cdots & P_{k|k-1}^{(1,d)} \\ P_{k|k-1}^{(2,1)} & P_{k|k-1}^{(2)} & \cdots & P_{k|k-1}^{(2,d)} \\ \vdots & \vdots & \ddots & \vdots \\ P_{k|k-1}^{(d,1)} & P_{k|k-1}^{(d,2)} & \cdots & P_{k|k-1}^{(d)} \end{bmatrix}\]

where,

  • $K_k$ is the Kalman gain.
  • $(x_{k k})_e$ is the posterior extended state estimate.
  • $(P_{k k})_e$ is the posterior extended covariance matrix.
  • $C$ is the measurement matrix, which only applies to the delayed state part.

Example Usage

This section describes Example Usage of KalmanFilter.

  • Initialization
#include "autoware/kalman_filter/kalman_filter.hpp"

// Define system parameters
int dim_x = 2; // state vector dimensions
int dim_y = 1; // measure vector dimensions

// Initial state
Eigen::MatrixXd x0 = Eigen::MatrixXd::Zero(dim_x, 1);
x0 << 0.0, 0.0;

// Initial covariance matrix
Eigen::MatrixXd P0 = Eigen::MatrixXd::Identity(dim_x, dim_x);
P0 *= 100.0;

// Define state transition matrix
Eigen::MatrixXd A = Eigen::MatrixXd::Identity(dim_x, dim_x);
A(0, 1) = 1.0;

// Define measurement matrix
Eigen::MatrixXd C = Eigen::MatrixXd::Zero(dim_y, dim_x);
C(0, 0) = 1.0;

// Define process noise covariance matrix
Eigen::MatrixXd Q = Eigen::MatrixXd::Identity(dim_x, dim_x);
Q *= 0.01;

// Define measurement noise covariance matrix
Eigen::MatrixXd R = Eigen::MatrixXd::Identity(dim_y, dim_y);
R *= 1.0;

// Initialize Kalman filter
autoware::kalman_filter::KalmanFilter kf;
kf.init(x0, P0);

  • Predict step
const Eigen::MatrixXd x_next = A * x0;
kf.predict(x_next, A, Q);

  • Update step
// Measured value
Eigen::MatrixXd y = Eigen::MatrixXd::Zero(dim_y, 1);
kf.update(y, C, R);

  • Get the current estimated state and covariance matrix
Eigen::MatrixXd x_curr = kf.getX();
Eigen::MatrixXd P_curr = kf.getP();

Assumptions / Known limits

  • Delay Step Check: Ensure that the delay_step provided during the update does not exceed the maximum delay steps set during initialization.
CHANGELOG

Changelog for package autoware_kalman_filter

1.1.0 (2025-05-01)

  • fix(autoware_kalman_filter): fixed clang-tidy error (#379)
    • fix(autoware_kalman_filter): fixed clang-tidy error

    * remove comment ---------

  • refactor(autoware_kalman_filter): rewrite using modern C++ without API breakage (#346)
    • refactor using modern c++
    • remove ctor/dtor
    • precommit
    • use eigen methods

    * Update common/autoware_kalman_filter/include/autoware/kalman_filter/kalman_filter.hpp ---------

  • chore(autoware_kalman_filter): add maintainer (#381)
    • chore(autoware_kalman_filter): add maintainer
    • removed the maintainer with an invalid email address.
    • added members of the Localization / Mapping team as maintainers.
    • removed the duplicate entry.

    * fixed the deletion as the wrong entry was removed ---------

  • Contributors: RyuYamamoto, Yutaka Kondo

1.0.0 (2025-03-31)

0.3.0 (2025-03-21)

  • chore: rename from [autoware.core]{.title-ref} to [autoware_core]{.title-ref} (#290)
  • test(autoware_kalman_filter): add tests for missed lines (#263)
  • Contributors: NorahXiong, Yutaka Kondo

0.2.0 (2025-02-07)

  • unify version to 0.1.0
  • update changelog
  • feat: port autoware_kalman_filter from autoware_universe (#141) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>> Co-authored-by: Ryohsuke Mitsudome <<43976834+mitsudome-r@users.noreply.github.com>>
  • Contributors: Yutaka Kondo, cyn-liu
  • feat: port autoware_kalman_filter from autoware_universe (#141) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>> Co-authored-by: Ryohsuke Mitsudome <<43976834+mitsudome-r@users.noreply.github.com>>
  • Contributors: cyn-liu

0.0.0 (2024-12-02)

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged autoware_kalman_filter at Robotics Stack Exchange

No version for distro noetic. Known supported distros are highlighted in the buttons above.
No version for distro galactic. Known supported distros are highlighted in the buttons above.
No version for distro iron. Known supported distros are highlighted in the buttons above.
No version for distro melodic. Known supported distros are highlighted in the buttons above.