Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(autoware_ekf_localizer)!: porting from universe to core 2nd #180

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
19 commits
Select commit Hold shift + click to select a range
4d17079
refactor(ekf_localizer)!: prefix package and namespace with autoware …
a-maumau Sep 18, 2024
af71fa3
refactor(localization_util)!: prefix package and namespace with autow…
a-maumau Sep 19, 2024
a06b13a
fix(autoware_ekf_localizer): remove `timer_tf_` (#9244)
SakodaShintaro Nov 6, 2024
9ef03b8
chore(package.xml): bump version to 0.38.0 (#9266) (#9284)
youtalk Nov 11, 2024
4427ef2
fix: fix ticket links to point to https://github.com/autowarefoundati…
esteve Nov 12, 2024
cbefbea
fix(autoware_ekf_localizer): publish `processing_time_ms` (#9443)
SakodaShintaro Nov 26, 2024
aac3296
fix(cpplint): include what you use - localization (#9567)
xmfcx Dec 4, 2024
5128f1e
chore(package.xml): bump version to 0.39.0 (#9587)
mitsudome-r Dec 6, 2024
94aa9e8
chore(package.xml): bump version to 0.40.0 (#9618)
rej55 Dec 12, 2024
51f5835
feat(ekf_localizer): check whether the initialpose has been set (#9787)
YamatoAndo Jan 7, 2025
75a8ba6
feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fie…
vish0012 Jan 9, 2025
f44cbf0
feat(autoware_ekf_localizer)!: porting from universe to core (#9978)
Motsu-san Jan 20, 2025
fcafabe
revert: revert "feat(autoware_ekf_localizer)!: porting from universe …
mitsudome-r Jan 22, 2025
fa403a9
chore: bump version to 0.41.0 (#10037)
rej55 Jan 29, 2025
a27573b
feat: add autoware_internal_msgs repo's link to build_depends.repos file
Motsu-san Jan 20, 2025
5e4864a
chore: delete the needless file CHANGELOG.rst
Motsu-san Jan 20, 2025
8bcee74
chore: initialize autoware_ekf_localizer versioning on autoware.core
Motsu-san Jan 20, 2025
c8cfad7
feat: change autoware_universe_utils package dependence to autoware_u…
Motsu-san Feb 3, 2025
5d0a137
Merge remote-tracking branch 'origin/main' into feat/porting_ekf_loca…
mitsudome-r Feb 13, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
82 changes: 82 additions & 0 deletions localization/autoware_ekf_localizer/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
cmake_minimum_required(VERSION 3.14)
project(autoware_ekf_localizer)

find_package(autoware_cmake REQUIRED)
autoware_package()

find_package(Eigen3 REQUIRED)

include_directories(
SYSTEM
${EIGEN3_INCLUDE_DIR}
)

ament_auto_find_build_dependencies()

ament_auto_add_library(${PROJECT_NAME} SHARED
src/ekf_localizer.cpp
src/covariance.cpp
src/diagnostics.cpp
src/mahalanobis.cpp
src/measurement.cpp
src/state_transition.cpp
src/warning_message.cpp
src/ekf_module.cpp
)

rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "autoware::ekf_localizer::EKFLocalizer"
EXECUTABLE ${PROJECT_NAME}_node
EXECUTOR SingleThreadedExecutor
)

target_link_libraries(${PROJECT_NAME} Eigen3::Eigen)

function(add_testcase filepath)
get_filename_component(filename ${filepath} NAME)
string(REGEX REPLACE ".cpp" "" test_name ${filename})

ament_add_gtest(${test_name} ${filepath})
target_link_libraries("${test_name}" ${PROJECT_NAME})
ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS})
endfunction()

if(BUILD_TESTING)
add_launch_test(
test/test_ekf_localizer_launch.py
TIMEOUT "30"
)
add_launch_test(
test/test_ekf_localizer_mahalanobis.py
TIMEOUT "30"
)
find_package(ament_cmake_gtest REQUIRED)

file(GLOB_RECURSE TEST_FILES test/*.cpp)

foreach(filepath ${TEST_FILES})
add_testcase(${filepath})
endforeach()
endif()


# if(BUILD_TESTING)
# find_package(ament_cmake_ros REQUIRED)
# ament_add_ros_isolated_gtest(ekf_localizer-test test/test_ekf_localizer.test
# test/src/test_ekf_localizer.cpp
# src/ekf_localizer.cpp
# src/kalman_filter/kalman_filter.cpp
# src/kalman_filter/time_delay_kalman_filter.cpp
# )
# target_include_directories(ekf_localizer-test
# PRIVATE
# include
# )
# ament_target_dependencies(ekf_localizer-test geometry_msgs rclcpp tf2 tf2_ros)
# endif()

ament_auto_package(
INSTALL_TO_SHARE
config
launch
)
211 changes: 211 additions & 0 deletions localization/autoware_ekf_localizer/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,211 @@
# Overview

The **Extend Kalman Filter Localizer** estimates robust and less noisy robot pose and twist by integrating the 2D vehicle dynamics model with input ego-pose and ego-twist messages. The algorithm is designed especially for fast-moving robots such as autonomous driving systems.

## Flowchart

The overall flowchart of the autoware_ekf_localizer is described below.

<p align="center">
<img src="./media/ekf_flowchart.png" width="800">
</p>

## Features

This package includes the following features:

- **Time delay compensation** for input messages, which enables proper integration of input information with varying time delays. This is important especially for high-speed moving robots, such as autonomous driving vehicles. (see the following figure).
- **Automatic estimation of yaw bias** prevents modeling errors caused by sensor mounting angle errors, which can improve estimation accuracy.
- **Mahalanobis distance gate** enables probabilistic outlier detection to determine which inputs should be used or ignored.
- **Smooth update**, the Kalman Filter measurement update is typically performed when a measurement is obtained, but it can cause large changes in the estimated value, especially for low-frequency measurements. Since the algorithm can consider the measurement time, the measurement data can be divided into multiple pieces and integrated smoothly while maintaining consistency (see the following figure).
- **Calculation of vertical correction amount from pitch** mitigates localization instability on slopes. For example, when going uphill, it behaves as if it is buried in the ground (see the left side of the "Calculate delta from pitch" figure) because EKF only considers 3DoF(x,y,yaw). Therefore, EKF corrects the z-coordinate according to the formula (see the right side of the "Calculate delta from pitch" figure).

<p align="center">
<img src="./media/ekf_delay_comp.png" width="800">
</p>

<p align="center">
<img src="./media/ekf_smooth_update.png" width="800">
</p>

<p align="center">
<img src="./media/calculation_delta_from_pitch.png" width="800">
</p>

## Node

### Subscribed Topics

| Name | Type | Description |
| -------------------------------- | ------------------------------------------------ | ---------------------------------------------------------------------------------------------------------------------------------------- |
| `measured_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Input pose source with the measurement covariance matrix. |
| `measured_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | Input twist source with the measurement covariance matrix. |
| `initialpose` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Initial pose for EKF. The estimated pose is initialized with zeros at the start. It is initialized with this message whenever published. |

### Published Topics

| Name | Type | Description |
| --------------------------------- | --------------------------------------------------- | ----------------------------------------------------- |
| `ekf_odom` | `nav_msgs::msg::Odometry` | Estimated odometry. |
| `ekf_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose. |
| `ekf_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance. |
| `ekf_biased_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose including the yaw bias |
| `ekf_biased_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance including the yaw bias |
| `ekf_twist` | `geometry_msgs::msg::TwistStamped` | Estimated twist. |
| `ekf_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The estimated twist with covariance. |
| `diagnostics` | `diagnostics_msgs::msg::DiagnosticArray` | The diagnostic information. |
| `debug/processing_time_ms` | `autoware_internal_debug_msgs::msg::Float64Stamped` | The processing time [ms]. |

### Published TF

- base_link
TF from `map` coordinate to estimated pose.

## Functions

### Predict

The current robot state is predicted from previously estimated data using a given prediction model. This calculation is called at a constant interval (`predict_frequency [Hz]`). The prediction equation is described at the end of this page.

### Measurement Update

Before the update, the Mahalanobis distance is calculated between the measured input and the predicted state, the measurement update is not performed for inputs where the Mahalanobis distance exceeds the given threshold.

The predicted state is updated with the latest measured inputs, measured_pose, and measured_twist. The updates are performed with the same frequency as prediction, usually at a high frequency, in order to enable smooth state estimation.

## Parameter description

The parameters are set in `launch/ekf_localizer.launch` .

### For Node

{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/node.sub_schema.json") }}

### For pose measurement

{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/pose_measurement.sub_schema.json") }}

### For twist measurement

{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/twist_measurement.sub_schema.json") }}

### For process noise

{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/process_noise.sub_schema.json") }}

note: process noise for positions x & y are calculated automatically from nonlinear dynamics.

### Simple 1D Filter Parameters

{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/simple_1d_filter_parameters.sub_schema.json") }}

### For diagnostics

{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/diagnostics.sub_schema.json") }}

### Misc

{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/misc.sub_schema.json") }}

## How to tune EKF parameters

### 0. Preliminaries

- Check header time in pose and twist message is set to sensor time appropriately, because time delay is calculated from this value. If it is difficult to set an appropriate time due to the timer synchronization problem, use `twist_additional_delay` and `pose_additional_delay` to correct the time.
- Check if the relation between measurement pose and twist is appropriate (whether the derivative of the pose has a similar value to twist). This discrepancy is caused mainly by unit error (such as confusing radian/degree) or bias noise, and it causes large estimation errors.

### 1. Tune sensor parameters

Set standard deviation for each sensor. The `pose_measure_uncertainty_time` is for the uncertainty of the header timestamp data.
You can also tune a number of steps for smoothing for each observed sensor data by tuning `*_smoothing_steps`.
Increasing the number will improve the smoothness of the estimation, but may have an adverse effect on the estimation performance.

- `pose_measure_uncertainty_time`
- `pose_smoothing_steps`
- `twist_smoothing_steps`

### 2. Tune process model parameters

- `proc_stddev_vx_c` : set to maximum linear acceleration
- `proc_stddev_wz_c` : set to maximum angular acceleration
- `proc_stddev_yaw_c` : This parameter describes the correlation between the yaw and yaw rate. A large value means the change in yaw does not correlate to the estimated yaw rate. If this is set to 0, it means the change in estimated yaw is equal to yaw rate. Usually, this should be set to 0.
- `proc_stddev_yaw_bias_c` : This parameter is the standard deviation for the rate of change in yaw bias. In most cases, yaw bias is constant, so it can be very small, but must be non-zero.

### 3. Tune gate parameters

EKF performs gating using Mahalanobis distance before updating by observation. The gate size is determined by the `pose_gate_dist` parameter and the `twist_gate_dist`. If the Mahalanobis distance is larger than this value, the observation is ignored.

This gating process is based on a statistical test using the chi-square distribution. As modeled, we assume that the Mahalanobis distance follows a chi-square distribution with 3 degrees of freedom for pose and 2 degrees of freedom for twist.

Currently, the accuracy of covariance estimation itself is not very good, so it is recommended to set the significance level to a very small value to reduce rejection due to false positives.

| Significance level | Threshold for 2 dof | Threshold for 3 dof |
| ------------------ | ------------------- | ------------------- |
| $10 ^ {-2}$ | 9.21 | 11.3 |
| $10 ^ {-3}$ | 13.8 | 16.3 |
| $10 ^ {-4}$ | 18.4 | 21.1 |
| $10 ^ {-5}$ | 23.0 | 25.9 |
| $10 ^ {-6}$ | 27.6 | 30.7 |
| $10 ^ {-7}$ | 32.2 | 35.4 |
| $10 ^ {-8}$ | 36.8 | 40.1 |
| $10 ^ {-9}$ | 41.4 | 44.8 |
| $10 ^ {-10}$ | 46.1 | 49.5 |

## Kalman Filter Model

### kinematics model in update function

<img src="./media/ekf_dynamics.png" width="320">

where, $\theta_k$ represents the vehicle's heading angle, including the mounting angle bias.
$b_k$ is a correction term for the yaw bias, and it is modeled so that $(\theta_k+b_k)$ becomes the heading angle of the base_link.
The pose_estimator is expected to publish the base_link in the map coordinate system. However, the yaw angle may be offset due to calibration errors. This model compensates this error and improves estimation accuracy.

### time delay model

The measurement time delay is handled by an augmented state [1] (See, Section 7.3 FIXED-LAG SMOOTHING).

<img src="./media/delay_model_eq.png" width="320">

Note that, although the dimension gets larger since the analytical expansion can be applied based on the specific structures of the augmented states, the computational complexity does not significantly change.

## Test Result with Autoware NDT

<p align="center">
<img src="./media/ekf_autoware_res.png" width="600">
</p>

## Diagnostics

<p align="center">
<img src="./media/ekf_diagnostics.png" width="320">
</p>

<p align="center">
<img src="./media/ekf_diagnostics_callback_pose.png" width="320">
</p>
<p align="center">
<img src="./media/ekf_diagnostics_callback_twist.png" width="320">
</p>

### The conditions that result in a WARN state

- The node is not in the activate state.
- The initial pose is not set.
- The number of consecutive no measurement update via the Pose/Twist topic exceeds the `pose_no_update_count_threshold_warn`/`twist_no_update_count_threshold_warn`.
- The timestamp of the Pose/Twist topic is beyond the delay compensation range.
- The Pose/Twist topic is beyond the range of Mahalanobis distance for covariance estimation.
- The covariance ellipse is bigger than threshold `warn_ellipse_size` for long axis or `warn_ellipse_size_lateral_direction` for lateral_direction.

### The conditions that result in an ERROR state

- The number of consecutive no measurement update via the Pose/Twist topic exceeds the `pose_no_update_count_threshold_error`/`twist_no_update_count_threshold_error`.
- The covariance ellipse is bigger than threshold `error_ellipse_size` for long axis or `error_ellipse_size_lateral_direction` for lateral_direction.

## Known issues

- If multiple pose_estimators are used, the input to the EKF will include multiple yaw biases corresponding to each source. However, the current EKF assumes the existence of only one yaw bias. Therefore, yaw bias `b_k` in the current EKF state would not make any sense and cannot correctly handle these multiple yaw biases. Thus, future work includes introducing yaw bias for each sensor with yaw estimation.

## reference

[1] Anderson, B. D. O., & Moore, J. B. (1979). Optimal filtering. Englewood Cliffs, NJ: Prentice-Hall.
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
/**:
ros__parameters:
node:
show_debug_info: false
enable_yaw_bias_estimation: true
predict_frequency: 50.0
tf_rate: 50.0
extend_state_step: 50

pose_measurement:
# for Pose measurement
pose_additional_delay: 0.0
pose_measure_uncertainty_time: 0.01
pose_smoothing_steps: 5
pose_gate_dist: 49.5 # corresponds to significance level = 10^-10

twist_measurement:
# for twist measurement
twist_additional_delay: 0.0
twist_smoothing_steps: 2
twist_gate_dist: 46.1 # corresponds to significance level = 10^-10

process_noise:
# for process model
proc_stddev_yaw_c: 0.005
proc_stddev_vx_c: 10.0
proc_stddev_wz_c: 5.0

simple_1d_filter_parameters:
#Simple1DFilter parameters
z_filter_proc_dev: 1.0
roll_filter_proc_dev: 0.1
pitch_filter_proc_dev: 0.1

diagnostics:
# for diagnostics
pose_no_update_count_threshold_warn: 50
pose_no_update_count_threshold_error: 100
twist_no_update_count_threshold_warn: 50
twist_no_update_count_threshold_error: 100
ellipse_scale: 3.0
error_ellipse_size: 1.5
warn_ellipse_size: 1.2
error_ellipse_size_lateral_direction: 0.3
warn_ellipse_size_lateral_direction: 0.25

misc:
# for velocity measurement limitation (Set 0.0 if you want to ignore)
threshold_observable_velocity_mps: 0.0 # [m/s]
pose_frame_id: "map"
Loading
Loading