Skip to content

自動緊急ブレーキ (AEB)#

目的/役割#

autonomous_emergency_braking は、制御モジュールによって作成された予測経路上の障害物や、制御モジュールから推定されたセンサー値との衝突を防ぐモジュールです。

前提条件#

このモジュールは以下の前提条件に基づいています。

  • 自車の予測経路は、センサーから作成された経路、制御モジュールから作成された経路、またはその両方のいずれかから作成できます。
  • 自車の現在の速度と角速度は、自車のセンサーから取得でき、点として障害物が使用されます。
  • AEBs の対象障害物は、入力された点群から取得するか、予測された自車のフットプリント経路と予測されたオブジェクトの形状との交点を求めることで取得できる 2D 点です。

IMU パス生成: ステアリング角度と IMU の角速度#

現在、IMU ベースのパスは、IMU 自体によって取得された角速度を使用して生成されています。角速度の代わりにステアリング角度を使用することが提案されています。

両方のアプローチの長所と短所は次のとおりです。

IMU 角速度:

  • (+) 一般的に高精度
  • (-) 車両の振動によりノイズが発生する可能性があります。

ステアリング角度:

  • (+) ノイズが少ない
  • (-) ステアリングオフセットまたは間違ったギアレシオが発生する可能性があり、Autoware のステアリング角度と実際のステアリングが同じではない場合があります。

現時点では、AEB モジュールのパス作成プロセスにステアリング角度を実装する予定はありません。

内部処理/アルゴリズム#

AEB は、緊急停止信号を出力する前に次の手順を実行します。

  1. 必要に応じて AEB をアクティブ化します。

  2. 自車の予測経路を生成します。

  3. 入力点群や予測されたオブジェクトデータから対象障害物を入手します。

  4. 最も近い障害物の速度を推定します。

  5. 対象障害物との衝突チェックを行います。

  6. /diagnostics に緊急停止信号を送信します。

以下に、各セクションの詳細を示します。

1. 必要に応じて AEB をアクティブ化する#

次の条件を満たしている場合は、AEB モジュールをアクティブ化しません。

  • 自車が自動運転状態にない場合
  • 自車が動いていない場合 (現在の速度が 0.1 m/s のしきい値を下回る場合)

2. 自車走行経路の予測#

AEBは、搭載センサーから取得した現在の速度および現在の角速度に基づいて、予測したフットプリント経路を生成します。use_imu_pathfalseの場合、このステップはスキップされることに注意してください。この予測経路は以下のように生成されます。

\[ x_{k+1} = x_k + v cos(\theta_k) dt \\ y_{k+1} = y_k + v sin(\theta_k) dt \\ \theta_{k+1} = \theta_k + \omega dt \]

ここで、\(v\)\(\omega\)はそれぞれ現在の縦断速度および角速度です。\(dt\)はユーザーが事前に定義できる時間間隔です。

一方、use_predicted_trajectoryがtrueに設定されている場合、AEBモジュールはMPCからの予測経路をベースとしてフットプリント経路を生成します。IMUフットプリント経路とMPCフットプリント経路は同時に使用できます。

3. ターゲット障害物の取得#

自車フットプリント経路を生成した後、ターゲット障害物が特定されます。ターゲット障害物を検索するには、入力点群を使用するか、知覚モジュールから来る予測オブジェクト情報を使用する2つの方法があります。

点群障害物フィルタリング#

AEBモジュールは、入力点群をフィルタリングして、自車が衝突する可能性のあるターゲット障害物を見つけることができます。この方法は、use_pointcloud_dataパラメーターをtrueに設定すると有効になります。点群障害物フィルタリングには、粗フィルタリング、クラスタリングによるノイズフィルタリング、厳密フィルタリングの3つの主要ステップがあります。

粗フィルタリング#

粗フィルタリングステップでは、単純なフィルタを使用してターゲット障害物を選択します。自車の予測経路から一定の距離(デフォルトは自車幅の半分にpath_footprint_extra_marginパラメーターを加えたもの)まで検索エリアを作成し、その範囲内にない点群は無視します。粗フィルタリングステップは以下に示されています。

rough_filtering

