概要
本記事では、自動運転AIチャレンジで提供されているAutoware-Miniを動かして障害物回避させてみた!という内容です。
筆者はAutoware、C++、Python、ROS2の初心者です。正確な情報は各ドキュメント等をご参照ください。
そもそもこの記事を書いた背景
Autowareの初心者なので学習のためにわかりやすいAutoware-Miniを触ってみた。
使ってみたものの元のAutowareで動作していたパラメータで障害物回避ができない、いろいろ課題がありそう…
自作ノードを作って障害物回避も考えたが、自作するには時間的に絶望的…
それでもAutoware-Miniを使って学習、シミュレーションがしてみしたい…
ということで、Autowareで動作していた障害物回避をAutoware-Miniで動作するようにしたまでのメモを思い出しつつ書いてみます。
(8/18追記)
同様の課題を打ち上げて変更してくださった方がいるので、最新版では障害物回避は行われるはずです。変更ありがとうございます!
開発環境
後日記載
環境構築
下記の通りに実施して、Autowareの環境構築を実施。
Autoware-Miniへの変更
下記の手順でファイルを変更し、実施
やっていることのメモ
①aichallenge_submit.launch.xmlをAutoware-Miniが起動するように変更。
②GUIツールRviz2の見た目を変えるため、aichallenge.launch.xmlを変更。
③behavior_path_plannerの設定値を変更。
④behavior_velocity_plannerの設定値を変更。
を実施して起動。
実行結果
Autoware➞最初の障害物を回避する。
Autoware-Mini➞最初の障害物を検知しているように見える(GUIツール上ではPathCandidateが回避ルートを示している)が、障害物を無視して回避操作を行わず衝突、また、定期的に「Stale」というログが出力されている。
解析
Autowareでは以下のようにノードの接続が設計されている。
一方、Autoware-Miniでは以下のようにノードの接続が設計されている。
behaviour_path_plannerのobstacle_avoidanceが設計上は消えているが、GUIツールの表示上は残っていそう、残っていると考えておく。
GUIツールの表示からbehaviour_path_plannerのobstacle_avoidanceでPathCandidateは生成されいる様子。
実行結果とAutoware−Miniへの変更内容から、PathCandidateが生成されるがどこかで棄却されていると想定。
仮説1:Staleのログ発生中はPathCandidateが棄却されている。
➞特定ノードが起動していないことによりログ出力がされている様子。暫定で該当しそうなノードを起動させStaleが出ないようにしてみる、変更内容は以下。
〜〜割愛〜〜
<push-ros-namespace namespace="util"/>
<group>
<push-ros-namespace namespace="error_monitor"/>
<include file="$(find-pkg-share localization_error_monitor)/launch/localization_error_monitor.launch.xml">
<arg name="input/odom" value="/localization/kinematic_state"/>
<arg name="param_file" value="$(find-pkg-share autoware_launch)/config/localization/localization_error_monitor.param.yaml"/>
</include>
</group>
<!-- pose_initializer -->
〜〜割愛〜〜
<push-ros-namespace namespace="planning"/>
<!--planning_validator-->
<group>
<push-ros-namespace namespace="planning_validator"/>
<arg name="planning_validator_param_path" default="$(find-pkg-share planning_validator)/config/planning_validator.param.yaml"/>
<arg name="input_trajectory" default="/planning/scenario_planning/trajectory"/>
<arg name="output_trajectory" default="/planning/dummy"/>
<node name="planning_validator" exec="planning_validator_node" pkg="planning_validator" output="screen">
<!-- load config a file -->
<param from="$(var planning_validator_param_path)"/>
<!-- remap topic name -->
<remap from="~/input/trajectory" to="/planning/scenario_planning/trajectory"/>
<remap from="~/input/kinematics" to="/localization/kinematic_state"/>
<remap from="~/output/trajectory" to="/planning/dummy"/>
<remap from="~/output/validation_status" to="~/validation_status"/>
</node>
</group>
<!-- mission_planning -->
〜〜割愛〜〜
➞現象変化なし。
仮説2:planning.behaviour_velocity_plannerによりplanning.behaviour_path_plannerで生成したPathが棄却されている。
➞behaviour_path_plannerについて、デバッグ用ノードを作りノード接続を変えた。
➞現象変化なし。
仮説3:planning.behaviour_velocity_planner内部でPathCandidateが棄却されている。
➞ソースコードを見てみるもよくわからない…
とりあえずデバッグログを出力させてみる
AutowareとAutoware-Miniでデバッグログを出力させる。
差分を確認、Autoware-Mini側ではRTC(Request To Cooperate)の承認待ち状態が続いている、承認がされず棄却されているのではないかと推測。また、ログからAutoware universeの実装を確認し、ソフトがCOMPILE_WITH_OLD_ARCHITECTUREで作成されているのではないかと推測。
➞RTC関連が動作しているか不明だが、動作させているところが見つからなかったので動作するようにxmlファイルを変更。
➞現象同じ、引き続きログを見る
➞RTC関連のログが出ていた(はず)
➞behavior_path_planner側の設定を元に戻す(Autoware側に倒す)
➞★障害物回避が行われるようになった!
RTC周りをもう少し見てみる、rtc_auto_manager.param.yamlの設定値をMini側を想定して変えてみる&behavior_path_plannerのパラメータをMini側にして実行
➞障害物回避が行われるようになる
変更内容
上記の環境構築、Autoware-Miniへの変更を実施後、ファイルを以下のように変更
/**:
ros__parameters:
module_list:
- "avoidance_left"
- "avoidance_right"
default_enable_list:
- "avoidance_left"
- "avoidance_right"'
〜〜割愛〜〜
<!-- behavior_planning_container -->
<include file="$(find-pkg-share rtc_auto_mode_manager)/launch/rtc_auto_mode_manager.launch.xml">
<arg name="param_path" value="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml"/>
</include>
<!-- behavior_path_planner::BehaviorPathPlannerNode -->
〜〜割愛〜〜
<!-- ad_api_adaptors -->
<include file="$(find-pkg-share ad_api_adaptors)/launch/rviz_adaptors.launch.xml" />
</group>
<group>
<push-ros-namespace namespace="autoware_api/external/rtc_controller"/>
<node_container pkg="rclcpp_components" exec="component_container_mt" name="container" namespace="" ros_args="--log-level autoware_api.external.rtc_controller.container:=warn">
<composable_node pkg="autoware_iv_external_api_adaptor" plugin="external_api::RTCController" name="node"/>
</node_container>
</group>
<!-- Rviz2 -->
〜〜割愛〜〜
まとめ
・なんとかAutoware-Miniのxmlファイル起動で障害物回避動作するようになった
・変更したところはRTC周り
・この直し方がAutoware-Miniとして正しい直し方なのか不明
・自分の環境の作り方が悪いだけなのか不明(ソフトがCOMPILE_WITH_OLD_ARCHITECTURE有効で動いている気がする、Miniの設計は無効を想定してパラメータ設定しているのでは?)