# ICRA2019 Robomaster AI challenge 技術報告
---
# はじめに
ICRA2019 Robomaster AI challenge (以降AICと略)で敵の検出,戦略意思決定システム,戦闘優位座標計算システム,ナビゲーションシステムを担当した安達です.この記事ではAICにおける僕が担当した部分の技術的取り組みを中心に報告します.この記事を読むことで今回のプロジェクトで使用されたハイレイヤソフトウェアはほぼ完全に理解できるようになります.
# Robomasterについて
Robomaster はロボット同士で弾を撃ち合いより多く相手のHPを削ったほうが勝つというシンプルなロボット競技で毎年中国の深センで試合が行われています.ロボットでやる FPS やサバゲーと考えてもらえば,わかりやすいと思います.オペレーターはフィールドと隔絶されたオペレータルームからロボットに搭載したカメラの情報を頼りにロボットを操作して戦います.詳しいルールについては[ここ](http://projectrm.niwakasoft.jp/what-is-robomaster/)に記述されています. FUKUOKA NIWAKA では,もちろんこの大会にも参加していますが,今回参加したのはこの大会とは少し違ったものです.
# AICとRobomaser本戦の違いについて
紹介した Robomaster 本戦と今回参加した AIC の大きな違いは主に2つです.
- 全自動が必須である点
- ルール,フィールドが本戦より簡単化されている点 (Fig1 フィールド)
全自動が必須となっているため,当然ソフトウェア側に要求される技術はより高度なものとなります.
ルールの簡単化として代表的なものとして
- ロボットは大会側から借りて使用し,大きなハードウェアの変更が許されていないこと (Fig2 ロボット)
- ロボットは歩兵ロボット2台のみであること
- フィールドに凹凸がなくロボットの移動経路は常に水平であること
これらが挙げられます.
# FUKUOKA NIWAKA AIC 開発チームの構成
僕はハイレイヤソフト全般を担当しましたが,ここで今回の開発チーム構成について振り返っておきます. FUKUOKA NIWAKA AIC 開発チームの構成は以下のようになっています.
- 機械学習担当 : 1名
- 組み込み開発担当兼チームリーダー : 1名
- ハイレイヤ全般担当 : 1名
- ハード担当兼メンテナンス担当 : 1名
- 回路担当 : 1名
- インテグレーション・実験担当 : 2名
そしてハード以下の4名は本戦の方のタスクが多く AIC に向けて動けたのは直前からという状況でした.つまり AIC に専念出来たエンジニアは3名だったということです.
我々は限られた人的リソースでソフトウェア開発を行っていく必要がありました.僕は常にどのように手を抜いて,どのように妥協して優勝できるかを考えていました.
# 結果
大会の結果としては 3rd PRIZE となりました.これは3位ではなく3等級という結果になります.ただしビデオ審査で68校が24校に絞られている点,第一試合でBerkeley,第二試合でAlbertaに勝って得られた結果であるという事実にも目を向けると悪い結果とも言えません.(Fig3 賞状)
# RobomasterBattleSystemの構成
今回自分が担当したハイレイヤのソフトウェア群を RobomasterBattleSystem と呼ぶことにします.これは ROS を使用して構成されています. RobomasterBattleSystem は以下に示すノード群で構成されています. (Fig4 rqt_graph)
RobomasterBattleSystem
- model_simulator
- communication_node
- lidar_node
- laser2location
- enemy_detector
- obstacle_cloud_generator
- battle_position_planner
- decision_maker
- move_base
- recovery_command_publisher
以下ではそれぞれのパッケージの技術的な概要を説明していきます.
### model_simulator
(Fig5 シミュレーション環境)
- 主要機能
- gazeboによるシミュレーション
- 詳細
gazeboによって実機の挙動をシミュレートするためのノードです.今回ホロノミックモデルの実装が間に合わずホロノミック対応のパスフォロワーについてはシミュレートは行っていませんでした.これは来年のシーズンが始まるまでにどうにかします.
### communication_node
- 主要機能
- マイコンとの通信
- ロボット間通信
- ロボットidやチームカラーの登録
- 詳細
通信機能が集約されたノードです.組み込み担当の宮崎君が書いてくれました.
### lidar_node
- 主要機能
- lidarのデータ入出力を管理
- 詳細
今回は[RPLIDAR](https://www.slamtec.com/en/Lidar/A2)を2台使用しているためオープンになっているROSノード [rplidar_ros](https://github.com/robopeak/rplidar_ros)を使用しました.
### laser2location
(Fig6 自己位置推定動画)
- 主要機能
- 自己位置の推定
- tf(map→base_link)のブロードキャスト
- 詳細
スキャンデータを使用した自己位置推定にはspiralray氏がNHK学生ロボコン2015用に開発してその後公開した[nhk2015_back_ros](https://github.com/spiralray/nhk2015_back_ros)のlaser2locationを一部改変して使用しました.
これは点群をラスター画像化した後,OpenCVのハフ変換により直線を抽出し,それらの線をフィールドのフェンスとして自己位置を推定するものです.詳しくは[ここ](https://blog.spiralray.net/archives/324)で解説されています.
今回はこのノードを複数のLiDARで使用できるようにし,定期的に取得できる屋内GPSによる絶対位置によって補正して使用しました.
AICではフェンスは半透明のガラスであり,他のチームはそれをセンシングする危うさからほとんどがLiDARを障害物より低い高さに設置しSLAMによる自己位置推定をしていましたが,FUKUOKA NIWAKAでは本番環境と同様の半透明ガラスに対しLiDAR計測実験を行十分使用可能であるとしフェンスを計測して自己位置推定を行いました.これによって以下のメリットを得られました.
- 自己位置推定の実装が簡単になること
- 自己位置推定の計算負荷が低減できること
- 自己位置推定用のLiDARを利用して障害物に隠れた敵の索敵が可能になること
特に3つ目のメリットは大きく,常にフィールド内の敵は可観測であることを前提とした戦略システムを組むことができました.これによって試合を通しての2台の敵の識別も可能になりました.これは2台それぞれに行った攻撃の回数から残りのそれぞれのロボットのおおよそのHPを推定可能になるということです.どちらかのマシンに対して集中攻撃することも可能になりました.AICではFUKUOKA NIWAKA以外に障害物より高い位置にLiDARを設置しているチームは1チームもありませんでした.
というか,ハイレイヤのソフトウェアはDJIがオープンにしてる[パッケージ](https://github.com/RoboMaster/RoboRTS)があるらしく,一からハイレイヤを構築してるチームはFUKUOKA NIWAKAのみでした.これはシンプルに僕の情報収集不足が原因です.しかし,そのおかげでソフトウェアの自由度が高かったのも事実です.AICではFUKUOKA NIWAKA以外のチームはDJIのソフトウェアに準拠するためにすべてのチームが全く同じ位置にLiDARを搭載していました.
### enemy_detector
(Fig7 トラッキング動画)
- 主要機能
- 点群のクラスタリング
- 敵の識別・トラッキング
- 敵の向きの推定
- 詳細
laser2locationによって得られる自己位置データを使用してLiDARの点群をmapフレームに変換できます.mapフレームではフィールドのフェンスを定義できるためLiDARの点群からフィールドフェンスと思われる点群を引き算すれば敵ロボット2台と味方ロボット1台,計測を行っているロボット自身の点群のみが残ります.
自己位置から計測を行っているロボット自身の点群を消し,味方同士の通信で共有される味方ロボットの位置から味方ロボットの点群を消します.残るのは敵ロボット2台の点群のみになります.
これに対しクラスタリングを行いクラスタごとの点群の重心を算出します.
それぞれのロボットにおいて前回位置と前回速度,前々回速度を用いて加速度一定モデルでこのステップに計測される重心位置の予測を行い,それらと実際に計測された重心との距離によって識別を行います.
ホロノミックではありますが,砲塔のジンバルは車両の前方から±90°しか旋回できない特性から敵ロボットが探索を行っているとき進行方向と砲塔の向きは一致しているという前提で速度を利用し砲塔の向きも推定しています.
### obstacle_cloud_generator
(Fig8 オブスタクルクラウド動画)
- 主要機能
- 侵入禁止エリアに対する障害物点群の追加
- 敵とボット,味方ロボット周辺に対する障害物点群の追加
- 詳細
AICのフィールドにはルール上侵入禁止な領域が存在します.今回のソフトウェアでは敵の補給エリア,ディフェンスエリアを侵入禁止に設定しました.補給エリアに侵入すればルール違反で失格になりますし,ディフェンスエリアに侵入すれば敵のディフェンスボーナスが有効化され敵に与えるダメージが半分になってしまいます.
また,LiDARでの敵ロボット・味方ロボットの検出はLiDARを付けた高さの点群しかとらえることができず,ロボットの全長を正確に捉えることはできていません.
経路計画に使用されるコストマップはLiDARの点群を考慮し障害物をマップに反映するため,ロボットに侵入して欲しくない領域に仮想のLiDAR点群をばら撒くことでそれを回避する軌道の生成が可能になります.ここの実装はAutowareの[lidar_fake_perception](https://gitlab.com/autowarefoundation/autoware.ai/core_perception/tree/master/lidar_fake_perception)を参考にしました.侵入禁止エリアは矩形領域内に格子状に点を並べ,ロボットは重心を中心としてロボッとサイズ内に同心円状に並べています.
### battle_position_planner
(Fig9 バトルポジション動画)
- 主要機能
- 銃撃戦を有利に進めるポジションを計算する
- 詳細
ロボットの四辺には装甲版という得点有効エリアがあります.障害物を利用し敵ロボットから装甲版を隠しつつ,こちらの砲塔からは敵の装甲版をロックできるポジショニングを行うのが基本戦略です.
障害物に隠れた敵も索敵可能なFUKUOKA NIWAKAのロボットならではの戦略と言えます.
まず,敵ロボット1から身を隠すのに利用できそうな障害物(盾オブジェクト)を探索します.盾オブジェクトによって発生する影をシミュレーションし,その陰から砲塔のみを出すポジションを計算します.そのポジションが敵ロボット2から隠れられているかをチェックし隠れることができていない場合は残りの障害物から盾オブジェクトの再探索を行います.
これに侵入禁止エリアやフィールド外には目標座標を生成しないという制約を加えて使用していました.
### decision_maker
- 主要機能
- 補給に行くべきか,ディフェンスエリアに行くべきか,battle_position_plannerで計算されたbattle_positionに行くべきかを判断する
- 詳細
AICに出場するロボットは球を補給するために補給エリアに行く必要があり,それとは別にディフェンスエリアに一定時間滞在して有効化することで敵からの攻撃で受けるダメージを半減できます.これらのエリアは時間ごとに開放されるシステムになっています.補給は30秒に一回,バフエリアは前回の有効化から1分の経過が解放条件となっています.
これらに対してdecision_makerノードはロボット本体の状態機械,ディフェンスエリアの状態機械,補給エリアの状態機械を用意しそれらの状態を加味しロボットのタスクを決定していました.敵と相対していればbattle_positionに行くことが最優先,そうでなければ現状受け入れ可能なエリアに行くのが最優先になります.
### move_base
(Fig10 Teb画像)
- 主要機能
- コストマップの生成
- グローバルパスの生成
- ローカルパスの生成
- 詳細
ROSデフォルトでプラグインとして使用できるmove_baseを使用しました.
コストマップはobstacle_cloud_generatorで生成されたobstacle_cloudを元に生成されます.
今回はホロノミック対応でいい感じのパスを出してくれる[Timed Elastic Band Local Planner](http://wiki.ros.org/teb_local_planner)を使用しました.
来年は流石に自分で書きます.
### recovery_command_publisher
- 主要機能
- move_baseがリカバリ不可能になった場合に障害物から遠ざかるようにコマンドを生成
- 詳細
move_baseのリカバリーは安全のためかなり弱いです(旋回動作によって周辺の障害物マップを更新しようとする).人がいる環境でのナビゲーションはそうあるべきですがこれはロボット競技なので,多少強引でも障害物から離れるようにコマンドを生成しています.
# RobomasterBattleSystemに残された課題
今年のRobomasterBattleSystemは最上位に目標座標を決定するレイヤがありその下にナビゲーションがありました.しかし,到達可能性については考慮されていませんでした.
敵ロボットが極めて動的なこの競技ではbattle_position_plannerも10Hz前後の周波数が必要となり,その下にグローバル・ローカルプランナが入っている構造には無理があったように感じます.実際,最適座標に到達する前に敵が移動し最適座標の位置が大きく変化することも少なくありませんでした.最適座標が計算できても到達できなければ意味がありません.
人間がサバゲーやFPSをやるときにフィールド全域の最適座標に行くことを目標にして常にグーグルマップで経路を調べているようなものです.敵前でそんなことをしていては撃たれてしまいます.さらに今回のフィールドとマシン速度から考えるとほぼ室内戦のようなスケールです.移動というよりアクションという感じのスケールでナビゲーションのパッケージが動いているのは違和感を覚えます.本来自己位置推定すら必要ないのではないかという考えすら浮かんできます.
今回のシステムは目的ありきで動くシステムでしたが,もっと直近の未来にフォーカスした戦略システムが必要に感じます.ルールにもよりますが人間もサバゲー中は身を隠すことを最優先にしているように感じます.目的ありきで動くのではなく次ステップ動作の合理性ありきなシステムも必要です.
# 来年のシステム設計
前項で低レイヤ重視の戦略システムの必要性について述べましたが,高レイヤの戦略が必要なくなるわけではありません.長期的に見ても短期的に見ても最適な戦略を選定できることがベストです.静的な長期目的と動的な短期目的を定め動作計画の評価指標にすれば今年より良いパフォーマンスが期待できます.
静的な長期目的として自チームの補給エリア,ディフェンスエリア付近の領域で試合を展開することで,それぞれの移動コストが下がり有利に試合を進められるはずです.また動的な短期目標として敵ロボットから身を隠すこと,敵とロボットを砲塔の射程にとらえることなどが考えられます.
静的な長期目的は常に少しずつ行動決定の評価関数に影響を与えるようにして主に会敵していないときに強く影響するように設計します.動的な短期目的はポテンシャルフィールド化し動作計画時の評価関数に加えるというのが現段階での構想です.
しかし,もちろん来年度はルールも変わるためルール発表以降,方針を再検討する必要がありそうです.
# 終わりに
最後まで読んでくださってありがとうございました.
FUKUOKA NIWAKA AIC 開発チームは現在深刻な人手不足に陥っています.FUKUOKA NIWAKA の中の人,外の人問わずメンバーを募集していますので興味があれば気軽に関係者にお声がけください.