クラスタリングと凸包によるノイズフィルタリング#

AEBがノイズのある点を考慮するのを防ぐため、フィルタリングされた点群に対してユークリッドクラスタリングが実行されます。クラスタを形成するには他の点に十分近くない点群内の点は破棄されます。さらに、クラスタ内の各点はcluster_minimum_heightパラメーターと比較され、クラスタ内のどの点もcluster_minimum_heightより大きい高さ/z値を持たない場合、点のクラスタ全体が破棄されます。cluster_toleranceminimum_cluster_sizemaximum_cluster_sizeパラメーターを使用して、クラスタリングと無視するオブジェクトのサイズを調整できます。AEBモジュールで使用されるクラスタリング方法の詳細については、PCLライブラリのユークリッドクラスタリングに関する公式ドキュメントを確認してください:https://pcl.readthedocs.io/projects/tutorials/en/master/cluster_extraction.html

さらに、検出された各クラスタの周囲に2D凸包が作成され、各包の頂点はクラスタの最も外側の点を表します。次に、これらの頂点は次のステップでチェックされます。

厳密フィルタリング#

ノイズフィルタリング後、モジュールは幾何学的衝突チェックを実行して、フィルタリングされた障害物/包の頂点が実際に自車と衝突する可能性があるかどうかを判断します。このチェックでは、自車は長方形として、点群障害物は点として表されます。衝突の可能性がある頂点のみが保持されます。

rigorous_filtering

ターゲット障害物の取得における予測オブジェクトの使用#

use_predicted_object_dataパラメーターをtrueに設定すると、AEBは知覚モジュールから来る予測オブジェクトデータを使用してターゲット障害物点を取得できます。これは、自車の予測フットプリント経路と各予測オブジェクトの包囲多角形またはバウンディングボックスとの2D交点を取得することで行われます。

predicted_object_and_path_intersection

ターゲット障害物との最接近の特定#

すべてのターゲット障害物が特定されたら、AEBモジュールは自車に最も近い点を衝突チェックの候補として選択します。RSS距離は衝突が発生するかどうかを判断するために使用され、自車への最も近い頂点が衝突から安全とみなされる場合、残りのターゲット障害物も衝突から安全であるため、最も近い点のみが考慮されます。

closest_object

4. 障害物速度推定#

ターゲットポイントの速度の計算を開始するには、ポイントは速度計算エリアに入る必要があります。これは、speed_calculation_expansion_marginパラメーターによって定義されます。 運用環境によっては、このマージンは初期計算ステップ中に速度の誤算によって引き起こされる不必要な自動緊急ブレーキを軽減することができます。

自動運転ソフトウェアドキュメント#

speed_calculation_expansion

最も近い障害物/ポイントの位置が決定されると、AEBモジュールは、以下の式を使用して、過去に検出されたオブジェクトの履歴から、最も近いオブジェクトの相対速度を推定します。

\[ d_{t} = t_{1} - t_{0} \]
\[ d_{x} = norm(o_{x} - prev_{x}) \]
\[ v_{norm} = d_{x} / d_{t} \]

ここで、\(t_{1}\)\(t_{0}\)は、現在の最も近いオブジェクトと、直前のポイントクラウドフレームの最も近いオブジェクトを検出するために使用したポイントクラウドのタイムスタンプであり、\(o_{x}\)\(prev_{x}\)は、それらのオブジェクトの位置です。

relative_speed

最も近い障害物/ポイントが予測されたオブジェクトデータを使用して得られる場合、\(v_{norm}\)は、x軸とy軸で予測されたオブジェクトの速度のノルムを直接計算することで計算されます。

次に、速度ベクトルをエゴの予測経路と比較して、縦方向速度\(v_{ego}\)を取得します。

\[ v_{obj} = v_{norm} * Cos(yaw_{diff}) + v_{ego} \]

ここで、\(yaw_{diff}\)は、エゴパスと移動ベクトルとの間のヨー差で、$$v_{pos} = o_{pos} - prev_{pos} \(\(、\)v_{ego}\)は、エゴの現在の速度で、エゴの移動によるポイントの移動を考慮していますが、オブジェクトによる移動は考慮していません。これらすべての式は、z軸(2D)を無視して実行されます。

