AIChallenge 2025の活動記(trajectory editor編)
AIチャレンジ2025活動記 第3弾です。今回のテーマはtrajectory editorです。
CSVファイルをいじるのって分かりづらい、、、
そんなあなたに!!これを使えば、効率よく最適な経路設定を追求できます!!
accel/brake mapに興味がある方は前回の記事をご覧ください!!
trajectory editorとは
/aichallenge/workspace/src/aichallenge_submit/simple_trajectory_generator/data/にraceline_awsim_15km.csv raceline_awsim_30km.csvというファイルがあり、こちらを直接編集して経路設定している方が多いのではないでしょうか?
# raceline_awsim_15km.csv
x,y,z,x_quat,y_quat,z_quat,w_quat,speed
89630.0674883,43130.6945594,0.0,0.0,0.0,0.8908735393706145,0.4542514026937883,4.166666666666667
89628.3148229,43133.1098699,0.0,0.0,0.0,0.8876786755288125,0.4604634285276228,4.166666666666667
89626.5962446,43135.5491846,0.0,0.0,0.0,0.8865758413551225,0.4625832655052025,4.166666666666667
89624.8893618,43137.9966586,0.0,0.0,0.0,0.8866177348157583,0.46250296465014545,4.166666666666667
89623.1819638,43140.4439264,0.0,0.0,0.0,0.886022717946053,0.4636418265034863,4.166666666666667
# 以下、省略
しかし、この方法にはいくつか面倒な点があります。
- 座標だとコースのどの位置についての値なのか分かりづらい
- 速度の単位がm/s
- 走行中にリアルタイムで経路を変更できない
trajectory editorは、rviz上で直感的に経路設定ができるツールであり、これらの面倒な点を全て解決してくれます!!

trajectory editorのドキュメントはこちらです。ぜひご覧ください。
セットアップ
1. リポジトリのクローン
まず、任意のワークスペース
(例:~/aichallenge-2025/aichallenge/workspace/src)
(例:~/aichallenge-2025/aichallenge/workspace/src/aichallenge_submit)
に上記のgithubのリポジトリをクローンします。
cd ~/aichallenge-2025/aichallenge/workspace/src
git clone https://github.com/iASL-Gifu/aichallenge-trajectory-editor.git
2. Autoware起動設定の追加
Autowareの起動設定ファイル~/aichallenge-2025/aichallenge/workspace/src/aichallenge_submit/aichallenge_submit_launch/launch/reference.launch.xmlに、以下のeditor_tool_serverノードを追加します。
<!-- Planning -->
<group>
<push-ros-namespace namespace="planning"/>
<!-- scenario_planning -->
<group>
<push-ros-namespace namespace="scenario_planning"/>
<!-- Customizable -->
<node pkg="simple_trajectory_generator" exec="simple_trajectory_generator_node" name="simple_trajectory_generator" output="screen">
<param name="csv_path" value="$(find-pkg-share simple_trajectory_generator)/data/raceline_awsim_15km.csv"/>
<param name="z" value="6.5"/>
</node>
</group>
</group>
+ <node pkg="editor_tool_server" exec="interactive_server" output="screen" name="editor_tool_server">
+ <param name="csv_file_path" value="/aichallenge/aichallenge-trajectory-editor/csv/35_07092101.csv"/>
+ <param name="publish_on_initialize" value="false"/>
+ <param name="wait_seconds" value="15.0"/>
+ <param name="grad_min_speed" value="0.0"/>
+ <param name="grad_mid_speed" value="15.0"/>
+ <param name="grad_max_speed" value="40.0"/>
+ </node>
3. Autowareのビルドと起動
ⅰ. Docker環境に入ります。
cd aichallenge-2025
./docker_build.sh dev
./docker_run.sh dev gpu
ⅱ. コンテナを起動したターミナル(コンテナ内)で以下を実行して、Autowareをビルドします。
cd /aichallenge
./build_autoware.bash
ⅲ. ビルドが完了したら、Autowareを起動します。
./run_evaluation.bash
4. rvizプラグインの追加
この記事では、rviz画面から手動で設定します。
おそらく、rvizの画面はこんな感じだと思います。trajectory editorを使えるようにするため、ここにいろんなものを追加していきます。

ⅰ. 画面上部のメニューからPanel -> Add New Panelを選択します。
表示されるウィンドウで、rviz_editor_pluginsカテゴリにあるCsvMarkerDisplayとEditorToolをそれぞれ追加します。

