MoTLab -GO Inc. Engineering Blog-MoTLab -GO Inc. Engineering Blog-

Gazeboで学ぶAutowareの歩き方

行灯Labo自動運転
December 17, 2019


💁🏻
※本記事は Mobility Technologies の前身である JapanTaxi 時代に公開していたもので、記事中での会社やサービスに関する記述は公開当時のものです。
An image from Notion

はじめに

ここ数年、国内でも自動運転の公道実証実験が行われるようになるなど、実用化に向けての動きが活発になってきています。

我々の研究開発においても自動運転周りの調査や研究は欠かせません。

今回は有名な国産自動運転フレームワークであるAutowareの使い方について紹介していきたいと思います。

Autowareとは

Autoware株式会社ティアフォーをはじめとしたAutoware Foundationにより開発が進められている日本発のオーブンソースによる自動運転開発環境です。

動作OSとしてはLinux(Ubuntu)を、ミドルウェアとしてはロボットの開発でよく知られているROSおよびROS2を採用しています。

開発言語はC++, Pythonが使用されています。

現在AutowareはROS2ベースのAutoware.Autoへの移行が大分進んでいる印象がありますが、本記事では1つ前のROSベースのAutoware.AIで解説を進めていきます。

Autowareをより理解するには

Autowareの公式ドキュメントや「Autoware自動運転ソフトウェア入門 (安積卓也ら)」などが有名かつ概要が掴みやすいと思います。

本記事ではこれらの記事を補完するように

  • 車の動かし方
  • LiDARのデータを取得方法

についてシミュレータ(Gazebo)を用いて説明をしたいと思います。

前述のコンテンツと合わせて学ぶことで、

  • (仮想)車両を動かしてLiDARのrosbagデータを採る
  • rosbagデータから自己位置推定用の点群マップを作る
  • マップ上に走行経路をつくる
  • 走行経路に沿って(仮想)車両を走らせる

と、自動運転で行うべき基本的なフローを一通り実施することができるようになります。

本記事ではROSの概念などについては説明を行いませんのでご了承ください。

環境

本記事は以下の環境で執筆しております。

An image from Notion

2019年5月にリポジトリがGitHubからGitLabへ移行し、しばらくソースの整理なども行われていましたが、11月中旬の時点でAutoware.AIのリポジトリは比較的安定している様です。

ROS kineticのバージョンが古いとビルドに失敗することがあるので、失敗した場合はROS kineticを再インストールしてからビルドしてみてください。

本記事では~/autoware.ai以下にAutowareがインストールされているものとする。

シミュレータについて

最近ではLGSVL Simulator(Unityベース)やCARLA(UnrealEngine4ベース)などのAutowareに対応している新しくてより自動運転研究に適したシミュレータが出ていますが、今回は導入の容易さからAutowareに組み込まれているGazeboベースのシミュレータを使用します。

Gazeboによるシミュレーションの概要はAutowareの公式にもありますが、本記事では手順周りを少し詳しく説明しようと思います。

シミュレータの起動

まずはシミュレータを起動してみましょう。公式の「Gazebo Simulation」のページではautoware_launcherを使用しているのですが、本記事では「Demo」の延長で説明するためRuntime Managerを使用します。

$ source ~/autoware.ai/install/setup.bash
$ roscore&
$ rosrun runtime_manager run

1行目の環境変数の読み込みは毎度必要なので、専用の端末や仮想マシンで作業している場合は~/.bashrcの末尾等に書いておくと便利です。

その後、roscoreを立ち上げた状態でRuntime Managerを起動します。

An image from Notion

Runtime Manager起動後、SimulationのTabを選択し、左下のGazeboボタンを押すと、Gazeboとシミュレータが起動します。

初回起動時はシミュレーション用の大きなデータのダウンロードが始まるので、しばらくお待ちください。

データのダウンロードが完了すると「mcity」というworldがロードされたGazeboが起動します。

下の起動直後の画像では小さいですが、赤丸をした所に白い仮想車両があります。

An image from Notion

Gazeboシミュレータ構成の概要

次に、RQTでAutowareのGazeboシミュレータのnodeを確認してみましょう。

Runtime Manager右下のRQTボタンを押して起動します。

起動したらMenuから’Plugins > Introspection > Node Graph’ でNode Graphを表示します。