オブジェクト速度は、エゴの現在の移動方向に対して計算されていることに注意してください。オブジェクトがエゴの移動とは逆方向に移動する場合、オブジェクト速度は負になり、次のステップでのrss距離が短くなります。

推定されたオブジェクト速度の結果は、タイムスタンプ付きの速度のキューに追加されます。次に、AEBは過去の速度推定の有効期限を確認し、期限切れの速度測定をキューから削除します。オブジェクトの有効期限は、速度が最初にキューに追加されてからの経過時間が、パラメーターprevious_obstacle_keep_timeより大きいかどうかを確認することによって決定されます。最後に、キューの平均速度が計算されます。平均速度は、衝突確認に使用されるRSS距離を計算するために使用されます。

5. RSS距離を使用したターゲット障害物との衝突チェック#

第4ステップでは、RSS距離を使用して最も近い障害物ポイントとの衝突をチェックします。RSS距離は次のように定式化されます。

\[ d = v_{ego}*t_{response} + v_{ego}^2/(2*a_{min}) -(sign(v_{obj})) * v_{obj}^2/(2*a_{obj_{min}}) + offset \]

ここで、\(v_{ego}\)\(v_{obj}\)は現在のエゴと障害物の速度、\(a_{min}\)\(a_{obj_{min}}\)はエゴとオブジェクトの最小加速度(最大減速)、\(t_{response}\)は減速を開始するエゴ車両の応答時間です。したがって、エゴ車両から障害物までの距離がこのRSS距離\(d\)よりも小さい場合、エゴ車両は緊急停止信号を送信します。これは次の図に示されています。

rss_check

6. /diagnosticsに対する緊急停止信号の送信#

AEBが前のステップでポイントクラウド障害物との衝突を検出した場合、このステップで/diagnosticsに緊急信号を送信します。緊急停止を有効にするには、ERRORレベルの緊急事態を送信する必要があります。さらに、AEBユーザーは設定ファイルを修正して緊急レベルを維持する必要があります。そうしないと、Autowareは緊急状態を保持しません。

ユースケース#

前方の車両が急ブレーキ#

前方車両が急ブレーキをかけ、AEBモジュールによって衝突が検出されると、AEBを起動できます。エゴ車両と前方車両の距離が十分に大きく、エゴの緊急加速度値が十分に高い場合、急ブレーキをかける前方車両との衝突を回避または緩和することができます。注意: AEBがrss距離の計算に使用した加速度は、緊急ブレーキ中にエゴが使用する加速度とは必ずしも同じではありません。実際の車両で使用される加速度は、mrm_emergency stop jerkとacceleration値を変更することで調整できます。

front vehicle collision prevention

急に登場したオブジェクトへの停止#

突然物体が現れた場合、他のモジュールが時間内に物体を検出できなかったとき、AEB は自動運転車両を停止するためにフェイルセーフとして動作できます。オブジェクトによる急な割り込みが予想される場合は、expand_width パラメータを増やすことで、AEB モジュールがオブジェクトが自動運転車両の実際のパスに入る前に衝突を検出するのに役立つ場合があります。

後方車両との衝突防止

後方オブジェクトとの衝突の防止#

AEB モジュールは、自動運転車両が後退している場合にも衝突を防止できます。

後退運転

オドメータの誤りによる衝突の防止(IMU パスのみ)#

車両オドメータの情報に誤りがある場合、MPC が自動運転車両の正しいパスを予測できない可能性があります。MPC が予測したパスが間違っていると、衝突回避が計画モジュールで意図したとおりに機能しません。ただし、AEB の IMU パスは MPC に依存せず、他のモジュールが衝突を検出できない場合に衝突を予測できる可能性があります。たとえば、MPC パスが間違っており、AEB の IMU パスのみが衝突を検出する仮想ケースの図を示します。

間違った mpc

パラメータ#