そうすると、こんなパネルが増えてるはずです。

ⅱ. DisplaysパネルからAdd -> By topicで、InteractiveMarkers MarkerArrayを追加して描画します。

そうすると、Displaysパネルにこんなtopicが増えてるはずなので、以下のように、チェックボックスを設定してみましょう。

これでtrajectory editorを使う準備は完了です。
それでは、実際に触ってみましょう!!
実際に使ってみる
まずは、CSVファイルをロードしてみましょう。CsvMarkerDisplayからLoad CSVで任意のCSVファイルをロードできます。

/aichallenge-2025/aichallenge/workspace/src/aichallenge-trajectory-editor/csv/raceline_awsim_15km_pp.csvを試しにロードしてみます。
そうすると、経路、経路上に矢印と15.0というkm/s単位の速度が表示されました。

経路を編集する
経路上の矢印をドラッグすることで、経路を編集することができます。
試しに矢印をいくつか動かしてみました。

EditorToolパネルからPost Trajectoryボタンを押すと編集した経路を即時反映させることができます。

編集された経路が反映されて、車の進路が変わりました!

最高速度を編集する
trajectory editorでは、目標速度設定も編集することができます。
- まず
EditorToolパネルから任意の数値を入力します。(単位km/s) -
Select Rangeボタンを押して、任意の経路上の矢印2つをクリックすることで、2つの間の全ての地点の最高速度が 1. で入力した値になります。
最高速度を30km/sに変更できました!

注意点
EditorToolパネルからPost Trajectoryボタンを押して編集した経路を即時反映させる部分に不具合が見つかりました。
/aichallenge2025/aichallenge/workspace/src/aichallenge_submit/simple_trajectory_generator/src/simple_trajectory_generator.cppに以下の修正をしてください。
for (const auto & param : parameters) {
if (param.get_name() == "csv_path") {
if (param.get_type() == rclcpp::ParameterType::PARAMETER_STRING) {
std::string new_csv_path = param.as_string();
// new_csv_pathがFileSystemのパスであることを確認
if (new_csv_path.empty()) {
RCLCPP_ERROR(get_logger(), "New csv_path parameter is empty. Keeping old trajectory.");
result.successful = false;
result.reason = "New csv_path parameter is empty.";
continue;
}
- if (new_csv_path != current_csv_path_) {
RCLCPP_INFO(get_logger(), "csv_path parameter changed from '%s' to '%s'",
current_csv_path_.c_str(), new_csv_path.c_str());
// 新しいCSVファイルの読み込みを試みる
if (loadCSVTrajectory(new_csv_path)) {
current_csv_path_ = new_csv_path;
RCLCPP_INFO(get_logger(), "Successfully loaded new trajectory from CSV: %s with %zu points",
current_csv_path_.c_str(), csv_trajectory_.points.size());
} else {
RCLCPP_ERROR(get_logger(), "Failed to load new CSV file: %s. Keeping old trajectory.", new_csv_path.c_str());
result.successful = false;
result.reason = "Failed to load new CSV file.";
}
- }
} else {
RCLCPP_WARN(get_logger(), "Parameter 'csv_path' received with wrong type. Expected string.");
result.successful = false;
result.reason = "Invalid type for csv_path parameter.";
}
} else if (param.get_name() == "z") {
if (param.get_type() == rclcpp::ParameterType::PARAMETER_DOUBLE || param.get_type() == rclcpp::ParameterType::PARAMETER_INTEGER) {
z_ = static_cast<float>(param.as_double());
RCLCPP_INFO(get_logger(), "z parameter changed to %f", z_);
// Z値が変更された場合、既存の軌道点のZ値を更新することも可能ですが、
// 今回はCSV読み込み時に適用されるため、再読み込みは不要です。
} else {
RCLCPP_WARN(get_logger(), "Parameter 'z' received with wrong type. Expected float/double.");
result.successful = false;
result.reason = "Invalid type for z parameter.";
}
}
}
修正後のbuildを忘れずに!!
cd aichallenge-2025
./docker_build.sh dev
./docker_run.sh dev gpu
cd /aichallenge
./build_autoware.bash
今後
ここまでの記事の内容がAIChallenge 2025の基盤になると思います。
ここから更に改善を施し、タイム更新を目指します!!
次回の記事もお楽しみに!!
Discussion