An image from Notion

余計なものを起動していないので、GazeboとAutoware側のGazeboとやりとりをするnodeのみが見えています。

ここで、仮想車両の動作を決定しているのが青枠で囲ったvehicle_gazebo_input_subscriberです。

このnodeが自動運転アルゴリズムがpublish(発行)してくる目標速度、目標角速度をsubscribe(購読)し、仮想車両の制御パラメータに変換してpublishします。

このnodeのソースは、node名で検索すると~/autoware.ai/src/autoware/simulation/vehicle_gazebo_simulation_interface/src/vehicle_gazebo_input_subscriber.cppに見つかります。

いくつかのsubscriberが設定されていますが、デフォルトでは63行目で設定されているコールバック関数vehicleCmdCallback()が使われています。

ここで受信した/vehicle_cmdを仮想車両に渡すパラメータに変換しています。

コントローラーで車両を動かす

車両をコントローラーで動かすため、入力を受け/vehicle_cmdをpublishするnodeを導入します。

インストール

一旦Runtime Managerを終了してください。ROSのjoyパッケージがインストールされていなければインストールします。

$ sudo apt install ros-kinetic-joy
$ sudo apt install ros-kinetic-joystick-drivers

次に、joy_vehicle_cmd_senderを導入します。「LGSVL SimulatorとAutowareによる自動運転チュートリアル」でも紹介されているROSの外部パッケージです。

ver.1.12.0ではビルドツールがcatkinからcolconに移行しています。

上記リポジトリをダウンロードして、~/autoware.ai/src以下に配置後、ビルドします。

$ cd ~/autoware.ai
$ colcon build --packages-select joy_vehicle_cmd_sender

実行

ビルド完了後、ハンドルコントローラー(G29)をPCに接続し、joy_vehicle_cmd_senderを起動します。

$ roslaunch joy_vehicle_cmd_sender sender.launch

環境変数にpathが通っていないかもしれないので、うまく起動しない場合は環境変数設定を読みなおして再度実行してみてください。

$ source ~/autoware.ai/install/setup.bash

起動したら、ハンドルやアクセルを操作して、/vehicle_cmdが変化することを確認してください。

$ rostopic echo /vehicle_cmd/twist_cmd/twist

操作に応じて/vehicle_cmd/twist_cmd/twistの目標速度linear[m/s]と目標角速度angular[rad/s]が変化していればOK。

先ほどのようにシミュレータを立ち上げれば、仮想車両をハンドルで操作できるようになります。

G29を所持していない場合

残念ながらG29を所持していない場合はjoy_vehicle_cmd_sender.cppを改造して手持ちのコントローラーで動くようにします。

動作としては関数publish_vehicle_cmd_()で受け取った/joy topicを解析し、車両制御指示を作成し/vehicle_cmd topicとしてpublishしています。

$ rostopic echo /joy

/joy topicをコンソールに出力してボタンの挙動を確認し、手持ちのコントローラーに合うようにpublish_vehicle_cmd_() を修正しましょう。

ステアリング角を指定したい場合

joy_vehicle_cmd_senderではpublish_vehicle_cmd_()の51-63行目ではvehicle_cmd.twist_cmd.twistに前進速度&回転角速度の形で速度とステアリングを設定しています(ロボット界隈おなじみの表現)。

AutowareのGazeboシミュレータでは前進速度とステアリング角の形式でも受け付けています。

autoware_msgs::ControlCommand ctrl_cmd;
ctrl_cmd.linear_acceleration = 0.0;
ctrl_cmd.linear_velocity = YOUR_VELOCITY; // [m/s]
ctrl_cmd.steering_angle = YOUR_STEER_ANGLE; // [rad]
autoware_msgs::VehicleCmd vehicle_cmd;
vehicle_cmd.ctrl_cmd = ctrl_cmd;

角速度ではなくステアリング角で指定したい場合は、デフォルトではtwist command(速度&角速度)を受けつけるようになっているので、~/autoware.ai/install/vehicle_gazebo_simulation_launcher/share/vehicle_gazebo_simulation_launcher/launch/gazebo_launcher.launch8,9行目の設定を変更して”input/twiststamped”を”false”に、”input/ctrl_cmd”を”true”としてください。

