はじめに
こんにちは!ティアフォーの片岡と申します。
本日は、ティアフォーのSimulation Teamで開発してきたシナリオテストフレームワークであるscenario_simulatorをApache-2.0ライセンスでOSS(オープンソースソフトウェア)とした件についてお話します。
github.com
また、ティアフォーでは「自動運転の民主化」をともに実現すべく、ロボット技術、ゲームエンジンを使った開発等幅広い分野に知見を持ったSimulation Engineerを募集しております。
自動運転のSimulator開発は、バグの少ない高品質なコードを書くのはもちろんのこと、三次元幾何や統計、はてはプログラミング言語開発まで様々な知識が要求される分野であり、広く深く様々なことをやってみたい方には非常にマッチするポジションであると思います。
もし興味等ございましたら以下のページよりコンタクトいただければ大変幸いです。
カジュアルな面談等も大歓迎です!
tier4.jp
Autoware開発におけるSimulation Test
ティアフォーで行われているSimulation Testの種類
現在ティアフォーではSimulatorによってそれぞれ得意・不得意な領域があることを認識しており、テストケースごとに適切なSimulatorを選定し評価を行っています。
AutowareをサポートしているSimulator
上の図で記されているのは大枠のカテゴリであり、実際にはAutoware対応のSimulatorには様々なものが存在しています。代表的なものには以下のようなものがあります。
SVL Simulator
youtu.be
github.com
LGエレクトロニクスのシリコンバレー研究所が開発しているUnityベースのSimulatorで、Pythonでテストシナリオを記述できます。
LiDARやCameraを多数取り付けたリッチな自動運転システムがSimulation可能です。
CARLA Simulator
youtu.be
github.com
IntelやToyota Research Instituteの出資のものとOpen Sourceで開発されているUnreal EngineベースのSimulatorで、OpenSCENARIO V1.0やPython等でテストシナリオを記述できます。
野心的な機能が多数盛り込まれており、非常に高機能なSimulatorです。
AutoCore Simulator
youtu.be
github.com
The Autoware Foundation (AWF) メンバーのAutoCoreが開発したUnityベースのSimulatorです。
非常に軽量でGTX750Tiでも動作可能になっています。
Simple Planning Simulator
youtu.be
github.com
AutowareArchitectureProposalに同梱されているSimulatorです。
ROSノードとして実装されており、OpenSCENARIO V0.9.2をベースとしたティアフォーの独自フォーマットでのシナリオ記述が可能で、軽量であるため非常に高速に動作します。
複数のSimulatorを使う場合に起こる問題点
複数のSimulatorを使ってシナリオテストを行っていく過程でティアフォーは以下のような問題に直面しました。
シナリオフォーマットがSimulatorに依存している
汎用なシナリオフォーマットはOpenSCENARIO等様々なものが提案されていますが、Simulator固有の拡張が入っていたり、SVL Simulator等独自シナリオフォーマットを中心としているようなSimulatorも多いため、一度書いたシナリオを使い回すのは簡単ではありません。
シナリオを異なるSimulatorの間でやり取りするには人力で動作確認をしながらポーティングを行う必要があり、シナリオ変更履歴のトレーサビリティの観点からも大きな問題があります。
NPCロジックがSimulatorごとに異なる
完全に等価なシナリオを人力でポーティングできたとしても、それを処理する処理系が異なるのであれば処理結果は異なってしまいます。
具体的な例として、「車の前に自転車が飛び出す」という状況を考えてみましょう。
これをシナリオに起こす時、以下のような処理が記述されることになります。
- ある地点から N(m) 以内に自車両が入った時
- 自転車のNPCをSpawnさせ、Waypointを与える。
ここで、自転車NPCの行動ロジックがSimulator Aでは「直線の点列をカクカクなぞる」、Simulator Bでは「スプライン補間したあと単純追跡コントローラでその経路をできるだけなぞる」のように異なっていた場合、これらは等価なテストシナリオとは言えません。
こういったNPC行動ロジックは厳密に一致している必要があります。
これをCARLAやSVL Simulatorに備わっているテストランナーの枠組み上で解決しようとすると、彼らのソースコードに含まれる何千行ものNPC行動ロジック記述部分に手を入れて異なる言語やプラットフォームを超えて完全に等価なロジックを実装し、メンテナンスし続けなくてはなりません。
これはほとんど不可能に近いと言えます。
こういった問題を解決するために仕様策定されたのがOpenSCENARIOですが、例えば以下のような基本的な箇所ですら未定義動作が非常に多く、OpenSCENARIOに対応したからと言って一度書いたシナリオがすべてのSimulatorで簡単に動くということは担保できません。
OpenSCENARIO V1.0の未定義動作の例
- 道路端点や世界の端に到達したNPCはどう振る舞うべきか
- AssignRouteActionで経路指定した結果ゴールに到達したNPCはそのまま走っていくべきか、それともその場で停止するべきか
- レーンチェンジができない場所でレーンチェンジ指示が出た場合はどのような挙動をすべきか
SimulatorごとにIntegrationの仕方が違う
例えばCARLAにおいては独自ブリッジでROSおよびAutowareとのIntegrationを行っており、ブリッジ内部でPID制御器が動いていたりと他のSimulatorと全く異なるロジックで制御がなされています。
youtu.be
他にも、SVL SimulatorはAutowareとrosbridgeで接続しており、ROSの標準的なツールを用いてインターフェースが設計されています。
https://www.lgsvlsimulator.com/docs/autoware-instructions/www.lgsvlsimulator.com
このように、Simulatorごとに根本的に異なるインターフェースが設計されており、これはクラウド上にテストパイプラインを構築、メンテナンスしていく上で大きな障害になります。
また、明示的な標準仕様がないため、新しいSimulatorをIntegrationする際には毎回設計を1からやり直す必要があり莫大な工数が発生することになります。
シナリオフォーマットは現在も技術開発が盛んな領域
現在シナリオフォーマットには様々なものが提案されています。
例えば、ASAMという標準化団体が提唱しているOpenSCENARIO V1.0が有名です。
www.asam.net
その他にも、現在策定が進められているOpenSCENARIO V2.0およびそのベースとなっているM-SDL
youtu.be
といった様々なフォーマットが現在も開発されています。
産業界だけでなく、2019年ので発表されたGeoSCENARIO等アカデミア方面からも研究開発が進められています。
geoscenario.readthedocs.io
どのシナリオフォーマットをどう使うのがAutowareの評価を最も効率化できるのかというのは未だ結論が出ていない領域の1つです。
そのため、同時に複数のシナリオフォーマットをサポートできるようなシナリオテストフレームワークが強く求められます。
ティアフォーにおいてはこれらの問題点を以下のアプローチで解決しました。
ティアフォーのシナリオテストフレームワークのアプローチ
Co-Simulation Modelの採用
すべてのSimulatorにおいてNPCロジックを共通化するため、NPCロジックをシナリオテストフレームワーク中の交通流Simulatorに対して実装しました。
センサSimulatorが交通流Simulatorとプロセス間通信を行い、歩調を合わせながらCo-SimulationをすることでNPCロジック共通化を実現しています。
これにより、交通流SimulatorはセンサSimulatorに対するOpenSCENARIOの「翻訳機」かのように振る舞い、OpenSCENARIOの未定義動作によるSimulatorごとの差異を吸収します。
プロセス間通信はすべて同期呼び出しで実装されており、シナリオテストフレームワークのうちROS 2に依存しない部分に関しては決定性を担保しています。
シナリオテストフレームワークとシナリオ解釈器のコンポーネント分離
シナリオテストフレームワークにC++ APIを用意し、シナリオフォーマットの解釈器がそれを叩くアーキテクチャ構成にすることで同時に複数のシナリオフォーマットをサポートしています。
完全にコンポーネントが分離されているので、スッキリとしたアーキテクチャに仕上がっています。
Simulatorを抽象化
SimulatorとAutowareとのインターフェースを統一し、複数のSimulatorを同時にサポートできるシナリオテストフレームワークを開発しました。
Autowareとの結合部分や、NPCロジックで使われている微分幾何アルゴリズムやHD MapとのインテグレーションをSimulatorで独自実装する必要はありません。
また、Autowareは非常に高い頻度で更新が行われているソフトウェアであり、常に結合確認を取りながらインテグレーションを行う必要があり、メンテナンスコストが非常に高いです。
これらの複雑で開発を難航させる原因になりがちなロジックはすべてシナリオテストフレームワークに含まれていますし、メンテナンスもティアフォーのSimulation Team主体で行っているため、Simulator開発者は短期間でSimulatorとAutowareを結合し、その結合を維持することが非常に簡単になりSimulatorとしてより本質的なセンサSimulationの高精度化や車両の運動モデルといった開発に時間を使うことができるようになります。
Open Source
更に、ティアフォーではこのシナリオテストフレームワークをオープンにすることでAutowareを様々なSimulator上で動かしてAutowareの評価を更に高速化していく仕組みを担保しようと考えています。
ライセンスはApache-2.0で統一されているため非常に使いやすいツール群となっています。
ティアフォーのシナリオテストフレームワークのアーキテクチャ
アーキテクチャ全体の紹介
本シナリオテストフレームワークのAWFの公式シナリオフォーマットであるTier IV Scenario Format version 2.0フォーマットあるいはテストシーケンスを記述したworkflowファイルの読み込みは、テストを起動するScenario Test Runner、OpenSCENARIO 1.0フォーマットで記述されたシナリオを解釈するOpenSCENARIO Interpreter、交通流をSimulationするTraffic Simulatorおよび本フレームワークにセンサSimulatorを統合する際の簡易なセンサSimulatorのリファレンス実装となるSimple Sensor Simulatorが含まれています。
OpenSCENARIO InterpreterおよびTraffic Simulatorは下のような実装になっており、シングルプロセスなROS 2 Nodeとして実装されています。
ティアフォーのシナリオテストフレームワークはAutowareとSimulatorの間をつなぐ役割を果たします。
シナリオテストフレームワークはROS 2との通信部分以外がシングルスレッドで動作する単独のROS 2 nodeとして設計されており、ROS 2 topicをPub / Subする部分を除いて完全に決定性があります。
シナリオテストフレームワークと通信してCo-Simulationを行うSimulatorはZeroMQで同期的に通信を行います。
zeromq.org
ZeroMQは様々な言語をサポートしており、Unity (C#)やUnreal Engine (C++)等様々な言語、プラットフォームで作られているSimulatorと簡単に通信することができます。
また、ZeroMQで送信されるデータはProtocol Buffersを使ってシリアライズすることで、スキーマを明確に定義してSimulator開発者がインターフェースが変わったことをすぐに把握できるよう工夫しています。
developers.google.com
SimulatorとROS 2はAutoware APIというAutowareを操作するために定義されたROS 2 topic群を利用して通信します。シナリオテストフレームワークは内部にBehavior Treeを用いたNPCロジックやHD Map管理機構を内包しており、それらを操作できるC++のインターフェースを備えています。
まず第一弾としてSimulatorに依存しないシナリオフォーマットの代表格の一つであるOpenSCENARIO V1.0をシナリオフォーマットとして採用し、シナリオテストフレームワークのC++ Interfaceを叩いてOpenSCENARIO規格に基づいてSimulationを行えるツールを開発しました。
その過程で動作確認用に副次的に生まれたC++ Scenario(ROS 2ノードからシナリオテストフレームワークのインターフェースをダイレクトに操作して実現)の誕生により、はからずも複数シナリオフォーマットをサポートすることが可能なアーキテクチャであることが立証されました。
下のC++ Scenarioのサンプルコードに示すような非常に簡易な指示をscenario_simulator::APIクラス(シナリオテストフレームワークとのC++ Interface)を経由して出すだけでSimulator内部のNPCの行動を制御することが可能です。
// Copyright 2021 Tier IV, Inc. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #include <quaternion_operation/quaternion_operation.h> #include <ament_index_cpp/get_package_share_directory.hpp> #include <rclcpp/rclcpp.hpp> #include <traffic_simulator/api/api.hpp> #include <traffic_simulator/metrics/metrics.hpp> // headers in STL #include <memory> #include <string> #include <utility> #include <vector> // headers in pugixml #include "pugixml.hpp" class ScenarioRunnerMoc : public rclcpp::Node { public: explicit ScenarioRunnerMoc(const rclcpp::NodeOptions & option) : Node("scenario_runner", option), api_( this, __FILE__, ament_index_cpp::get_package_share_directory("kashiwanoha_map") + "/map/lanelet2_map.osm", 5) { api_.setVerbose(true); api_.initialize(1.0, 0.05); pugi::xml_document catalog_xml_doc; catalog_xml_doc.load_string(catalog_xml.c_str()); auto vehicle_params = traffic_simulator::entity::VehicleParameters(catalog_xml_doc).toRosMsg(); vehicle_params.name = "ego"; api_.spawn(false, "ego", vehicle_params); api_.setEntityStatus( "ego", traffic_simulator::helper::constructLaneletPose(120545, 0), traffic_simulator::helper::constructActionStatus(10)); api_.setTargetSpeed("ego", 15, true); pugi::xml_document pedestrian_xml_doc; pedestrian_xml_doc.load_string(pedestrian_xml.c_str()); const auto pedestrian_params = traffic_simulator::entity::PedestrianParameters(pedestrian_xml_doc).toRosMsg(); api_.spawn(false, "tom", pedestrian_params); api_.setEntityStatus( "tom", "ego", traffic_simulator::helper::constructPose(10, 3, 0, 0, 0, -1.57), traffic_simulator::helper::constructActionStatus()); api_.requestWalkStraight("tom"); api_.setTargetSpeed("tom", 3, true); api_.spawn( false, "bob", pedestrian_params, traffic_simulator::helper::constructLaneletPose(34378, 0.0), traffic_simulator::helper::constructActionStatus(1)); api_.setTargetSpeed("bob", 1, true); vehicle_params.name = "npc1"; api_.spawn( false, "npc1", vehicle_params, traffic_simulator::helper::constructLaneletPose(34579, 20.0), traffic_simulator::helper::constructActionStatus(5)); api_.setTargetSpeed("npc1", 5, true); lanechange_executed_ = false; vehicle_params.name = "npc2"; api_.spawn( false, "npc2", vehicle_params, traffic_simulator::helper::constructLaneletPose(34606, 20.0), traffic_simulator::helper::constructActionStatus(5)); api_.setTargetSpeed("npc2", 0, true); api_.requestAssignRoute( "ego", std::vector<openscenario_msgs::msg::LaneletPose>{ traffic_simulator::helper::constructLaneletPose(34675, 0.0), traffic_simulator::helper::constructLaneletPose(34690, 0.0)}); api_.requestAcquirePosition( "npc1", traffic_simulator::helper::constructLaneletPose(34675, 0.0)); api_.spawn(false, "npc3", vehicle_params); api_.setEntityStatus( "npc3", traffic_simulator::helper::constructLaneletPose(34468, 0), traffic_simulator::helper::constructActionStatus(10)); /* api_.addMetric<metrics::TraveledDistanceMetric>("ego_traveled_distance", "ego"); api_.addMetric<metrics::MomentaryStopMetric>( "ego_momentary_stop0", "ego", -10, 10, 34805, metrics::MomentaryStopMetric::StopTargetLaneletType::STOP_LINE, 30, 1, 0.05); api_.addMetric<metrics::MomentaryStopMetric>( "ego_momentary_stop1", "ego", -10, 10, 120635, metrics::MomentaryStopMetric::StopTargetLaneletType::STOP_LINE, 30, 1, 0.05); api_.addMetric<metrics::MomentaryStopMetric>( "ego_momentary_stop_crosswalk", "ego", -10, 10, 34378, metrics::MomentaryStopMetric::StopTargetLaneletType::CROSSWALK, 30, 1, 0.05); */ std::vector<std::pair<double, traffic_simulator::TrafficLightColor>> phase; phase = { {10, traffic_simulator::TrafficLightColor::GREEN}, {10, traffic_simulator::TrafficLightColor::YELLOW}, {10, traffic_simulator::TrafficLightColor::RED}}; api_.setTrafficLightColorPhase(34802, phase); using namespace std::chrono_literals; update_timer_ = this->create_wall_timer(50ms, std::bind(&ScenarioRunnerMoc::update, this)); } private: void update() { if (api_.getCurrentTime() >= 4 && api_.entityExists("tom")) { api_.despawn("tom"); } /* if (api_.getLinearJerk("ego")) { std::cout << "ego linear jerk :" << api_.getLinearJerk("ego").get() << std::endl; } */ if (api_.reachPosition( "ego", traffic_simulator::helper::constructLaneletPose(34615, 10.0), 5)) { api_.requestAcquirePosition( "ego", traffic_simulator::helper::constructLaneletPose(35026, 0.0)); if (api_.entityExists("npc2")) { api_.setTargetSpeed("npc2", 13, true); } } if (api_.reachPosition("ego", traffic_simulator::helper::constructLaneletPose(34579, 0.0), 5)) { api_.requestAcquirePosition( "ego", traffic_simulator::helper::constructLaneletPose(34675, 0.0)); if (api_.entityExists("npc2")) { api_.setTargetSpeed("npc2", 3, true); } } if (api_.reachPosition( "npc2", traffic_simulator::helper::constructLaneletPose(34513, 0.0), 5)) { api_.requestAcquirePosition( "npc2", traffic_simulator::helper::constructLaneletPose(34630, 0.0)); api_.setTargetSpeed("npc2", 13, true); } /* if (api_.checkCollision("ego", "npc1")) { std::cout << "npc1 collision!" << std::endl; } if (api_.checkCollision("ego", "npc2")) { std::cout << "npc2 collision!" << std::endl; } */ if (api_.getCurrentTime() > 10.0 && api_.entityExists("bob")) { api_.despawn("bob"); } api_.updateFrame(); } bool lanechange_executed_; bool target_speed_set_; int port_; traffic_simulator::API api_; rclcpp::TimerBase::SharedPtr update_timer_; std::string catalog_xml = R"(<Vehicle name= 'vehicle.volkswagen.t2' vehicleCategory='car'> <ParameterDeclarations/> <Performance maxSpeed='69.444' maxAcceleration='200' maxDeceleration='10.0'/> <BoundingBox> <Center x='1.5' y='0.0' z='0.9'/> <Dimensions width='2.1' length='4.5' height='1.8'/> </BoundingBox> <Axles> <FrontAxle maxSteering='0.5' wheelDiameter='0.6' trackWidth='1.8' positionX='3.1' positionZ='0.3'/> <RearAxle maxSteering='0.0' wheelDiameter='0.6' trackWidth='1.8' positionX='0.0' positionZ='0.3'/> </Axles> <Properties> <Property name='type' value='ego_vehicle'/> </Properties> </Vehicle>)"; std::string pedestrian_xml = R"(<Pedestrian model='bob' mass='0.0' name='Bob' pedestrianCategory='pedestrian'> <BoundingBox> <Center x='0.0' y='0.0' z='0.5'/> <Dimensions width='1.0' length='1.0' height='2.0'/> </BoundingBox> <Properties/> </Pedestrian>)"; }; int main(int argc, char * argv[]) { rclcpp::init(argc, argv); rclcpp::NodeOptions options; const auto component = std::make_shared<ScenarioRunnerMoc>(options); rclcpp::spin(component); rclcpp::shutdown(); return 0; }
このように、ROS 2と密にIntegrationされ非常に簡易に使用できるインターフェースとなっていますので、今後他のシナリオフォーマットを採用する必要が出た場合は、その解釈器さえ書いてしまえば簡単にAutoware、Simulatorと接続を行うことができます。
開発時に注力した要素
シナリオテストフレームワーク開発においては、以下の要素に対して開発時に大きく注力しました。
レーン座標系のサポート
レーン座標系とは、レーンに沿って歪んだ座標系のことです(いわゆるフレネ座標系です)。
みなさんが公道で車を運転する時、「前30mにトラックがいる」というとそれはデカルト座標系で距離を計算したら30m先にトラックがいるという意味ではなくレーンに沿ってこのまま進んだら30m先にトラックがいるという意味になるかと思います。
レーン座標系でシナリオが記述できないと、直感的な記述ができず非常にシナリオ記述が煩雑なものとなります。
また、レーン座標系を計算する時にはスプライン曲線等のパラメトリック曲線で点列を補間する処理が入るのですが、どんな式の形のパラメトリック曲線を使用するかで補間の結果は全く異なります。
そのため、シナリオテストフレームワークでは内部にレーン座標系、ワールド座標系、物体間の相対座標系を相互に座標変換するAPIを備えており、Simulatorとプロセス間通信する際に渡される情報ではすべての物体位置はワールド座標系で記述されています。
これらの座標変換はtfを介さずにフルスクラッチで実装されていますので、完全に決定性があります。
この仕組みを導入することによってSimulatorはレーン座標系をサポートするためにHD Mapを解釈する必要がなくなり、AutowareとIntegrationする際の工数を大幅に削減することができる上、どのSimulatorを使っても完全に同じロジックで座標変換が行われるのでクオリティの担保が非常にやりやすくなります。
強化されたNPCロジック
Autowareに同梱されているSimple Planning SimulatorのNPCロジックは非常にシンプルなものでした。
- レーンに沿って動く
- NPCの前方にBounding Boxを設け、その中に他のNPCやAutowareの車両が入った場合急ブレーキを踏む
実装されていたロジックはこの2点のみです。
これではシナリオライターはNPCの一挙手一投足を指定しなければならず、シナリオ作成に大きな負荷が発生していました。
そこでBehavior Treeを使用してNPCロジックを大幅に強化し、以下のような挙動を明示的に指示しなくても自動的にやってくれるようにしました。
- レーンに沿ってNPCが移動する。
- 赤、黄色信号の前で停止する。
- HD Mapに埋め込まれた法定速度を遵守して走行する。
- 明示的に速度指示があった場合にはそちらを目標速度として走行する。
- 一時停止線で一時停止後、発車する。
- 非優先道路において優先道路に他の車両がいる場合道を譲る。
- レーン座標系でみて自分の前方に車両がいる場合、速度を合わせて追従する。
- レーンチェンジの指示が出た場合、レーンチェンジ可能な地点であればレーンチェンジを行う。
- レーンチェンジが不可なエリアであった場合、レーンチェンジは行わない。
自動テスト
自動運転のテストパイプラインを運用していく上で「Simulatorにバグがあった」というケースは非常に厄介です。徹底的にバグは潰していかないといけませんし、早期発見しなくてはなりません。
Simulatorにバグがあった場合、テスト担当の方はかなり深くSimulatorのソースコードやシナリオを追って問題の根源を考えないといけません。このコストは非常に高いですし、致命的な不具合が見つかった場合過去のテスト結果が信用できなくなる可能性もありえます。
大きなコード規模(2021年5月21日現在、リポジトリ全体で36481行)を誇るROS 2パッケージ群であるシナリオテストフレームワークはなにか致命的な問題が見つかったからといって簡単に大規模なリファクタや修正をすることはできませんし、機能追加やバグフィックスによってデグレが発生しうることは容易に想像できます。
そこで、シナリオテストフレームワークの開発においてはGitHub Actionsを使用して以下のテストケースをシナリオテストフレームワーク本体のCIとして継続的に回しています。
テスト項目 | テスト内容 | トリガー |
---|---|---|
BuildTest | リポジトリに含まれる各ROS 2パッケージが独立にビルドできること各種linterチェックが通ること単体テストの実施 | 毎朝9時PRへの更新手動 |
ScenarioTest | リポジトリに含まれるパッケージ全体をビルド結合テストの実施テストの分岐網羅率チェック | 毎朝9時PRへの更新手動 |
Docker | (PRへの更新時)DockerImageのビルド(master更新時)DockerImageのビルドとDocker Hubへのpush | 毎朝9時PRへの更新master更新手動 |
Documentation | (PRへの更新時)ドキュメントのビルド(その他)ドキュメントのビルドとGitHub Pagesへのデプロイ | 毎朝9時PRへの更新master更新手動 |
Release | CHANGELOG発行とバージョン付与 | 手動 |
SpellCheck | ドキュメント、ソースコードに対してスペルチェック | PRへの更新 |
単にテストケースを回すだけでなくGitHub Pagesに常に最新版ドキュメントがデプロイされるようになっています。
これにより簡単に最新版のドキュメントにアクセスすることができます。
https://tier4.github.io/scenario_simulator_v2/tier4.github.io
今後の開発計画
今後ティアフォーのSimulation Teamでは以下のような改良をシナリオテストフレームワークに加えることを計画しています。
NPCロジックの更なる性能向上
現状のNPCロジックはある程度賢く動いてシナリオライターの作業負荷を大きく軽減してくれるものの、左折時の割り込みや信号無視、速度制限の超過といったより抽象的な指示を簡単に出せるようにするにはNPCロジックを更に賢くしていく必要があります。
現在、ICRA2020で発表されたこちらのNPCロジックを改良し、Autowareの更なるシナリオテスト効率化を推し進めていこうと考えています。
公道走行ログからのシナリオ自動起こし
公道走行中にあったヒヤリハットの状況をSimulatorの中で再現し、安全であることを検証する取り組みは非常に重要です。
以前紹介したRSSは公道において発生した危険な状況を数値化することが可能となります。
tech.tier4.jp
Simulation TeamではRSS等のメトリクスを用いて検出した危険な状況のデータを取り出し、周囲の交通状況を自動的にシナリオ化する技術開発にもトライしていこうと考えています。
最後に改めてですが、興味等ございましたら以下のページよりコンタクトいただければ大変ありがたいです。
カジュアルな面談も大歓迎です!
tier4.jp
よろしくお願いいたします。