📚

AIChallenge 2025の活動記 (番外編:エンドツーエンド自動運転)

に公開

AIチャレンジ決勝 — E2E自動運転の挑戦

AIチャレンジ決勝に参加された方々、本当にお疲れ様でした。
当日はあいにくの雨で、車両制御に苦労した方も多かったのではないでしょうか。

本記事では、予選で猛威を振るったエンドツーエンド(E2E)自動運転モデルについて、その概要と実装方法を紹介します。


🧠 エンドツーエンドモデルとは?

E2Eモデルとは、センサ入力(画像やLiDARなど)から直接制御出力(ステアリングやスロットル)を推論するモデルのことを指します。

AIチャレンジで運営が提供しているAutowareは「ルールベース」な構造で、
自己位置推定 → 経路生成 → 経路追従
というステップを踏んで自動運転を行います。

一方、E2Eモデルではこれらのステップを飛び越え、センサデータから制御信号を直接出力します。

項目 ルールベース (Autoware) E2E モデル
入力 GNSS, IMU, LiDAR, カメラなど 任意のセンサ入力 (例: LiDAR距離データ)
中間処理 自己位置推定 → 経路生成 → 経路追従 なし(センサ→制御を直接推論)
特徴 説明性が高い・安全性重視 柔軟で学習により高性能化可能

🔍 手法の概要

E2Eモデルを開発する際には、
(1) 入力データの選定 と (2) モデル構造の設計 が重要です。

🎯 入力データ

利用可能なセンサは以下の通りです。

  • GNSS
  • IMU
  • Velocity_Status
  • Steering_Status
  • (採点環境外ではRGB画像も可)

しかし今回、私は2D LiDARを仮想的に再現して入力に使用しました。


📡 2D LiDARを仮想的に再現する

「そんなセンサ存在しないのでは?」と思う方、その通りです。
AWSIMから直接出力されるわけではありません。
しかし、laneletマップと自己位置情報を用いることで仮想的に再現可能です。

自己位置から放射状にビームを発射し、壁との距離を取得することで2Dスキャンを生成します。

📎 scan_node ソースコード


⚙️ 2D LiDARを使う理由

2D LiDARを選んだ理由は、圧倒的なデータ効率の良さにあります。

データ種別 1フレームあたりの次元数 比率
RGB画像 3 × 1920 × 1280 ≒ 約7.4M 約6,800倍多い
2D LiDAR 1080 1

画像に比べてデータサイズは1/6800ですが、コース形状や自己位置の把握には十分な情報を含みます。
軽量かつ学習効率が良いため、エッジデバイスにも最適です。


🧩 モデルの選定

LiDAR入力に適した軽量モデルとして、RoboracerプロジェクトのTinyLidarNetが知られています。

📎 TinyLidarNet ソースコード

今回はこのモデルを参考にし、

  • 畳み込み層のチャネル削減
  • 全結合層の最小化
  • PyTorch→NumPyへの移植

を行い、採点環境下でも5.5ms(180hz相当)で推論可能な軽量版を実装しました。

📎 e2e_controller ソースコード


🎮 教師データの収集

E2Eモデルを学習させるために、DualShock4コントローラを用いて人間による制御データを収集しました。

セットアップ手順

1. GitHubからclone

git clone https://github.com/Arata-Stu/aichallenge-2025-AT.git

2. Dockerのセットアップ

./docker_build.sh dev
./docker_run.sh dev gpu
terminator

rosbagデータ記録

Autoware(EKF出力を使用)とAWSIMを起動し、rosbagを記録します。
コントローラのR2ボタンで記録開始、L2ボタンで記録終了するようなシステムになっています。

初回ビルド

bash build_autoware.bash

terminal 1(Autoware起動)

source workspace/install/setup.bash
ros2 launch original_launch system.launch.xml record:=true

terminal 2(AWSIM起動)

run_simulator.bash

コントローラ設定

ボタン 機能
Manual / Autonomous 切り替え
× リセット
押下中のみ人間制御を入力
R2 rosbag record 開始
L2 rosbag record 停止

データ保存先: /aichallenge/record/


🧾 rosbagから学習データ作成

cd /aichallenge/python_ws/supervised_learning
python3 extract_data_from_bag.py --bags_dir /aichallenge/record --outdir ./datasets/extracted

🧠 学習・推論手順

学習

理想的には、学習データと検証データを別で用意するのですが、試す程度なら同じパスを指定しても問題ないです。

python3 train.py data.train_dir=./datasets/extracted/ data.val_dir=./datasets/extracted/

重みは ./ckpts/ に保存されます。

PyTorch → NumPy形式変換

./ckpts/ に保存されている重みパスを指定します。

python3 convert_weight.py --ckpts /path/to/weight.pth

ROS 2 ノード実行

変換した重みを指定して実行しましょう。コントローラの◻︎ボタンで自動運転が始まるはずです。ピット内部の走行は基本的に安定しないので、ピットの外に出るまでは手動で操作することをおすすめします。

ros2 launch original_launch system.launch.xml   record:=false   e2e:=true   ckpt_path:=/path/to/weight.npy

🏁 まとめ

  • E2Eモデルはセンサ入力から制御を直接学習する革新的手法
  • 仮想2D LiDARにより、軽量で効率的なデータ表現を実現
  • 採点環境下でもリアルタイム動作可能なTinyLidarNet派生モデルを構築

次回大会では、E2Eモデルが広く利用されることを期待しています。


🧩 関連リンク

岐阜大学アレックス研究室

Discussion