Name 単位 タイプ 説明 デフォルト値
publish_debug_markers [なし] ブール デバッグマーカーを発行するフラグ true
publish_debug_pointcloud [なし] ブール デバッグに使用されるポイントクラウドを発行するフラグ false
use_predicted_trajectory [なし] ブール コントロールモジュールからの予測パスの使用フラグ true
use_imu_path [なし] ブール センサーデータによって生成された予測パスの使用フラグ true
use_object_velocity_calculation [なし] ブール オブジェクト速度計算の使用フラグ。 false に設定すると、オブジェクト速度は 0 [m/s] に設定されます。 true
check_autoware_state [なし] ブール Autoware ステートチェックの有効/無効フラグ。 false に設定すると、エゴ車が AUTONOMOUS ステートにない場合でも AEB モジュールは動作します。 true
detection_range_min_height [m] 倍精度 誤検出によるゴーストブレーキを回避するために使用される検出範囲の最小高さ 0.0
detection_range_max_height_margin [m] 倍精度 誤検出によるゴーストブレーキを回避するために使用される検出範囲の最大高さのマージン。 detection_range_max_height = vehicle_height + detection_range_max_height_margin 0.0
voxel_grid_x [m] 倍精度 ボクセルグリッドフィルタの X 軸ダウンサンプリングパラメータ 0.05
voxel_grid_y [m] 倍精度 ボクセルグリッドフィルタの Y 軸ダウンサンプリングパラメータ 0.05
voxel_grid_z [m] 倍精度 ボクセルグリッドフィルタの Z 軸ダウンサンプリングパラメータ 減速
cluster tolerance [m] 倍精度 2 つの点の間に許容可能な最大距離。それ以下の距離では、同じクラスタの一部とみなされます。 0.15
cluster_minimum_height [m] 倍精度 クラスタ内の少なくとも 1 つの点が衝突対象の可能性のあるクラスタに含まれるために、この値よりも高くする必要があります。 0.1
minimum_cluster_size [なし] 整数 対象の障害物として考慮されるためには、クラスタに必要最低限のポイント数 10
maximum_cluster_size [なし] 整数 対象の障害物として考慮されるためには、クラスタに含まれる最大ポイント数 10000
min_generated_imu_path_length [m] 倍精度 センサーによって生成された予測パスの最小距離 0.5
max_generated_imu_path_length [m] 倍精度 センサーによって生成された予測パスの最大距離 10.0
expand_width [m] 倍精度 衝突チェック時のエゴ車両の拡張幅 0.1
longitudinal_offset [m] 倍精度 衝突チェック時の縦方向オフセット距離 2.0
t_response [s] 倍精度 エゴ車が前方の車両を検知してから減速を開始するまでの反応時間 1.0
a_ego_min [m/ss] 倍精度 エゴ車両の最大減速度 -3.0
a_obj_min [m/ss] 倍精度 オブジェクトの最大減速度 -3.0
imu_prediction_time_horizon [s] 倍精度 センサーによって生成された予測パスの時間範囲 1.5
imu_prediction_time_interval [s] 倍精度 センサーによって生成された予測パスの時間間隔 Planning
mpc_prediction_time_horizon [s] 倍精度 mpc によって生成された予測パスの時間範囲 1.5
mpc_prediction_time_interval [s] 倍精度 mpc によって生成された予測パスの時間間隔 0.1
aeb_hz [なし] 倍精度 AEBが1秒間に動作する頻度 10
speed_calculation_expansion_margin [m] 倍精度 開始速度計算時のエゴ車両の拡張幅 0.1

制約事項#

  • 衝突検出後の停止に必要な距離は、自車速度と減速性能によって異なります。衝突を回避するには、検出距離を長くし、より高い減速率を設定する必要があります。ただし、不要なアクティベーションの数を増やす可能性があるため、トレードオフが生じます。したがって、このモジュールが果たすべき役割を考慮し、それに応じてパラメータを調整することが不可欠です。
  • AEBは、地上に近い障害物に対しては反応できない場合があります。これは、点群に適用される前処理方法のパフォーマンスに依存します。
  • センサーから取得した縦方向加速度の情報は、ノイズが大きいので使用されていません。
  • センサーデータから作成された予測経路の精度は、自車に搭載されたセンサーの精度に依存します。

aeb_range