実車の始動遅れを軽減#
シミュレーションでは、自車両はAutowareによって生成された制御コマンドにほぼ瞬時に反応します。 ただし、実際の車両では遅延が発生し、エゴの反応が鈍くなる可能性があります。
このページでは、実車で Autoware を使用したときに発生する開始遅延を紹介します。 開始遅延を、 (a) Autoware が自車両を始動させることを決定したときと、 (b) 車両が実際に動き始めるまでの時間として定義します。 より正確に:
- (a) は、Autoware によって出力された速度または加速度コマンドがゼロ以外の値に切り替わる時刻です。
- (b) は自車両の測定速度が正の値に切り替わる時刻です。
手動運転時の発進遅れ#
まず、人間が運転する場合の発進遅れを見てみましょう。
次の図は、人間のドライバーがギアを _パーキング_から_ドライブ_に切り替え、すぐにブレーキを放してスロットルペダルを押して車両の速度を上げたときの始動遅れを示しています。
この図からは注目すべき点が複数あります。
- ブレーキ (赤): ドライバーが瞬時にブレーキペダルを放したにもかかわらず、
測定されたブレーキは
100%
から0%
まで150ms
かかることがわかります。 - ギア(オレンジ): ドライバーはブレーキペダルを放す_前_にギアを切り替えますが、ギアはブレーキペダルを放した_後_に切り替わるように測定されます。 the brake is released.
- スロットル(緑)と速度(青): ドライバーがスロットルペダルを押すと、車両が
500ms
後で動き始めることが測定されます。
フィルター遅延#
乗客の快適性を保証するために、 一部のAutowareモジュールは車両の急激な変化にフィルターを実装し、加速度の突然の変化を防ぎます。
たとえば、
vehicle_cmd_gate
コントローラによって
生成された加速度コマンドをフィルタリングするため、
以前は加速度が負の停止コマンドと
加速度が正の移動コマンドの間で移行するときに
大幅な遅延が発生していました。
ジャークフィルターのため、負と正の間の遷移は瞬時ではなく、数百ミリ秒かかります。
ギアディレイ#
多くの車両では、最初に車両を動かし始める前にギアを変更する必要があります。 このギアチェンジを自律的に実行すると、かなりの時間がかかる場合があります。 また、マニュアル運転で記録したデータからもわかるように、ギアの計測値が遅れる場合があります。
Autowareでは、ギアが_ドライブ_状態に変更されるまで、コントローラーは停止制御コマンドを送信します。 これは、ギア変更の遅れとその報告値が始動遅れに大きな影響を与える可能性があることを意味します。 これは、車両が最初に_パーキング_ギアに入っている場合にのみ問題となることに注意してください。
この遅延を減らす唯一の方法は、車両を調整してギアチェンジ速度を上げるか、 ギアチェンジレポートの遅延を減らすことです。
ブレーキの遅れ#
ブレーキペダルを備えた車両では、 ブレーキシステムは多くの場合、瞬時に動かすことができない複数の可動部品で構成されています。 したがって、Autowareが車両にブレーキコマンドを送信する場合、 車輪にかかる実際のブレーキにはある程度の遅延が予想されます。
このブレーキが長引くと、自己車両の初期動作が妨げられたり、遅れたりする可能性があります。
この遅れは車両をチューニングすることで短縮できます。
スロットルレスポンス#
スロットル制御を備えた車両の場合、 始動遅延の主な原因の1つは車両の スロットル応答によるものです。 スロットルペダルを踏んでも、車両の車輪はすぐには回転しません。 これは部分的には車両の慣性によるものですが、 ホイールにトルクを加え始めるまでにかなりの時間がかかる モーターも原因です。
この遅延を減らすために車両側のパラメータの一部を調整することは可能かもしれませんが、 多くの場合、エネルギー効率の低下させて行われます。
Autoware側では、この遅延を減らす唯一の方法は初期スロットルを上げることですが、 これにより初期加速が不快に高くなる可能性があります。
初期加速とスロットル#
先ほど説明したように、スロットル制御を備えた車両の場合、初期スロットル値を大きくすると、始動遅れを減らすことができます。
Autoware は加速値を出力するため、変換モジュール
raw_vehicle_cmd_converter
はAutowareからの加速値を車両に送信されるスロットル値にマッピングするために使用されます。
このようなマッピングは通常、
accel_brake_map_calibrator
モジュールを使用して自動的に調整されますが、
初期スロットルが低くなり、始動遅延が大きくなる場合があります。
初期スロットルを増やすには2つのオプションがあります: Autowareによって初期加速出力を増やすか、 加速とスロットルのマッピングを変更する。
Autoware による初期加速出力は、
motion_velocity_smoother
のengage_velocity
とengage_acceleration
パラメータを使用して調整できます.
ただし、vehicle_cmd_gate
制御コマンドにフィルターを適用して、ジャークと加速度の急激な変化を防ぎ、
自車両が停止している間の最大許容加速度を制限します。
あるいは、加速度のマッピングを調整して、初期加速度に対応するスロットルを増加させることもできます。
加速度マップ
の例を見ると、
次の変換が行われます:
自己速度が0
(最初の列) の場合、0.631
(1 行目)と0.836
(2 行目) の間の加速度値は
0%
と10%
の間のスロットルに変換されます。
これは、0.631m/s²
以下の初期加速が発生してもスロットルが発生しないことを意味します。
加速マップを調整した後は、
ブレーキマップ
の更新も必要になる場合があることに注意してください。
デフォルト | 0 | 1.39 | 2.78 | 4.17 | 5.56 | 6.94 | 8.33 | 9.72 | 11.11 | 12.5 | 13.89 |
---|---|---|---|---|---|---|---|---|---|---|---|
0 | 0.631 | 0.11 | -0.04 | -0.04 | -0.041 | -0.096 | -0.137 | -0.178 | -0.234 | -0.322 | -0.456 |
0.1 | 0.836 | 0.57 | 0.379 | 0.17 | 0.08 | 0.07 | 0.068 | 0.027 | -0.03 | -0.117 | -0.251 |
0.2 | 1.129 | 0.863 | 0.672 | 0.542 | 0.4 | 0.38 | 0.361 | 0.32 | 0.263 | 0.176 | 0.042 |
0.3 | 1.559 | 1.293 | 1.102 | 0.972 | 0.887 | 0.832 | 0.791 | 0.75 | 0.694 | 0.606 | 0.472 |
0.4 | 2.176 | 1.909 | 1.718 | 1.588 | 1.503 | 1.448 | 1.408 | 1.367 | 1.31 | 1.222 | 1.089 |
0.5 | 3.027 | 2.76 | 2.57 | 2.439 | 2.354 | 2.299 | 2.259 | 2.218 | 2.161 | 2.074 | 1.94 |