diff --git a/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/.pages b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/.pages index 76036a5a2f3..e4c5615857f 100644 --- a/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/.pages +++ b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/.pages @@ -2,3 +2,4 @@ nav: - index.md - Tuning localization: localization-tuning - Tuning perception: perception-tuning + - Tuning planning: planning-tuning diff --git a/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/localization-tuning/index.md b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/localization-tuning/index.md index bdcb66c6656..27e3031beb2 100644 --- a/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/localization-tuning/index.md +++ b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/localization-tuning/index.md @@ -63,23 +63,25 @@ ensuring optimal performance in the specific conditions of the YTU campus. please bear in mind that since this alteration enlarges the size of the NDT input point cloud, it will require additional resources on your processor. - ```diff - /**: - ros__parameters: - input_frame: "base_link" - output_frame: "base_link" - - min_x: -60.0 - + min_x: -150.0 - - max_x: 60.0 - + max_x: 150.0 - - min_y: -60.0 - + min_y: -150.0 - - max_y: 60.0 - + max_y: 150.0 - min_z: -30.0 - max_z: 50.0 - negative: False - ``` +!!! note "[`crop_box_filter_measurement_range.param.yaml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/localization/crop_box_filter_measurement_range.param.yaml) parameter file:" + + ```diff + /**: + ros__parameters: + input_frame: "base_link" + output_frame: "base_link" + - min_x: -60.0 + + min_x: -150.0 + - max_x: 60.0 + + max_x: 150.0 + - min_y: -60.0 + + min_y: -150.0 + - max_y: 60.0 + + max_y: 150.0 + min_z: -30.0 + max_z: 50.0 + negative: False + ```
![ytu-campus-pcd-range](images/ndt-range-150m.png){ align=center } @@ -124,17 +126,19 @@ ensuring optimal performance in the specific conditions of the YTU campus. so we will reduce the voxel size to improve localization accuracy. Feel free to experiment with tuning the voxel size for your own computer setup. - ```diff - - /**: - ros__parameters: - - voxel_size_x: 3.0 - + voxel_size_x: 1.0 - - voxel_size_y: 3.0 - + voxel_size_y: 1.0 - - voxel_size_z: 3.0 - + voxel_size_z: 1.0 - ``` +!!! note "[voxel_grid_filter.param.yaml](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/localization/voxel_grid_filter.param.yaml) parameter file:" + + ```diff + + /**: + ros__parameters: + - voxel_size_x: 3.0 + + voxel_size_x: 1.0 + - voxel_size_y: 3.0 + + voxel_size_y: 1.0 + - voxel_size_z: 3.0 + + voxel_size_z: 1.0 + ```
![voxel-size-1.0](images/voxel-size-1.0.png){ align=center } diff --git a/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/perception-tuning/index.md b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/perception-tuning/index.md index db3bfd939ea..df7a4e3782e 100644 --- a/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/perception-tuning/index.md +++ b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/perception-tuning/index.md @@ -55,24 +55,28 @@ file: you can set these camera offsets to "0" as the initial value. Please be careful with the offset array size; it must be equal to your camera count. -```diff -- input_offset_ms: [61.67, 111.67, 45.0, 28.33, 78.33, 95.0] # 6 cameras -+ input_offset_ms: [0.0, 0.0, 0.0, 0.0] # 4 cameras -``` +!!! note "[roi_sync.param.yaml](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml) parameter file:" + + ```diff + - input_offset_ms: [61.67, 111.67, 45.0, 28.33, 78.33, 95.0] # 6 cameras + + input_offset_ms: [0.0, 0.0, 0.0, 0.0] # 4 cameras + ``` - If you have used different namespaces for your camera and ROI topics, you will need to add the input topics for camera_info, image_raw, - and rois messages in the [`tier4_perception_component.launch.xml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/launch/components/tier4_perception_component.launch.xml) file. + and rois messages in the `tier4_perception_component.launch.xml` launch file. -```diff -- -+ -- -+ -- -+ -``` +!!! note "[`tier4_perception_component.launch.xml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/launch/components/tier4_perception_component.launch.xml) launch file:" + + ```diff + - + + + - + + + - + + + ``` ### Tuning ground segmentation @@ -109,29 +113,35 @@ points on the high-slope roads with default configurations. However, be cautious when increasing the threshold, as it may lead to an increase in the number of false negatives. -```diff -- global_slope_max_angle_deg: 10.0 -+ global_slope_max_angle_deg: 30.0 -``` +!!! note "[`ground_segmentation.param.yaml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml) parameter file:" + + ```diff + - global_slope_max_angle_deg: 10.0 + + global_slope_max_angle_deg: 30.0 + ``` - Then we will update the split_height_distance parameter from 0.2 to 0.35 meters. This adjustment will help in reducing false positive non-ground points, especially on step-like road surfaces or in cases of misaligned multiple lidar configurations. -```diff -- split_height_distance: 0.2 -+ split_height_distance: 0.35 -``` +!!! note "[`ground_segmentation.param.yaml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml) parameter file:" + + ```diff + - split_height_distance: 0.2 + + split_height_distance: 0.35 + ``` - Now, we will change the non_ground_height_threshold value from 0.2 to 0.3 meters. This will help us in reducing false positive non-ground points, but it may also decrease the number of true positive non-ground points that are below this threshold value. -```diff -- non_ground_height_threshold: 0.2 -+ non_ground_height_threshold: 0.3 -``` +!!! note "[`ground_segmentation.param.yaml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml) parameter file:" + + ```diff + - non_ground_height_threshold: 0.2 + + non_ground_height_threshold: 0.3 + ``` - The following image illustrates the results after these fine-tunings with the ground remover package. @@ -167,10 +177,12 @@ the false positive points will disappear from the same location. - Firstly, we will change our object filter method from lanelet_filter to position_filter to detect objects that are outside the lanelet boundaries at the [`tier4_perception_component.launch.xml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/launch/components/tier4_perception_component.launch.xml). -```diff -- -+ -``` +!!! note "[`tier4_perception_component.launch.xml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/launch/components/tier4_perception_component.launch.xml) launch file:" + + ```diff + - + + + ``` - After changing the filter method for objects, the output of our perception pipeline looks like the image below: @@ -186,34 +198,40 @@ the false positive points will disappear from the same location. but we still need to update the filter range or disable the filter for unknown objects in the [`object_position_filter.param.yaml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/perception/object_recognition/detection/object_filter/object_position_filter.param.yaml) file. -```diff - upper_bound_x: 100.0 -- lower_bound_x: 0.0 -+ lower_bound_x: -100.0 -- upper_bound_y: 10.0 -+ upper_bound_y: 100.0 -- lower_bound_y: -10.0 -+ lower_bound_y: -100.0 -``` +!!! note "[`object_position_filter.param.yaml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/perception/object_recognition/detection/object_filter/object_position_filter.param.yaml) parameter file:" + + ```diff + upper_bound_x: 100.0 + - lower_bound_x: 0.0 + + lower_bound_x: -100.0 + - upper_bound_y: 10.0 + + upper_bound_y: 100.0 + - lower_bound_y: -10.0 + + lower_bound_y: -100.0 + ``` - Also, you can simply disable the filter for unknown labeled objects. -```diff -- UNKNOWN : true -+ UNKNOWN : false -``` +!!! note "[`object_position_filter.param.yaml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/perception/object_recognition/detection/object_filter/object_position_filter.param.yaml) parameter file:" + + ```diff + - UNKNOWN : true + + UNKNOWN : false + ``` - After that, we can update our clustering parameters since we can detect all objects regardless of filtering objects with the lanelet2 map. As we mentioned earlier, we want to detect small objects. Therefore, - we will decrease the minimum cluster size to 1 in the [`voxel_grid_based_euclidean_cluster.param.yaml` file](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml). + we will decrease the minimum cluster size to 1 in the `voxel_grid_based_euclidean_cluster.param.yaml` file. -```diff -- min_cluster_size: 10 -+ min_cluster_size: 1 -``` +!!! note "[`voxel_grid_based_euclidean_cluster.param.yaml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml) parameter file:" + + ```diff + - min_cluster_size: 10 + + min_cluster_size: 1 + ``` - After making these changes, our perception output is shown in the following image: diff --git a/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/planning-tuning/images/avoidance-current-lane.png b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/planning-tuning/images/avoidance-current-lane.png new file mode 100644 index 00000000000..5f2ae537599 Binary files /dev/null and b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/planning-tuning/images/avoidance-current-lane.png differ diff --git a/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/planning-tuning/images/avoidance-lateral-margin.png b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/planning-tuning/images/avoidance-lateral-margin.png new file mode 100644 index 00000000000..91e5e4a58d3 Binary files /dev/null and b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/planning-tuning/images/avoidance-lateral-margin.png differ diff --git a/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/planning-tuning/images/avoidance-opposite-lane.png b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/planning-tuning/images/avoidance-opposite-lane.png new file mode 100644 index 00000000000..2cb6e71d95b Binary files /dev/null and b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/planning-tuning/images/avoidance-opposite-lane.png differ diff --git a/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/planning-tuning/images/speed-bump.png b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/planning-tuning/images/speed-bump.png new file mode 100644 index 00000000000..1c571cefdde Binary files /dev/null and b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/planning-tuning/images/speed-bump.png differ diff --git a/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/planning-tuning/index.md b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/planning-tuning/index.md new file mode 100644 index 00000000000..38505c216b5 --- /dev/null +++ b/docs/how-to-guides/integrating-autoware/tuning-parameters-and-performance/tuning-parameters/planning-tuning/index.md @@ -0,0 +1,163 @@ +# Tuning planning + +In this section, we will update, evaluate, and fine-tune the Autoware planning modules, +with a specific emphasis on the lane driving modules within the YTU campus environment. +The Autoware planning side consists of the following main lane driving sections: +**Behavior planning and motion planning**. Our focus will be on fine-tuning these modules to +enhance our planning performance in the campus environment. + +## Introduction + +## Planning parameter tuning + +### Behavior Planning Tuning + +#### Behavior Velocity Planner + +The Behavior velocity planner is a planner that adjusts velocity based on traffic rules. +It loads modules as plugins. Please refer to the package documentation for more +information about these modules. + +To enable or disable Behavior velocity planner modules, +we will comment or uncomment the necessary plugin modules in the [`behavior_velocity_planner.param.yaml` file](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml) according to our preferences. + +- For example, in the YTU campus environment, there are many speed bumps, pedestrians, and specific areas where autonomous driving is not permitted. + We will enable the following three modules to handle these conditions: + + - Run-out module + - Speed bump module + - Out of lane module + +- To enable these modules, we need to uncomment these modules on the `behavior_velocity_planner.param.yaml` parameter file: + +!!! note "[`behavior_velocity_planner.param.yaml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml) parameter file:" + + ```diff + - # behavior_velocity_planner::RunOutModulePlugin + + behavior_velocity_planner::RunOutModulePlugin + - # behavior_velocity_planner::SpeedBumpModulePlugin + + behavior_velocity_planner::SpeedBumpModulePlugin + - # behavior_velocity_planner::NoDrivableLaneModulePlugin + + behavior_velocity_planner::NoDrivableLaneModulePlugin + ``` + +#### Speed bump module tuning + +- Our vehicle's cruising speed is set to `15 km/h`. + Therefore, + we will decrease the default speed bump velocity limits in the `speed_bump.param.yaml` + to allow for minimum and maximum speeds when going over speed bumps. + +!!! note "[`speed_bump.param.yaml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/speed_bump.param.yaml) parameter file:" + + ```diff + - min_speed: 1.39 # [m/s] = [5 kph] + + min_speed: 1.11 # [m/s] = [4 kph] + - max_speed: 2.78 # [m/s] = [10 kph] + + max_speed: 2.22 # [m/s] = [8 kph] + ``` + +- Also, we will increase the slow_start_margin parameter to provide + a greater margin for slowing down when approaching a speed bump. + Please refer to the speed bump module page for more information + about these parameters. It is essential to fine-tune these modules + based on your specific vehicle and environmental conditions. + +!!! note "[`speed_bump.param.yaml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/speed_bump.param.yaml) parameter file:" + + ```diff + - slow_start_margin: 1.0 [m] + + slow_start_margin: 2.0 [m] + ``` + +- The following image illustrates the virtual wall created by the slow start margin + of the speed bump module. If you increase or decrease the `slow_start_margin` parameter, + you will observe that the position of the virtual wall changes is relative to the speed bump. + +
+ ![speed-bump-tuning](images/speed-bump.png){ align=center } +
+ The speed bump module slow start margin is demonstrated as a virtual wall in RViz. +
+
+ +#### Avoidance + +The Avoidance module plays a pivotal role in Autoware's behavior planning scene modules, +offering rule-based avoidance capabilities. It provides the flexibility to define behavior +based on intuitive parameters like lateral jerk and avoidance distance margin, enabling +adaptable avoidance strategies tailored to your specific environment. This module operates +within lane constraints, requiring access to lane structure information to ensure compliance +with traffic rules. For example, it triggers indicator signals when the vehicle crosses a lane. +The key distinction between motion and behavior modules in the planning stack is their consideration +of traffic rules. +Please refer to the [`Avoidance Module` page](https://autowarefoundation.github.io/autoware.universe/main/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design/) for more information about the module's capabilities. + +We will modify and update certain avoidance rules and margin parameters +to handle with the specific conditions of our YTU campus environment +and the capabilities of our vehicle. + +- First, we will disable the use of opposite lanelets while avoiding, + as we do not want to utilize them in our YTU Campus environment. + The default avoidance behavior in our environment is as depicted in the image below. + +
+ ![avoidance-opposite-lane](images/avoidance-opposite-lane.png){ align=center } +
+ When the opposite_lane parameter is set to true, +the path can be shifted to the opposite lane if the ego vehicle cannot fit in the current lane. +
+
+ +- To disable the use of the opposite lanelet in the avoidance, we will modify the value in the `avoidance.param.yaml` file: + +!!! note "[`avoidance.param.yaml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml) parameter file:" + + ```diff + - use_opposite_lane: true + + use_opposite_lane: false + ``` + +Now, we expect the avoidance module not to utilize the opposite lane in our area. +If the vehicle cannot fit past an obstacle in the same lanelet, it will come to a stop, +as depicted in the image below: + +
+ ![avoidance-current-lane](images/avoidance-current-lane.png){ align=center } +
+ When the opposite_lane parameter is set to false, +the path cannot be shifted to the opposite lane, even if the ego vehicle cannot fit in the current lane. +
+
+ +Since we disabled the use of opposite lanelets for the Avoidance module, +there may be instances where we cannot avoid objects due to the shifted path +(`safety_buffer_lateral` + `avoid_margin_lateral`) not fitting within the available lanelet. +As a small vehicle, we will reduce the `avoid_margin_lateral` parameter to decrease the distance +between objects and the ego vehicle. For more information on these parameters, please refer to +the avoidance documentation. + +
+ ![avoidance-current-lane](images/avoidance-lateral-margin.png){ align=center } +
+ The Avoidance module's behavior changes when the avoid_margin value is decreased, +such that the shifted path fits within the lanelet. +
+
+ +- Also, you can choose which objects can be avoided along the path. + In the YTU campus environment, as mentioned earlier, there are many + pedestrians, and we do not want to perform avoidance maneuvers for them. + Therefore, we will disable the avoidance maneuver for pedestrians by + modifying the target value in the [`avoidance.param.yaml` file](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml). + You can disable any target object according to your preference. + +!!! note "[`avoidance.param.yaml`](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml) parameter file:" + + ```diff + ... + pedestrian: + - is_target: true + + is_target: false + ... + ```