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(lane_departure_checker): add parameter of footprint_extra_margin #1565

Conversation

yn-mrse
Copy link

@yn-mrse yn-mrse commented Sep 30, 2024

Description

本PRでは「自己位置推定が大きくずれる前に停車する機能」を実現するため、lane_departure_checkerにおける車両周囲に固定のマージンを設ける機能を追加する。
この機能は下記の通り、車両左右方向に0.2[m]下駄を履かせた範囲を監視するために利用する想定となっている。
image

autoware最新ではこれに相当するパラメータとして footprint_extra_marginが存在するが、
本PRではこのパラメータに対する簡易実装で上記機能を実現する。

計算式

Footprintの計算は、従来下記のように計算していた。

const auto margin = calcFootprintMargin(covariance, param.footprint_margin_scale);

これに対して固定値のマージンを加算したい。

const auto margin = calcFootprintMargin(covariance, param.footprint_margin_scale) + constant_margin;

ここでcalcFootprintMargin関数はFootPrintMargin構造体 {double lat, double lon} を戻り値にとるため、各要素にマージンを加算する必要がある。
c++にはoperatorのオーバーロード機能があるため、これを活用して和の形で計算できるようにする。

パラメータ値

本PRでは「自己位置推定が大きくずれる前に停車する機能」に対するパラメータ値の適用を可能とするとともに、既存の機能のリグレッションを防止しなければならない。
よってdefaultの値としては固定マージンの値を0.0と設定し、新たな機能を適用する際に外部リポジトリからパラメータ値を変更するポリシーとする。

Related links

How was this PR tested?

パラメータ値 footprint_extra_marginを設定ファイルから変更することで経路逸脱判定結果が変動することを確認した。
これにより

  1. 設定ファイルが正常に読み込まれること
  2. パラメータ値により経路逸脱判定結果が期待通り変動すること
    を確認できている。
狭路走行、footprint_extra_margin = 0.0[m]

経路逸脱(及び逸脱予測)の判定が発生は見られない。
image

LatestLaneDepartureLevel = 0 (=OK)

狭路走行、footprint_extra_margin = 0.5[m]

経路逸脱の判定が常に発生し続けた。
image

LatestLaneDepartureLevel = 2 (=ERROR)

Notes for reviewers

None.

Interface changes

None.

Effects on system behavior

None.

control/lane_departure_checker/README.md Outdated Show resolved Hide resolved
yn-mrse and others added 3 commits October 1, 2024 20:51
Co-authored-by: Shigekazu Fukuta <107168699+sfukuta@users.noreply.github.com>
@yn-mrse yn-mrse merged commit 0245366 into beta/v0.3.19 Oct 1, 2024
8 of 9 checks passed
@yn-mrse yn-mrse deleted the feat/lane_departure_checker/add_param_footprint_extra_margin branch October 1, 2024 11:56
Copy link

sonarcloud bot commented Oct 1, 2024

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants