自動運転AIチャレンジ2025の開発環境(Autoware + AWSIM)において、パラメータチューニングを自動化するためのメモ。
Optunaとは?
Optuna は、Python製のハイパーパラメータ自動最適化ライブラリです。
ベイズ最適化などの手法を用いて、少ない試行回数で効率的に最適なパラメータを見つけることができます。
ベイズ最適化とは、評価コストの高い関数に対して、過去の試行結果をもとに次に試すべき点を予測しながら探索を進める手法です。
なぜOptuna?
AutowareのPure Pursuit制御パラメータ(例:lookahead距離、ゲインなど)は、シミュレーション評価における走行性能に大きく影響する。
手動チューニングは時間がかかるし、最適値を見つけるのもなかなか大変。気合と根性で調整するのではなく、できれば寝ている間に自動でチューニングしてほしい。
そこで、「評価スクリプトとOptunaを連携」させて、AWSIM上での1周タイムを自動で最適化してみた。
最終構成イメージ
aichallenge-2025/
├── optuna_tune_pure_pursuit.py # Optuna本体
├── evaluate_wrapper.py # 1回分の評価+結果読み取り
├── run_evaluation_60sec.bash # Autoware/AWSIM評価 (60秒で自動終了)
├── workspace/src/...
│ └── aichallenge_submit_launch/
│ └── launch/
│ ├── reference.launch.xml.template # envsubst用テンプレート
│ └── reference.launch.xml # 評価時に自動生成
├── output/YYYYMMDD-HHMMSS/result-summary.json # 評価結果(最小タイムなど)
├── optuna_logs/tuning_result_YYYYMMDD.csv # 試行ログ(自動保存)
今回は以下3つのパラメータを対象に調整する。
lookahead_gain
lookahead_min_distance
speed_proportional_gain
手順まとめ
1. Dockerfileに envsubst を追加
RUN apt-get update && apt-get install -y gettext-base
envsubst がないとテンプレート置換が動かない。明示的に入れておく。
envsubst は、環境変数を展開(置換)するためのコマンドラインツール。
テンプレートファイルにある $VARIABLE
を実際の環境変数の値に置き換えるだけのシンプルなツール。
また requirements.txt
に optuna
を追記しておく。
2. reference.launch.xml.template
を環境変数対応に修正
<param name="lookahead_gain" value="${PURE_PURSUIT_LOOKAHEAD_GAIN}"/>
<param name="lookahead_min_distance" value="${PURE_PURSUIT_LOOKAHEAD_MIN}"/>
<param name="speed_proportional_gain" value="${PURE_PURSUIT_SPEED_GAIN}"/>
3. 評価用ラッパー evaluate_wrapper.py
import os, sys, subprocess, glob, json, time
lookahead_gain, lookahead_min, speed_gain = sys.argv[1:4]
os.environ["PURE_PURSUIT_LOOKAHEAD_GAIN"] = lookahead_gain
os.environ["PURE_PURSUIT_LOOKAHEAD_MIN"] = lookahead_min
os.environ["PURE_PURSUIT_SPEED_GAIN"] = speed_gain
subprocess.run([
"bash", "-c",
"envsubst < workspace/src/.../reference.launch.xml.template > workspace/src/.../reference.launch.xml"
])
subprocess.run(["bash", "./run_evaluation_60sec.bash"])
time.sleep(3)
paths = sorted(glob.glob("output/*/result-summary.json"))
score = float(json.load(open(paths[-1])).get("laps", [9999])[0]) if paths else 9999
print(score)
4. 評価を60秒で終える run_evaluation_60sec.bash
の一部
最後まで評価すると時間がかかるため、60秒だけ動かして1周目だけのタイムで評価する。
echo "Running for 60 seconds..."
sleep 60
cleanup
5. Optuna本体 optuna_tune_pure_pursuit.py
import optuna
import subprocess
import json
import os
import pandas as pd
from datetime import datetime
N_TRIALS = 20 # 試行回数
def objective(trial):
lookahead_gain = trial.suggest_float("lookahead_gain", 0.05, 0.5)
lookahead_min = trial.suggest_float("lookahead_min", 0.5, 5.0)
speed_gain = trial.suggest_float("speed_gain", 0.1, 2.0)
print(f"Trying: lookahead_gain={lookahead_gain:.3f}, lookahead_min={lookahead_min:.3f}, speed_gain={speed_gain:.3f}")
result = subprocess.run(
["python3", "evaluate_wrapper.py", str(lookahead_gain), str(lookahead_min), str(speed_gain)],
capture_output=True,
text=True
)
try:
score = float(result.stdout.strip())
print(f"→ Score: {score:.3f}")
return score
except Exception as e:
print("Failed to parse score:", e)
return float("inf")
def main():
print(f"Starting Optuna optimization: {N_TRIALS} trials")
study = optuna.create_study(direction="minimize")
study.optimize(objective, n_trials=N_TRIALS)
print("\nBest parameters found:")
print(study.best_params)
log_dir = "optuna_logs"
os.makedirs(log_dir, exist_ok=True)
timestamp = datetime.now().strftime("%Y%m%d-%H%M%S")
df = study.trials_dataframe()
csv_path = os.path.join(log_dir, f"tuning_result_{timestamp}.csv")
df.to_csv(csv_path, index=False)
print(f"Trial log saved to: {csv_path}")
if __name__ == "__main__":
main()
おわりに:雑感と今後の拡張
Optunaを試してみたが、結論としては、手動でチューニングした最初のパラメータのほうがラップタイムが速かった。
20回試行した中の大半はコースアウトして壁に衝突していた。改善の余地あり。
当たり前だけど、
- 調整対象のパラメータ選定
- 探索範囲と試行回数のバランス
- 評価指標の設計
- エラー処理の堅牢さ
は重要。
ある程度は人間がチューニングしてから、最後の詰めの部分だけ自動化するのが現実的かもしれない。
今後試してみたいこと:
- 評価関数を最適化
- OptunaのDashboardや可視化plotで挙動を確認
備考メモ
-
result-summary.json
が出ないときはautoware.log
を確認 - rosbag 記録が重すぎる場合は記録対象の制限を検討
この記事の目的
チーム内でのノウハウ共有や、再現性のある検証環境の整備を目的とした備忘録。間違いを見つけたり、うまくいったりしたら、更新するかもしれません。アドバイスやご指摘もありがたいです。
本格導入前のプロトタイプとして試してみたい人の参考になればうれしいです。