~/autoware.ai/install下のlaunchファイルは、ビルド時に~/autoware.ai/srcからコピーされてくるので、恒久的に変更したい場合はsrc側のファイルを書き換えてください。

点群データの取得

Gazeboシミュレータを起動した時点でLiDARの点群が取得できる状態になっています。

LiDAR入力の確認

Runtime Managerの右下のボタンからRvizを起動します。

この時点では自己位置推定が完了していないので、仮想のLiDARの座標系に表示を切り替えてLiDARが動作していることを確認します。

‘Global Options > Fixed Frame’をvelodyneまたはbase_linkにし、’Points Raw’で/points_raw topicを指定してください。

An image from Notion

すると上記のように車を中心としたLiDAR点群が可視化されます。車両を動かすと移動に合わせて周囲の点群も変化することを確認してください。

ここまでできれば、あとはrosbag record で/points_raw をrosbagデータとして記録すれば、Youtube動画の「Autoware – Mapping using rosbag」や「Planning with ROSBAG」などと同様の手順で、以下ができるようになります。

  • ndt_mappingでPoint Cloud Mapを作成
  • 作成したMap上で自己位置推定
  • waypoint_saverで走行ログから経路データ作成
  • 記録した経路データと同じ経路を自動運転で走らせる

自動運転で走らせる際には、車両へのコマンドが衝突しないようにjoy_vehicle_cmd_senderは停止してください。

NDT Mappingの設定値

補足としてデフォルトの仮想LiDARでNDT Mappingがうまくいったときの設定値を載せておきます。

An image from Notion

Resolutionを変えるのが一番効きます。

傾向としては、大きくする演算時間がかかりますが、マッチングはしやすくなります。

NDT Matchingもコアのアルゴリズムは同じなのでほぼ同様の設定で良いです。

仮想LiDARの設定

Gazeboの車両モデルの定義は~/autoware.ai/install/vehicle_model/share/vehicle_model/urdfvehicle.xacro にありますので、これを少し読んでいきます。

LiDARに関する記述としてはまず、6,7行目のincludeがあります。

ここでは、ROSのパッケージvelodyne_descriptionから2種類の仮想Velodyne(HDL-32E, VLP-16)を読み込んでいます。

57-60行目を見るとこの内HDL32-Eの方を使用しているようです。

パラメータからデータの取得周期や点数は簡単に設定できることがわかります。

パッケージ名を頼りにROSのインストールディレクトリからHDL-32E/opt/ros/kinetic/share/velodyne_description/urdf/HDL-32E.urdf.xacro を見ると、samplesが回転方向のサンプル数、hzが取得周波数[Hz]など、いろいが読み取れると思います。

手持ちのLiDARのスペックが既知であれば、相当するものを作るのも難しくは無いでしょう。

作成されるマップの座標系

NDT Matchingによって作成されるPointCloudのマップの座標系は、入力の最初のフレームのbase_linkを基準に作成されます。

デフォルトの場合ではbase_link位置が原点、車両の前方がx軸の正方向になります。

初期姿勢を毎回Rvizから2D Pose Estimateで指定するのであれば、マップさえRviz上で目視できれば特に問題はないのですが、実車の場合はGPSと合わせて利用することがあるので、x軸の正方向が北を指す様に回転しておいた方が無難です。

私はあまり広くない範囲で実験する場合は真上からPointCloudマップを見下ろした画像と、方位が明らかな地図(Google Map)を比較してz軸周りの回転量を決めています。

その際、簡単には対応が明らかな直線部分を比較しています。

最後に

既存の公式ドキュメントやblogで述べられている箇所は結構飛ばして説明してしまいましたが、以上で仮想車両での実験は一通りできると思います。

有名なセンサー類はdriverもROSのノードも結構揃っているので、シミュレータで慣れればラジコンや実車での実験へ順次ステップアップできるはずです。

Autowareの公式のドキュメントに不足を感じるときはありますが、ソースコードは比較的きれいで読みやすいので、頑張って読めばなんとかなります。


💁🏻
※本記事は Mobility Technologies の前身である JapanTaxi 時代に公開していたもので、記事中での会社やサービスに関する記述は公開当時のものです。

Mobility Technologies では共に日本のモビリティを進化させていくエンジニアを募集しています。話を聞いてみたいという方は、是非 募集ページ からご相談ください!