はじめに
自動運転AIチャレンジ2024 に参加させていただいております。
予選も残り1週間強、ということで最後の追い込み パラメータ調整 をされているチームもあると思います。
2023年大会で実施した パラメータ自動調整 を 2024年大会向けに改良したので、simple_pure_pursuit
の自動調整を例として共有します。
2023年版からの改良点
1. パラメータの渡し方
以下のように launchファイルでノードにパラメータを直接渡す 書き方ができるようなので、 Python(optuna) → 環境変数 → Autowareノード という流れでパラメータを渡すように変更します。
<node pkg="simple_pure_pursuit" exec="simple_pure_pursuit" name="simple_pure_pursuit_node" output="screen">
<param name="use_external_target_vel" value="true"/>
<param name="external_target_vel" value="8.0"/>
<param name="lookahead_gain" value="0.3"/>
<param name="lookahead_min_distance" value="4.0"/>
<param name="speed_proportional_gain" value="1.0"/>
2. 目的関数
競技内容に沿って設計します。
今回の競技内容だと、合計ラップタイム / 最小ラップタイム / 最小ジャークなど最適化対象がありそうですが、まずは 合計ラップタイム を最小にするように変更します。
具体的な実装は後述のサンプルコードを参照ください。
実施例
simple_pure_pursuit
コントローラの4パラメータ external_target_vel
、lookahead_gain
、lookahead_min_distance
、speed_proportional_gain
を自動調整するサンプルを示します。
1. 自動調整実行スクリプトの作成
以下optuna_simple_pure_pursuit.py
を適当な場所に保存します。
import optuna
import subprocess
import os
import json
import numpy as np
import psutil
def objective(trial):
# Optunaによって最適化するパラメータを定義
external_target_vel = trial.suggest_uniform('external_target_vel', 0.1, 15.0)
lookahead_gain = trial.suggest_uniform('lookahead_gain', 0.1, 1.5)
lookahead_min_distance = trial.suggest_uniform('lookahead_min_distance', 0.1, 15.0)
speed_proportional_gain = trial.suggest_uniform('speed_proportional_gain', 0.1, 2.5)
# 最適化されたパラメータを使ってrun_evaluation.bashを起動する
command = ['/bin/bash', '/aichallenge/run_evaluation.bash']
env = os.environ.copy()
env['EXTERNAL_TARGET_VEL'] = str(external_target_vel)
env['LOOKAHEAD_GAIN'] = str(lookahead_gain)
env['LOOKAHEAD_MIN_DISTANCE'] = str(lookahead_min_distance)
env['SPEED_PROPORTIONAL_GAIN'] = str(speed_proportional_gain)
process = subprocess.Popen(command, env=env)
# 評価プロセスが終了するまで待つ(評価時間に応じてタイムアウトを調整)
process.wait(timeout=3600) # 評価時間に応じて適宜調整する
# ノードをキルする
subprocess.run("ps aux | grep ros | grep -v grep | awk '{ print \"kill -9\", $2 }' | sh", shell=True)
# スコアを計算する
try:
with open('/output/latest/result-summary.json') as f:
result = json.load(f)
print(result)
if result["laps"] == []:
score = 999.0
elif len(result["laps"]) < 6:
score = 900.0
else:
score = np.sum(result['laps'])
except Exception as e:
print(f"Error reading result file: {e}")
score = 999.0
return score
def main():
study = optuna.create_study(direction='minimize', study_name='Autoware-turning-study', storage='sqlite:///Autoware-turning-study.db', load_if_exists=True)
study.optimize(objective, n_trials=100)
print('Best parameters:', study.best_params)
print('Best score:', study.best_value)
if __name__ == '__main__':
main()
2. reference.launch.xml
の変更
環境変数を介して、Python(optuna)の提案パラメータを受け取るように変更します。
〜(略)〜
<!-- Optional parameters -->
<arg name="external_target_vel" default="$(env EXTERNAL_TARGET_VEL 8.0)" description="parameters"/>
<arg name="lookahead_gain" default="$(env LOOKAHEAD_GAIN 0.3)" description="parameters"/>
<arg name="lookahead_min_distance" default="$(env LOOKAHEAD_MIN_DISTANCE 4.0)" description="parameters"/>
<arg name="speed_proportional_gain" default="$(env SPEED_PROPORTIONAL_GAIN 1.0)" description="parameters"/>
〜(略)〜
<node pkg="simple_pure_pursuit" exec="simple_pure_pursuit" name="simple_pure_pursuit_node" output="screen">
<param name="external_target_vel" value="$(var external_target_vel)"/>
<param name="lookahead_gain" value="$(var lookahead_gain)"/>
<param name="lookahead_min_distance" value="$(var lookahead_min_distance)"/>
<param name="speed_proportional_gain" value="$(var speed_proportional_gain)"/>
〜(略)〜
実行
※ 環境構築が終わっていてデフォルトソースコードでのシミュレーション実施可能であることを前提とします。
Dockerコンテナ内で以下を実行してください。
(Terminal-1)
pip3 install optuna
cd /path/to/optuna_simple_pure_pursuit.py
python3 optuna_simple_pure_pursuit.py
result-summary.jsonを使用する都合上、壁に衝突して停止してしまった場合などでも、シミュレーション終了を待たなければならないので注意してください。要は 7min/iter 程度の時間がかかる、ということです。
途中経過含めた最適化結果は、別ターミナルでoptuna-dashboardを使って確認できます。
(Terminal-2)
pip3 install optuna-dashboard
cd /path/to/optuna_simple_pure_pursuit.py
optuna-dashboard sqlite:///Autoware-turning-study.db
デフォルトだと http://127.0.0.1:8080/ にアクセスで使えます。
※ Portを変更したい場合は以下でどうぞ。
optuna-dashboard sqlite:///Autoware-turning-study.db --port 8000
おわりに
以上、パラメータ自動調整例のご紹介でした。
今回は目的関数を合計ラップタイムとしましたが、 最小ラップタイム / 最小ジャーク に変更したらパラメータ傾向がどう変わるかなど試してみても面白そうです。
自作Controller / 既存Plannerなど他ノードパラメータへの応用も可能ですので、是非トライしてみてください。
ただ実行時間には改善の余地ありで、壁に衝突・停止した場合は終了する等でより効率化できそうです。
※ 個人的には、パラメータの渡し方を変更することで yamlファイルをぐちゃぐちゃに汚してしまう という前回の課題が改善できて嬉しい…!
ということで、パラメータ調整の泥臭いところはAIにおまかせして、最後まで楽しく走るぞ〜!
この記事は、AI文章校正ツール「ちゅらいと」で校正されています。
追記① 時短版
result-details.json
を使えば多少実行時間が短縮できそうです。
とりあえず90sec/iterバージョンが以下です。
「障害物のない、最初の一周だけでパラメータ評価」が可能です。
import optuna
import subprocess
import os
import json
import numpy as np
import psutil
import time
def objective(trial):
# Optunaによって最適化するパラメータを定義
external_target_vel = trial.suggest_uniform('external_target_vel', 0.1, 15.0)
lookahead_gain = trial.suggest_uniform('lookahead_gain', 0.1, 1.5)
lookahead_min_distance = trial.suggest_uniform('lookahead_min_distance', 0.1, 15.0)
speed_proportional_gain = trial.suggest_uniform('speed_proportional_gain', 0.1, 2.5)
# 最適化されたパラメータを使ってrun_evaluation.bashを起動する
command = ['/bin/bash', '/aichallenge/run_evaluation.bash']
env = os.environ.copy()
env['EXTERNAL_TARGET_VEL'] = str(external_target_vel)
env['LOOKAHEAD_GAIN'] = str(lookahead_gain)
env['LOOKAHEAD_MIN_DISTANCE'] = str(lookahead_min_distance)
env['SPEED_PROPORTIONAL_GAIN'] = str(speed_proportional_gain)
process = subprocess.Popen(command, env=env)
# 90秒待つ
time.sleep(90)
# シャットダウン
# 現在のPythonプロセス以外のすべてのプロセスをキル
current_process = psutil.Process()
for process in psutil.process_iter(attrs=['pid', 'name']):
if process.info['pid'] != current_process.pid:
process.terminate() # プロセスを終了させる
# ノードをキルする
subprocess.run("ps aux | grep ros | grep -v grep | awk '{ print \"kill -9\", $2 }' | sh", shell=True)
# AWSIM終了を待つ
time.sleep(30)
# スコアを計算する
try:
with open('/output/latest/result-details.json') as f:
result = json.load(f)
if result["laps"] == []:
score = 99.0
else:
score = np.min(result['laps'])
except Exception as e:
print(f"Error reading result file: {e}")
score = 99.0
return score
def main():
study = optuna.create_study(direction='minimize', study_name='Autoware-turning-study', storage='sqlite:///Autoware-turning-study.db', load_if_exists=True)
study.optimize(objective, n_trials=100)
print('Best parameters:', study.best_params)
print('Best score:', study.best_value)
if __name__ == '__main__':
main()