diff --git a/docs/course/avoidance.md b/docs/course/avoidance.md index 063752b..a05c78c 100644 --- a/docs/course/avoidance.md +++ b/docs/course/avoidance.md @@ -58,6 +58,105 @@ ros2 run autoware_practice_course trajectory_follower --ros-args -p kp:=5.0 -p l ## 03-02. 点群情報に基づいて経路・軌道計画し車両を追従させる -!!! warning +取得した点群を元に障害物を回避することを考えます。 +障害物を回避するには様々なものがありますが、今回はstate lattice plannerについて説明し実装します。 - 作成中 +### State Lattice Planner のアルゴリズム + +State lattice plannerとは、車両の現在の状態と目標状態の間に一連の軌道候補を生成し、それぞれの軌道を評価して最適な経路を選択するアルゴリズムです。 +以下の画像に軌道を生成するフローを示します。 + +
+ flow +
+ state lattice plannerのフロー +
+ +#### 1. 目標状態をサンプリング + +車両の現在の状態からゴールまでの経路上に複数の目標状態をサンプリングします。 +今回は予め分かっているゴールまでの軌道に垂直に等間隔に並ぶように目標状態をサンプリングします。 + +
+ target_state_sampling +
+ 目標状態を複数サンプリング +
+ +#### 2. 各目標状態に対して軌道生成 + +現在の状態から各目標状態への軌道を生成します。 +今回はベジエ曲線を用いて軌道を生成します。 + +
+ generate_trajectory +
+ 現在の状態から各目標状態への軌道を生成 +
+ +#### 3. コストマップを生成 + +取得した点群データから周囲の障害物情報を反映したコストマップを生成します。コストマップは、各セルに通行の難易度を示す値を持ちます。 +今回は点群が存在するセルのコストは100を設定し、点群が存在するセルに隣接するセルのコストは50を設定しました。 +また障害物がない場合、予め予め分かっているゴールまでの軌道に戻るようにするために、ゴールまでの軌道のウェイポイントが存在するセルのコストを-1に設定しました。 +上記のルールに基づいて各セルのコストを計算します。 + +例)ゴールまでの軌道のウェイポイントと点群が存在するセルのコストは、-1+100で99となります。 + +
+ generate_costmap +
+ コストマップの生成 +
+ +#### 4. コストマップを用いて各軌道を評価 + +各軌道のウェイポイントが存在するセルのコストの総和を軌道のコストとし、最もコストが低い軌道を選択します。 + +
+ evaluate_trajectory +
+ コストマップを用いて各軌道を評価 +
+ +今回は以下のようにtrajectory_plannerノードにstate lattice plannerを作成しました。 + +![alt text](images/3-2/nodemap.jpg) + +`src/autoware_practice_lidar_simulator/config/object_centers.csv`を修正して障害物の位置を変更します。 + +```diff +x_center,y_center +- 7.0,0.0 +- 10.0,5.0 +- 5.0,-3.0 ++ 47.0,-1.0 ++ 30.0,1.0 ++ 15.0,-1.0 +``` + +以下のコマンドを別々のターミナルで実行して画像のように障害物を適切に回避できるか確かめましょう。 + +```bash +ros2 launch autoware_practice_launch practice.launch.xml +``` + +```bash +ros2 run autoware_practice_course trajectory_loader --ros-args -p path_file:=src/autoware_practice_course/config/trajectory.csv --remap /planning/scenario_planning/trajectory:=/planning/trajectory_loader/trajectory +``` + +```bash +ros2 run autoware_practice_course trajectory_follower --ros-args -p kp:=5.0 -p lookahead_distance:=5.0 +``` + +```bash +ros2 run autoware_practice_course trajectory_planner --ros-args -p state_num:=9 -p target_interval:=1.0 +``` + +`state_num`は経路上にサンプリングする目標状態の数、`target_interval`はサンプリングする目標位置の間隔です。 +trajectory_plannerを起動する際に他のパラメータも指定できるので是非変更してみてください。ノード起動時に設定できるパラメータは`src/autoware_practice_course/src/avoidance/trajectory_planner.cpp`で確認することができます。 + +![alt text](images/3-2/rviz_image.png) + +参考: +[State Lattice Plannerの概要とPythonサンプルコード](https://myenigma.hatenablog.com/entry/2017/07/21/115833) diff --git a/docs/course/images/3-2/evaluate_trajectory.jpg b/docs/course/images/3-2/evaluate_trajectory.jpg new file mode 100644 index 0000000..1d5ccab Binary files /dev/null and b/docs/course/images/3-2/evaluate_trajectory.jpg differ diff --git a/docs/course/images/3-2/flow.jpg b/docs/course/images/3-2/flow.jpg new file mode 100644 index 0000000..6a45230 Binary files /dev/null and b/docs/course/images/3-2/flow.jpg differ diff --git a/docs/course/images/3-2/generate_costmap.jpg b/docs/course/images/3-2/generate_costmap.jpg new file mode 100644 index 0000000..436909e Binary files /dev/null and b/docs/course/images/3-2/generate_costmap.jpg differ diff --git a/docs/course/images/3-2/generate_trajectory.jpg b/docs/course/images/3-2/generate_trajectory.jpg new file mode 100644 index 0000000..b2ee876 Binary files /dev/null and b/docs/course/images/3-2/generate_trajectory.jpg differ diff --git a/docs/course/images/3-2/nodemap.jpg b/docs/course/images/3-2/nodemap.jpg new file mode 100644 index 0000000..c4237a4 Binary files /dev/null and b/docs/course/images/3-2/nodemap.jpg differ diff --git a/docs/course/images/3-2/rviz_image.png b/docs/course/images/3-2/rviz_image.png new file mode 100644 index 0000000..5afd49f Binary files /dev/null and b/docs/course/images/3-2/rviz_image.png differ diff --git a/docs/course/images/3-2/target_state_sampling.jpg b/docs/course/images/3-2/target_state_sampling.jpg new file mode 100644 index 0000000..33dabf6 Binary files /dev/null and b/docs/course/images/3-2/target_state_sampling.jpg differ