diff --git a/.github/dependabot.yaml b/.github/dependabot.yaml index 3f3bf243f6..0264c03535 100644 --- a/.github/dependabot.yaml +++ b/.github/dependabot.yaml @@ -6,5 +6,5 @@ updates: interval: daily open-pull-requests-limit: 1 labels: - - bot - - github-actions + - tag:bot + - type:github-actions diff --git a/.github/stale.yml b/.github/stale.yml index 84928d1b81..bc99e4383c 100644 --- a/.github/stale.yml +++ b/.github/stale.yml @@ -4,7 +4,7 @@ daysUntilClose: false # Label to use when marking as stale -staleLabel: stale +staleLabel: status:stale # Comment to post when marking as stale markComment: > diff --git a/.github/workflows/beta-to-tier4-main-sync.yaml b/.github/workflows/beta-to-tier4-main-sync.yaml new file mode 100644 index 0000000000..79bdb6f0bd --- /dev/null +++ b/.github/workflows/beta-to-tier4-main-sync.yaml @@ -0,0 +1,34 @@ +name: beta-to-tier4-main-sync + +on: + workflow_dispatch: + inputs: + source_branch: + description: Source branch + required: true + type: string + +jobs: + sync-beta-branch: + runs-on: ubuntu-latest + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v1 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run sync-branches + uses: autowarefoundation/autoware-github-actions/sync-branches@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + base-branch: tier4/main + sync-pr-branch: beta-to-tier4-main-sync + sync-target-repository: https://github.com/tier4/autoware_launch.git + sync-target-branch: ${{ inputs.source_branch }} + pr-title: "chore: sync beta branch ${{ inputs.source_branch }} with tier4/main" + pr-labels: | + bot + sync-beta-branch + auto-merge-method: merge diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 6459a98044..33096b753d 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -24,6 +24,14 @@ jobs: - name: Check out repository uses: actions/checkout@v3 + - name: Free disk space (Ubuntu) + uses: jlumbroso/free-disk-space@v1.2.0 + with: + tool-cache: false + dotnet: false + swap-storage: false + large-packages: false + - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 diff --git a/.github/workflows/cancel-previous-workflows.yaml b/.github/workflows/cancel-previous-workflows.yaml index f9c29b81b6..1da4d24966 100644 --- a/.github/workflows/cancel-previous-workflows.yaml +++ b/.github/workflows/cancel-previous-workflows.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Cancel previous runs - uses: styfle/cancel-workflow-action@0.11.0 + uses: styfle/cancel-workflow-action@0.12.0 with: workflow_id: all all_but_latest: true diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml index 95ebb8725f..b426d0cba6 100644 --- a/.github/workflows/github-release.yaml +++ b/.github/workflows/github-release.yaml @@ -30,7 +30,7 @@ jobs: echo "tag-name=${REF_NAME#beta/}" >> $GITHUB_OUTPUT - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: fetch-depth: 0 ref: ${{ steps.set-tag-name.outputs.ref-name }} diff --git a/.github/workflows/pre-commit-optional.yaml b/.github/workflows/pre-commit-optional.yaml index e754ecab24..38738196a0 100644 --- a/.github/workflows/pre-commit-optional.yaml +++ b/.github/workflows/pre-commit-optional.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: fetch-depth: 0 diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml index b231dbda87..33c00ee106 100644 --- a/.github/workflows/pre-commit.yaml +++ b/.github/workflows/pre-commit.yaml @@ -16,7 +16,7 @@ jobs: private_key: ${{ secrets.PRIVATE_KEY }} - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: ref: ${{ github.event.pull_request.head.ref }} diff --git a/.github/workflows/spell-check-differential.yaml b/.github/workflows/spell-check-differential.yaml index eb18ccdba3..1fbf2ff469 100644 --- a/.github/workflows/spell-check-differential.yaml +++ b/.github/workflows/spell-check-differential.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Run spell-check uses: autowarefoundation/autoware-github-actions/spell-check@v1 diff --git a/.github/workflows/sync-awf-upstream.yaml b/.github/workflows/sync-awf-upstream.yaml index f0e6272286..91012439fb 100644 --- a/.github/workflows/sync-awf-upstream.yaml +++ b/.github/workflows/sync-awf-upstream.yaml @@ -1,9 +1,12 @@ name: sync-awf-upstream on: - schedule: - - cron: 0 1 * * 1-5 workflow_dispatch: + inputs: + target_branch: + description: Target branch + required: true + type: string jobs: sync-awf-upstream: @@ -29,12 +32,17 @@ jobs: const holiday_jp = require(`${process.env.GITHUB_WORKSPACE}/node_modules/@holiday-jp/holiday_jp`) core.setOutput('holiday', holiday_jp.isHoliday(new Date())); + - name: Print warning for invalid branch name + if: ${{ inputs.target_branch == 'tier4/main' }} + run: | + echo This action cannot be performed on 'tier4/main' branch + - name: Run sync-branches uses: autowarefoundation/autoware-github-actions/sync-branches@v1 - if: ${{ steps.is-holiday.outputs.holiday != 'true' || github.event_name == 'workflow_dispatch' }} + if: ${{ inputs.target_branch != 'tier4/main' }} with: token: ${{ steps.generate-token.outputs.token }} - base-branch: tier4/main + base-branch: ${{ inputs.target_branch }} sync-pr-branch: sync-awf-upstream sync-target-repository: https://github.com/autowarefoundation/autoware_launch.git sync-target-branch: main diff --git a/.github/workflows/sync-files.yaml b/.github/workflows/sync-files.yaml index b9dc5907a5..5025e6c8bd 100644 --- a/.github/workflows/sync-files.yaml +++ b/.github/workflows/sync-files.yaml @@ -28,6 +28,6 @@ jobs: with: token: ${{ steps.generate-token.outputs.token }} pr-labels: | - bot - sync-files + tag:bot + tag:sync-files auto-merge-method: squash diff --git a/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml b/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml index 09db0feb34..1a870aff7a 100644 --- a/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml +++ b/autoware_launch/config/control/autonomous_emergency_braking/autonomous_emergency_braking.param.yaml @@ -1,5 +1,6 @@ /**: ros__parameters: + publish_debug_pointcloud: false use_predicted_trajectory: true use_imu_path: true voxel_grid_x: 0.05 @@ -11,7 +12,9 @@ t_response: 1.0 a_ego_min: -3.0 a_obj_min: -1.0 - prediction_time_horizon: 1.5 - prediction_time_interval: 0.1 + imu_prediction_time_horizon: 1.5 + imu_prediction_time_interval: 0.1 + mpc_prediction_time_horizon: 1.5 + mpc_prediction_time_interval: 0.1 collision_keeping_sec: 0.0 aeb_hz: 10.0 diff --git a/autoware_launch/config/control/control_validator/control_validator.param.yaml b/autoware_launch/config/control/control_validator/control_validator.param.yaml index 9ce677b2c2..c51cbafba2 100644 --- a/autoware_launch/config/control/control_validator/control_validator.param.yaml +++ b/autoware_launch/config/control/control_validator/control_validator.param.yaml @@ -1,14 +1,14 @@ /**: ros__parameters: - publish_diag: true # if true, diagnostic msg is published + publish_diag: false # if true, diagnostic msg is published # If the number of consecutive invalid predicted_path exceeds this threshold, the Diag will be set to ERROR. # (For example, threshold = 1 means, even if the predicted_path is invalid, Diag will not be ERROR if # the next predicted_path is valid.) diag_error_count_threshold: 0 - display_on_terminal: true # show error msg on terminal + display_on_terminal: false # show error msg on terminal thresholds: max_distance_deviation: 1.0 diff --git a/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml b/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml index d381c47b47..08993907f0 100644 --- a/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml +++ b/autoware_launch/config/control/lane_departure_checker/lane_departure_checker.param.yaml @@ -1,5 +1,10 @@ /**: ros__parameters: + # Enable feature + will_out_of_lane_checker: false + out_of_lane_checker: false + boundary_departure_checker: true + # Node update_rate: 10.0 visualize_lanelet: false @@ -7,7 +12,7 @@ include_left_lanes: true include_opposite_lanes: true include_conflicting_lanes: true - road_border_departure_checker: false + boundary_types_to_detect: [curbstone] # Core footprint_margin_scale: 1.0 diff --git a/autoware_launch/config/control/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml b/autoware_launch/config/control/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml index a86443f5ca..a4e8ab2c83 100644 --- a/autoware_launch/config/control/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml +++ b/autoware_launch/config/control/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml @@ -2,6 +2,10 @@ ros__parameters: transition_timeout: 10.0 frequency_hz: 10.0 + + # set true if you want to engage the autonomous driving mode while the vehicle is driving. If set to false, it will deny Engage in any situation where the vehicle speed is not zero. Note that if you use this feature without adjusting the parameters, it may cause issues like sudden deceleration. Before using, please ensure the engage condition and the vehicle_cmd_gate transition filter are appropriately adjusted. + enable_engage_on_driving: false + check_engage_condition: false # set false if you do not want to care about the engage condition. nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index diff --git a/autoware_launch/config/control/predicted_path_checker/predicted_path_checker.param.yaml b/autoware_launch/config/control/predicted_path_checker/predicted_path_checker.param.yaml new file mode 100644 index 0000000000..780d86b5e9 --- /dev/null +++ b/autoware_launch/config/control/predicted_path_checker/predicted_path_checker.param.yaml @@ -0,0 +1,22 @@ +/**: + ros__parameters: + # Node + update_rate: 10.0 + delay_time: 0.17 + max_deceleration: 1.5 + resample_interval: 0.5 + stop_margin: 0.5 # [m] + ego_nearest_dist_threshold: 3.0 # [m] + ego_nearest_yaw_threshold: 1.046 # [rad] = 60 [deg] + min_trajectory_check_length: 1.5 # [m] + trajectory_check_time: 3.0 + distinct_point_distance_threshold: 0.3 + distinct_point_yaw_threshold: 5.0 # [deg] + filtering_distance_threshold: 1.5 # [m] + use_object_prediction: true + + collision_checker_params: + width_margin: 0.2 + chattering_threshold: 0.2 + z_axis_filtering_buffer: 0.3 + enable_z_axis_obstacle_filtering: false diff --git a/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml b/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml index 63c73e9fb6..8d774a3fa0 100644 --- a/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml +++ b/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml @@ -32,7 +32,9 @@ max_d_effort: 0.0 min_d_effort: 0.0 lpf_vel_error_gain: 0.9 + enable_integration_at_low_speed: false current_vel_threshold_pid_integration: 0.5 + time_threshold_before_pid_integration: 2.0 enable_brake_keeping_before_stop: false brake_keeping_acc: -0.2 diff --git a/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml b/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml index 3d4d41a50f..03ae9a3e99 100644 --- a/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml +++ b/autoware_launch/config/control/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml @@ -6,6 +6,8 @@ check_external_emergency_heartbeat: false use_start_request: true enable_cmd_limit_filter: true + filter_activated_count_threshold: 5 + filter_activated_velocity_threshold: 1.0 external_emergency_stop_heartbeat_timeout: 0.0 stop_hold_acceleration: -1.5 emergency_acceleration: -2.4 @@ -15,6 +17,8 @@ nominal: vel_lim: 25.0 reference_speed_points: [20.0, 30.0] + steer_lim: [1.0, 0.8] + steer_rate_lim: [1.0, 0.8] lon_acc_lim: [5.0, 4.0] lon_jerk_lim: [5.0, 4.0] lat_acc_lim: [5.0, 4.0] @@ -23,6 +27,8 @@ on_transition: vel_lim: 50.0 reference_speed_points: [20.0, 30.0] + steer_lim: [1.0, 0.8] + steer_rate_lim: [1.0, 0.8] lon_acc_lim: [1.0, 0.9] lon_jerk_lim: [0.5, 0.4] lat_acc_lim: [2.0, 1.8] diff --git a/autoware_launch/config/localization/ekf_localizer.param.yaml b/autoware_launch/config/localization/ekf_localizer.param.yaml index 6b349c7dab..2a3489ee97 100644 --- a/autoware_launch/config/localization/ekf_localizer.param.yaml +++ b/autoware_launch/config/localization/ekf_localizer.param.yaml @@ -21,3 +21,12 @@ proc_stddev_yaw_c: 0.005 proc_stddev_vx_c: 10.0 proc_stddev_wz_c: 5.0 + + # for diagnostics + pose_no_update_count_threshold_warn: 50 + pose_no_update_count_threshold_error: 100 + twist_no_update_count_threshold_warn: 50 + twist_no_update_count_threshold_error: 100 + + # for velocity measurement limitation (Set 0.0 if you want to ignore) + threshold_observable_velocity_mps: 0.0 # [m/s] diff --git a/autoware_launch/config/localization/localization_error_monitor.param.yaml b/autoware_launch/config/localization/localization_error_monitor.param.yaml index 026daf0532..def5c80164 100644 --- a/autoware_launch/config/localization/localization_error_monitor.param.yaml +++ b/autoware_launch/config/localization/localization_error_monitor.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: scale: 3.0 - error_ellipse_size: 1.0 - warn_ellipse_size: 0.8 + error_ellipse_size: 1.5 + warn_ellipse_size: 1.2 error_ellipse_size_lateral_direction: 0.3 - warn_ellipse_size_lateral_direction: 0.2 + warn_ellipse_size_lateral_direction: 0.25 diff --git a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml index 4c29059581..1a6c26cd9c 100644 --- a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml +++ b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml @@ -6,6 +6,12 @@ # Vehicle reference frame base_frame: "base_link" + # NDT reference frame + ndt_base_frame: "ndt_base_link" + + # map frame + map_frame: "map" + # Subscriber queue size input_sensor_points_queue_size: 1 @@ -35,7 +41,15 @@ converged_param_nearest_voxel_transformation_likelihood: 2.3 # The number of particles to estimate initial pose - initial_estimate_particles_num: 100 + initial_estimate_particles_num: 200 + + # The number of initial random trials in the TPE (Tree-Structured Parzen Estimator). + # This value should be equal to or less than 'initial_estimate_particles_num' and more than 0. + # If it is equal to 'initial_estimate_particles_num', the search will be the same as a full random search. + n_startup_trials: 20 + + # Tolerance of timestamp difference between current time and sensor pointcloud. [sec] + lidar_topic_timeout_sec: 1.0 # Tolerance of timestamp difference between initial_pose and sensor pointcloud. [sec] initial_pose_timeout_sec: 1.0 @@ -43,15 +57,11 @@ # Tolerance of distance difference between two initial poses used for linear interpolation. [m] initial_pose_distance_tolerance_m: 10.0 - # neighborhood search method - # 0=KDTREE, 1=DIRECT26, 2=DIRECT7, 3=DIRECT1 - neighborhood_search_method: 0 - # Number of threads used for parallel computing num_threads: 4 # The covariance of output pose - # Do note that this covariance matrix is empirically derived + # Note that this covariance matrix is empirically derived output_pose_covariance: [ 0.0225, 0.0, 0.0, 0.0, 0.0, 0.0, @@ -62,6 +72,14 @@ 0.0, 0.0, 0.0, 0.0, 0.0, 0.000625, ] + # 2D Real-time covariance estimation with multiple searches (output_pose_covariance is the minimum value) + use_covariance_estimation: false + + # Offset arrangement in covariance estimation [m] + # initial_pose_offset_model_x & initial_pose_offset_model_y must have the same number of elements. + initial_pose_offset_model_x: [0.0, 0.0, 0.5, -0.5, 1.0, -1.0] + initial_pose_offset_model_y: [0.5, -0.5, 0.0, 0.0, 0.0, 0.0] + # Regularization switch regularization_enabled: false @@ -77,8 +95,12 @@ # Radius of input LiDAR range (used for diagnostics of dynamic map loading) lidar_radius: 100.0 + # cspell: ignore degrounded # A flag for using scan matching score based on de-grounded LiDAR scan estimate_scores_for_degrounded_scan: false # If lidar_point.z - base_link.z <= this threshold , the point will be removed z_margin_for_ground_removal: 0.8 + + # The execution time which means probably NDT cannot matches scans properly. [ms] + critical_upper_bound_exe_time_ms: 100 diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml deleted file mode 100644 index 3dd303464a..0000000000 --- a/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml +++ /dev/null @@ -1,20 +0,0 @@ -/**: - ros__parameters: - - # distance threshold for compare compare - distance_threshold: 0.5 - - # publish voxelized map pointcloud for debug - publish_debug_pcd: False - - # use dynamic map loading - use_dynamic_map_loading: True - - # time interval to check dynamic map loading - timer_interval_ms: 100 - - # distance threshold for dynamic map update - map_update_distance_threshold: 10.0 - - # radius map for dynamic map loading - map_loader_radius: 150.0 diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml deleted file mode 100644 index 1962fba1f3..0000000000 --- a/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml +++ /dev/null @@ -1,8 +0,0 @@ -/**: - ros__parameters: - input_frame: base_link - output_frame: base_link - voxel_size_x: 0.3 - voxel_size_y: 0.3 - voxel_size_z: 100.0 - voxel_points_threshold: 3 diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/radar_object_clustering.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/radar_object_clustering.param.yaml new file mode 100644 index 0000000000..2abbf14622 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/clustering/radar_object_clustering.param.yaml @@ -0,0 +1,15 @@ +/**: + ros__parameters: + # clustering parameter + angle_threshold: 0.174 # [rad] (10 deg) + distance_threshold: 10.0 # [m] + velocity_threshold: 4.0 # [m/s] + + # output object settings + # set false if you want to use the object information from radar + is_fixed_label: true + fixed_label: "CAR" + is_fixed_size: true + size_x: 4.0 # [m] + size_y: 1.5 # [m] + size_z: 1.5 # [m] diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml deleted file mode 100644 index 3ff32bfbb7..0000000000 --- a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml +++ /dev/null @@ -1,7 +0,0 @@ -/**: - ros__parameters: - input_frame: base_link - output_frame: base_link - voxel_size_x: 0.15 - voxel_size_y: 0.15 - voxel_size_z: 0.15 diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml index 2f3de2b789..26b027f007 100644 --- a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml +++ b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml @@ -7,9 +7,11 @@ max_cluster_size: 3000 use_height: false input_frame: "base_link" - max_x: 70.0 - min_x: -70.0 - max_y: 70.0 - min_y: -70.0 - max_z: 4.5 - min_z: -4.5 + + # low height crop box filter param + max_x: 200.0 + min_x: -200.0 + max_y: 200.0 + min_y: -200.0 + max_z: 2.0 + min_z: -10.0 diff --git a/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml new file mode 100644 index 0000000000..b98f8adfb5 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/detected_object_validation/obstacle_pointcloud_based_validator.param.yaml @@ -0,0 +1,15 @@ +/**: + ros__parameters: + min_points_num: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [10, 10, 10, 10, 10,10, 10, 10] + + max_points_num: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [10, 10, 10, 10, 10,10, 10, 10] + + min_points_and_distance_ratio: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [800.0, 880.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0] + + using_2d_validator: true diff --git a/autoware_launch/config/perception/object_recognition/detection/detection_by_tracker/detection_by_tracker.param.yaml b/autoware_launch/config/perception/object_recognition/detection/detection_by_tracker/detection_by_tracker.param.yaml new file mode 100644 index 0000000000..6957040506 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/detection_by_tracker/detection_by_tracker.param.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + tracker_ignore_label: + UNKNOWN : true + CAR : false + TRUCK : false + BUS : false + TRAILER : false + MOTORCYCLE : false + BICYCLE : false + PEDESTRIAN : false diff --git a/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml index a626bc0269..6b3ccc14a6 100644 --- a/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml +++ b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml @@ -3,3 +3,9 @@ input_offset_ms: [50.0, 66.67, 83.33, 0.0, 16.67, 33.33] timeout_ms: 70.0 match_threshold_ms: 50.0 + filter_scope_min_x: -100.0 + filter_scope_min_y: -100.0 + filter_scope_min_z: -100.0 + filter_scope_max_x: 100.0 + filter_scope_max_y: 100.0 + filter_scope_max_z: 100.0 diff --git a/autoware_launch/config/perception/object_recognition/detection/object_filter/radar_lanelet_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/object_filter/radar_lanelet_filter.param.yaml new file mode 100644 index 0000000000..62051e1c5e --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/object_filter/radar_lanelet_filter.param.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + filter_target_label: + UNKNOWN : true + CAR : true + TRUCK : true + BUS : true + TRAILER : true + MOTORCYCLE : true + BICYCLE : true + PEDESTRIAN : true diff --git a/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml index 0423217582..62b3074c15 100644 --- a/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml +++ b/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml @@ -1,7 +1,5 @@ /**: ros__parameters: - # use downsample filter before compare map - use_down_sample_filter: False # voxel size for downsample filter down_sample_voxel_size: 0.1 diff --git a/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml b/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml index 31fae9c811..69ff96a263 100644 --- a/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml +++ b/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml @@ -2,6 +2,7 @@ ros__parameters: enable_delay_compensation: true prediction_time_horizon: 10.0 #[s] + lateral_control_time_horizon: 5.0 #[s] prediction_sampling_delta_time: 0.5 #[s] min_velocity_for_map_based_prediction: 1.39 #[m/s] min_crosswalk_user_velocity: 1.39 #[m/s] @@ -28,5 +29,6 @@ diff_dist_threshold_to_left_bound: 0.29 #[m] diff_dist_threshold_to_right_bound: -0.29 #[m] num_continuous_state_transition: 3 + consider_only_routable_neighbours: false reference_path_resolution: 0.5 #[m] diff --git a/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/multi_object_tracker_node.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/multi_object_tracker_node.param.yaml new file mode 100644 index 0000000000..f58de8e615 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/multi_object_tracker_node.param.yaml @@ -0,0 +1,23 @@ +/**: + ros__parameters: + # default tracker models for each class + car_tracker: "multi_vehicle_tracker" + truck_tracker: "multi_vehicle_tracker" + bus_tracker: "multi_vehicle_tracker" + trailer_tracker: "multi_vehicle_tracker" + pedestrian_tracker: "pedestrian_and_bicycle_tracker" + bicycle_tracker: "pedestrian_and_bicycle_tracker" + motorcycle_tracker: "pedestrian_and_bicycle_tracker" + + # default tracker node parameters + publish_rate: 10.0 + world_frame_id: map + enable_delay_compensation: true + pass_through_unknown_objects: false + publish_untracked_objects: false + + # debug parameters + publish_processing_time: false + publish_tentative_objects: false + diagnostic_warn_delay: 0.5 # [sec] + diagnostic_error_delay: 1.0 # [sec] diff --git a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/data_association_matrix.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/data_association_matrix.param.yaml index 104d790d18..69628414e6 100644 --- a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/data_association_matrix.param.yaml +++ b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/data_association_matrix.param.yaml @@ -14,10 +14,10 @@ max_dist_matrix: #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN [4.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN - 4.0, 4.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR - 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK - 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS - 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRAILER + 4.0, 8.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #CAR + 4.0, 6.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #TRUCK + 4.0, 6.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #BUS + 4.0, 6.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #TRAILER 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #MOTORBIKE 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #BICYCLE 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN diff --git a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/default_tracker.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/default_tracker.param.yaml index 757125202d..6c26034860 100644 --- a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/default_tracker.param.yaml +++ b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/default_tracker.param.yaml @@ -1,9 +1,9 @@ /**: ros__parameters: - car_tracker: "linear_motion_tracker" - truck_tracker: "linear_motion_tracker" - bus_tracker: "linear_motion_tracker" - trailer_tracker: "linear_motion_tracker" - pedestrian_tracker: "linear_motion_tracker" - bicycle_tracker: "linear_motion_tracker" - motorcycle_tracker: "linear_motion_tracker" + car_tracker: "constant_turn_rate_motion_tracker" + truck_tracker: "constant_turn_rate_motion_tracker" + bus_tracker: "constant_turn_rate_motion_tracker" + trailer_tracker: "constant_turn_rate_motion_tracker" + pedestrian_tracker: "constant_turn_rate_motion_tracker" + bicycle_tracker: "constant_turn_rate_motion_tracker" + motorcycle_tracker: "constant_turn_rate_motion_tracker" diff --git a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/radar_object_tracker.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/radar_object_tracker.param.yaml new file mode 100644 index 0000000000..d2c0841cf3 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/radar_object_tracker.param.yaml @@ -0,0 +1,26 @@ +# general parameters for radar_object_tracker node +/**: + ros__parameters: + # basic settings + world_frame_id: "map" + tracker_lifetime: 1.0 # [sec] + measurement_count_threshold: 3 # object will be published if it is tracked more than this threshold + + # delay compensate parameters + publish_rate: 10.0 + enable_delay_compensation: true + + # logging + enable_logging: false + logging_file_path: "/tmp/association_log.json" + + # filtering + ## 1. distance based filtering: remove closer objects than this threshold + use_distance_based_noise_filtering: true + minimum_range_threshold: 60.0 # [m] + + ## 2. lanelet map based filtering + use_map_based_noise_filtering: true + max_distance_from_lane: 5.0 # [m] + max_angle_diff_from_lane: 0.785398 # [rad] (45 deg) + max_lateral_velocity: 7.0 # [m/s] diff --git a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/constant_turn_rate_motion_tracker.yaml b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/constant_turn_rate_motion_tracker.yaml new file mode 100644 index 0000000000..f80f881cab --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/constant_turn_rate_motion_tracker.yaml @@ -0,0 +1,36 @@ +default: + # This file defines the parameters for the linear motion tracker. + # All this parameter coordinate is assumed to be in the vehicle coordinate system. + # So, the x axis is pointing to the front of the vehicle, y axis is pointing to the left of the vehicle. + ekf_params: + # random walk noise is used to model the acceleration noise + process_noise_std: # [m/s^2] + x: 0.5 + y: 0.5 + yaw: 0.1 + vx: 1.0 # assume 1m/s velocity noise + wz: 0.4 + measurement_noise_std: + x: 4.0 # [m] + y: 4.0 # [m] + # y: 0.02 # rad/m if use_polar_coordinate_in_measurement_noise is true + yaw: 0.2 # [rad] + vx: 10 # [m/s] + initial_covariance_std: + x: 3.0 # [m] + y: 6.0 # [m] + yaw: 10.0 # [rad] + vx: 100.0 # [m/s] + wz: 10.0 # [rad/s] + # input flag + trust_yaw_input: false # set true if yaw input of sensor is reliable + trust_twist_input: false # set true if twist input of sensor is reliable + use_polar_coordinate_in_measurement_noise: false # set true if you want to define the measurement noise in polar coordinate + assume_zero_yaw_rate: false # set true if you want to assume zero yaw rate + # output limitation + limit: + max_speed: 80.0 # [m/s] + # low pass filter is used to smooth the yaw and shape estimation + low_pass_filter: + time_constant: 1.0 # [s] + sampling_time: 0.1 # [s] diff --git a/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/linear_motion_tracker.yaml b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/linear_motion_tracker.yaml new file mode 100644 index 0000000000..5e813558a2 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/tracking/radar_object_tracker/tracking/linear_motion_tracker.yaml @@ -0,0 +1,38 @@ +default: + # This file defines the parameters for the linear motion tracker. + # All this parameter coordinate is assumed to be in the vehicle coordinate system. + # So, the x axis is pointing to the front of the vehicle, y axis is pointing to the left of the vehicle. + ekf_params: + # random walk noise is used to model the acceleration noise + process_noise_std: # [m/s^2] + ax: 0.98 # assume 0.1G acceleration noise + ay: 0.98 + vx: 1.0 # assume 1m/s velocity noise + vy: 1.0 + x: 1.0 # assume 1m position noise + y: 1.0 + measurement_noise_std: + x: 0.6 # [m] + # y: 4.0 # [m] + y: 0.01 # rad/m if use_polar_coordinate_in_measurement_noise is true + vx: 10 # [m/s] + vy: 100 # [m/s] + initial_covariance_std: + x: 3.0 # [m] + y: 6.0 # [m] + vx: 1000.0 # [m/s] + vy: 1000.0 # [m/s] + ax: 1000.0 # [m/s^2] + ay: 1000.0 # [m/s^2] + estimate_acc: false # set true if you want to estimate the acceleration + # input flag + trust_yaw_input: false # set true if yaw input of sensor is reliable + trust_twist_input: false # set true if twist input of sensor is reliable + use_polar_coordinate_in_measurement_noise: true # set true if you want to define the measurement noise in polar coordinate + # output limitation + limit: + max_speed: 80.0 # [m/s] + # low pass filter is used to smooth the yaw and shape estimation + low_pass_filter: + time_constant: 1.0 # [s] + sampling_time: 0.1 # [s] diff --git a/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/data_association_matrix.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/data_association_matrix.param.yaml new file mode 100644 index 0000000000..702809b3ce --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/data_association_matrix.param.yaml @@ -0,0 +1,168 @@ +/**: + ros__parameters: + lidar-lidar: + can_assign_matrix: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN + [0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN + 0, 1, 1, 1, 1, 0, 0, 0, #CAR + 0, 1, 1, 1, 1, 0, 0, 0, #TRUCK + 0, 1, 1, 1, 1, 0, 0, 0, #BUS + 0, 1, 1, 1, 1, 0, 0, 0, #TRAILER + 0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE + 0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE + 0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN + + max_dist_matrix: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [4.0, 4.0, 5.0, 5.0, 5.0, 2.0, 2.0, 2.0, #UNKNOWN + 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR + 5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK + 5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS + 5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRAILER + 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #MOTORBIKE + 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #BICYCLE + 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN + + max_rad_matrix: # If value is greater than pi, it will be ignored. + #UNKNOWN, CAR, TRUCK, BUS, TRAILER MOTORBIKE, BICYCLE, PEDESTRIAN + [3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #CAR + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRUCK + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #BUS + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRAILER + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN + + max_velocity_diff_matrix: # Ignored when value is larger than 100.0 + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #UNKNOWN + 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #CAR + 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRUCK + 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #BUS + 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRAILER + 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #MOTORBIKE + 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #BICYCLE + 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0] #PEDESTRIAN + + min_iou_matrix: # If value is negative, it will be ignored. + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN + 0.1, 0.3, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR + 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK + 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS + 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] #PEDESTRIAN + + lidar-radar: + can_assign_matrix: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN + [0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN + 0, 1, 1, 1, 1, 0, 0, 0, #CAR + 0, 1, 1, 1, 1, 0, 0, 0, #TRUCK + 0, 1, 1, 1, 1, 0, 0, 0, #BUS + 0, 1, 1, 1, 1, 0, 0, 0, #TRAILER + 0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE + 0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE + 0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN + + max_dist_matrix: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [4.0, 4.0, 5.0, 5.0, 5.0, 3.5, 3.5, 3.5, #UNKNOWN + 4.0, 5.5, 6.0, 6.0, 6.0, 1.0, 1.0, 1.0, #CAR + 5.0, 6.0, 6.5, 6.5, 6.5, 1.0, 1.0, 1.0, #TRUCK + 5.0, 6.0, 6.5, 6.5, 6.5, 1.0, 1.0, 1.0, #BUS + 5.0, 6.0, 6.5, 6.5, 6.5, 1.0, 1.0, 1.0, #TRAILER + 3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #MOTORBIKE + 3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #BICYCLE + 3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.5] #PEDESTRIAN + + max_rad_matrix: # If value is greater than pi, it will be ignored. + #UNKNOWN, CAR, TRUCK, BUS, TRAILER MOTORBIKE, BICYCLE, PEDESTRIAN + [3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #CAR + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRUCK + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #BUS + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRAILER + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN + + max_velocity_diff_matrix: # Ignored when value is larger than 100.0 + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #UNKNOWN + 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #CAR + 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRUCK + 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #BUS + 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRAILER + 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #MOTORBIKE + 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #BICYCLE + 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0] #PEDESTRIAN + + min_iou_matrix: # set all value to 0.0 to disable this constraint + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #UNKNOWN + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #CAR + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #TRUCK + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #BUS + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #TRAILER + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #MOTORBIKE + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #BICYCLE + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] #PEDESTRIAN + + radar-radar: + can_assign_matrix: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN + [0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN + 0, 1, 1, 1, 1, 0, 0, 0, #CAR + 0, 1, 1, 1, 1, 0, 0, 0, #TRUCK + 0, 1, 1, 1, 1, 0, 0, 0, #BUS + 0, 1, 1, 1, 1, 0, 0, 0, #TRAILER + 0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE + 0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE + 0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN + + max_dist_matrix: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [4.0, 4.0, 5.0, 5.0, 5.0, 3.5, 3.5, 3.5, #UNKNOWN + 4.0, 7.0, 7.5, 7.5, 7.5, 1.0, 1.0, 1.0, #CAR + 5.0, 7.5, 7.5, 7.5, 7.5, 1.0, 1.0, 1.0, #TRUCK + 5.0, 7.5, 7.5, 7.5, 7.5, 1.0, 1.0, 1.0, #BUS + 5.0, 7.5, 7.5, 7.5, 7.5, 1.0, 1.0, 1.0, #TRAILER + 3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #MOTORBIKE + 3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #BICYCLE + 3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.5] #PEDESTRIAN + max_rad_matrix: # If value is greater than pi, it will be ignored. + #UNKNOWN, CAR, TRUCK, BUS, TRAILER MOTORBIKE, BICYCLE, PEDESTRIAN + [3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #CAR + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRUCK + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #BUS + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRAILER + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN + + max_velocity_diff_matrix: # Ignored when value is larger than 100.0 + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #UNKNOWN + 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #CAR + 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRUCK + 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #BUS + 100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRAILER + 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #MOTORBIKE + 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #BICYCLE + 100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0] #PEDESTRIAN + + min_iou_matrix: # set all value to 0.0 to disable this constraint + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #UNKNOWN + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #CAR + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #TRUCK + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #BUS + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #TRAILER + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #MOTORBIKE + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #BICYCLE + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] #PEDESTRIAN diff --git a/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger.param.yaml new file mode 100644 index 0000000000..13369d5422 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger.param.yaml @@ -0,0 +1,26 @@ +# Node parameters +/**: + ros__parameters: + base_link_frame_id: "base_link" + time_sync_threshold: 0.999 + sub_object_timeout_sec: 0.8 + publish_interpolated_sub_objects: true #for debug + + # choose the input sensor type for each object type + # "lidar", "radar", "camera" are available + main_sensor_type: "lidar" + sub_sensor_type: "radar" + + # tracker settings + tracker_state_parameter: + remove_probability_threshold: 0.3 + publish_probability_threshold: 0.5 + default_lidar_existence_probability: 0.7 + default_radar_existence_probability: 0.6 + default_camera_existence_probability: 0.5 + decay_rate: 0.1 + max_dt: 1.0 + + # logging + enable_logging: false + log_file_path: "/tmp/decorative_tracker_merger.log" diff --git a/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger_policy.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger_policy.param.yaml new file mode 100644 index 0000000000..0b98e1b202 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/tracking/tracking_object_merger/decorative_tracker_merger_policy.param.yaml @@ -0,0 +1,16 @@ +# Merger policy for decorative tracker merger node +# decorative tracker merger works by merging the sub-object trackers into a main object tracker result +# There are 3 merger policy: +# 1. "skip": skip the sub-object tracker result +# 2. "overwrite": overwrite the main object tracker result with sub-object tracker result +# 3. "fusion": merge the main object tracker result with sub-object tracker result by using covariance based fusion +/**: + ros__parameters: + kinematics_to_be_merged: "velocity" # currently only support "velocity" + + # choose the merger policy for each object type + # : "skip", "overwrite", "fusion" + kinematics_merge_policy: "overwrite" + classification_merge_policy: "skip" + existence_prob_merge_policy: "skip" + shape_merge_policy: "skip" diff --git a/autoware_launch/config/planning/mission_planning/mission_planner/mission_planner.param.yaml b/autoware_launch/config/planning/mission_planning/mission_planner/mission_planner.param.yaml index 98c28344ea..9b7dcffbc6 100644 --- a/autoware_launch/config/planning/mission_planning/mission_planner/mission_planner.param.yaml +++ b/autoware_launch/config/planning/mission_planning/mission_planner/mission_planner.param.yaml @@ -9,3 +9,4 @@ reroute_time_threshold: 10.0 minimum_reroute_length: 30.0 consider_no_drivable_lanes: false # This flag is for considering no_drivable_lanes in planning or not. + check_footprint_inside_lanes: true diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml new file mode 100644 index 0000000000..7bd3dd26b3 --- /dev/null +++ b/autoware_launch/config/planning/preset/default_preset.yaml @@ -0,0 +1,117 @@ +launch: + # behavior path modules + - arg: + name: launch_avoidance_module + default: "true" + - arg: + name: launch_avoidance_by_lane_change_module + default: "true" + - arg: + name: launch_dynamic_avoidance_module + default: "false" + - arg: + name: launch_lane_change_right_module + default: "true" + - arg: + name: launch_lane_change_left_module + default: "true" + - arg: + name: launch_external_request_lane_change_right_module + default: "false" + - arg: + name: launch_external_request_lane_change_left_module + default: "false" + - arg: + name: launch_goal_planner_module + default: "true" + - arg: + name: launch_start_planner_module + default: "true" + - arg: + name: launch_side_shift_module + default: "true" + + # behavior velocity modules + - arg: + name: launch_crosswalk_module + default: "true" + - arg: + name: launch_walkway_module + default: "true" + - arg: + name: launch_traffic_light_module + default: "true" + - arg: + name: launch_intersection_module + default: "true" + - arg: + name: launch_merge_from_private_module + default: "true" + - arg: + name: launch_blind_spot_module + default: "true" + - arg: + name: launch_detection_area_module + default: "true" + - arg: + name: launch_virtual_traffic_light_module + default: "false" + - arg: + name: launch_no_stopping_area_module + default: "true" + - arg: + name: launch_stop_line_module + default: "true" + - arg: + name: launch_occlusion_spot_module + default: "false" + - arg: + name: launch_run_out_module + default: "true" + - arg: + name: launch_speed_bump_module + default: "false" + - arg: + name: launch_out_of_lane_module + default: "true" + - arg: + name: launch_no_drivable_lane_module + default: "false" + + # motion planning modules + - arg: + name: motion_path_smoother_type + default: elastic_band + # option: elastic_band + # none + + - arg: + name: motion_path_planner_type + default: obstacle_avoidance_planner + # option: obstacle_avoidance_planner + # path_sampler + # none + + - arg: + name: motion_stop_planner_type + default: obstacle_stop_planner + # option: obstacle_stop_planner + # obstacle_cruise_planner + # none + + - arg: + name: motion_velocity_smoother_type + default: JerkFiltered + # option: JerkFiltered + # L2 + # Linf(Unstable) + # Analytical + + - arg: + name: launch_surround_obstacle_checker + default: "true" + + # parking modules + - arg: + name: launch_parking_module + default: "true" diff --git a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml index 6bb130e805..03958fda9a 100644 --- a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml @@ -7,6 +7,10 @@ min_jerk: -1.0 # min jerk [m/sss] max_jerk: 1.0 # max jerk [m/sss] + slow_down: + min_acc: -1.0 # min deceleration [m/ss] + min_jerk: -1.0 # min jerk [m/sss] + # constraints to be observed limit: min_acc: -2.5 # min deceleration limit [m/ss] diff --git a/autoware_launch/config/planning/scenario_planning/common/costmap_generator.param.yaml b/autoware_launch/config/planning/scenario_planning/common/costmap_generator.param.yaml new file mode 100644 index 0000000000..cf4f73dc79 --- /dev/null +++ b/autoware_launch/config/planning/scenario_planning/common/costmap_generator.param.yaml @@ -0,0 +1,22 @@ +/**: + ros__parameters: + costmap_frame: "map" + vehicle_frame: "base_link" + map_frame: "map" + update_rate: 10.0 + activate_by_scenario: False + grid_min_value: 0.0 + grid_max_value: 1.0 + grid_resolution: 0.2 + grid_length_x: 70.0 + grid_length_y: 70.0 + grid_position_x: 0.0 + grid_position_y: 0.0 + maximum_lidar_height_thres: 0.3 + minimum_lidar_height_thres: -2.2 + use_wayarea: true + use_parkinglot: true + use_objects: true + use_points: true + expand_polygon_size: 1.0 + size_of_expansion_kernel: 9 diff --git a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml index 2fd2ee8542..c759ead2c8 100644 --- a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml @@ -7,12 +7,21 @@ # external velocity limit parameter margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m] - # curve parameters + # -- curve parameters -- + # common parameters + curvature_calculation_distance: 5.0 # distance of points while curvature is calculating for the steer rate and lateral acceleration limit [m] + # lateral acceleration limit parameters + enable_lateral_acc_limit: true # To toggle the lateral acc filter on and off. You can switch it dynamically at runtime. max_lateral_accel: 0.6 # max lateral acceleration limit [m/ss] min_curve_velocity: 2.74 # min velocity at lateral acceleration limit and steering angle rate limit [m/s] decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit min_decel_for_lateral_acc_lim_filter: -2.5 # deceleration limit applied in the lateral acceleration filter to avoid sudden braking [m/ss] + # steering angle rate limit parameters + enable_steering_rate_limit: true # To toggle the steer rate filter on and off. You can switch it dynamically at runtime. + max_steering_angle_rate: 40.0 # maximum steering angle rate [degree/s] + resample_ds: 0.1 # distance between trajectory points [m] + curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m] # engage & replan parameters replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s] @@ -48,12 +57,6 @@ post_sparse_resample_dt: 0.1 # resample time interval for sparse sampling [s] post_sparse_min_interval_distance: 1.0 # minimum points-interval length for sparse sampling [m] - # steering angle rate limit parameters - max_steering_angle_rate: 40.0 # maximum steering angle rate [degree/s] - resample_ds: 0.1 # distance between trajectory points [m] - curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m] - curvature_calculation_distance: 1.0 # distance of points while curvature is calculating [m] - # system over_stop_velocity_warn_thr: 1.389 # used to check if the optimization exceeds the input velocity on the stop point diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index 389e77ed6f..41d1bd02a7 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -9,7 +9,6 @@ # avoidance module common setting enable_bound_clipping: false - enable_force_avoidance_for_stopped_vehicle: false enable_yield_maneuver: true enable_yield_maneuver_during_shifting: false enable_cancel_maneuver: true @@ -28,7 +27,6 @@ # avoidance is performed for the object type with true target_object: car: - is_target: true # [-] execute_num: 1 # [-] moving_speed_threshold: 1.0 # [m/s] moving_time_threshold: 1.0 # [s] @@ -37,8 +35,8 @@ avoid_margin_lateral: 0.0 # [m] safety_buffer_lateral: 0.8 # [m] safety_buffer_longitudinal: 0.0 # [m] + use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance. truck: - is_target: true execute_num: 1 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -47,8 +45,8 @@ avoid_margin_lateral: 0.0 safety_buffer_lateral: 0.8 safety_buffer_longitudinal: 0.0 + use_conservative_buffer_longitudinal: true bus: - is_target: true execute_num: 1 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -57,8 +55,8 @@ avoid_margin_lateral: 0.0 safety_buffer_lateral: 0.8 safety_buffer_longitudinal: 0.0 + use_conservative_buffer_longitudinal: true trailer: - is_target: true execute_num: 1 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -67,8 +65,8 @@ avoid_margin_lateral: 0.0 safety_buffer_lateral: 0.8 safety_buffer_longitudinal: 0.0 + use_conservative_buffer_longitudinal: true unknown: - is_target: false execute_num: 1 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 @@ -77,8 +75,8 @@ avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 + use_conservative_buffer_longitudinal: true bicycle: - is_target: true execute_num: 1 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 @@ -87,8 +85,8 @@ avoid_margin_lateral: 0.0 safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 + use_conservative_buffer_longitudinal: true motorcycle: - is_target: true execute_num: 1 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -97,8 +95,8 @@ avoid_margin_lateral: 0.0 safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 + use_conservative_buffer_longitudinal: true pedestrian: - is_target: true execute_num: 1 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 @@ -107,19 +105,23 @@ avoid_margin_lateral: 0.0 safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 + use_conservative_buffer_longitudinal: true lower_distance_for_polygon_expansion: 30.0 # [m] upper_distance_for_polygon_expansion: 100.0 # [m] # For target object filtering target_filtering: - # params for avoidance of not-parked objects - threshold_time_force_avoidance_for_stopped_vehicle: 1.0 # [s] - object_ignore_section_traffic_light_in_front_distance: 100.0 # [m] - object_ignore_section_crosswalk_in_front_distance: 30.0 # [m] - object_ignore_section_crosswalk_behind_distance: 30.0 # [m] + # avoidance target type + target_type: + car: true # [-] + truck: true # [-] + bus: true # [-] + trailer: true # [-] + unknown: true # [-] + bicycle: true # [-] + motorcycle: true # [-] + pedestrian: true # [-] # detection range - object_check_forward_distance: 150.0 # [m] - object_check_backward_distance: 10.0 # [m] object_check_goal_distance: 20.0 # [m] # filtering parking objects threshold_distance_object_is_on_center: 1.0 # [m] @@ -128,8 +130,40 @@ # lost object compensation object_last_seen_threshold: 2.0 + # detection area generation parameters + detection_area: + static: false # [-] + min_forward_distance: 50.0 # [m] + max_forward_distance: 150.0 # [m] + backward_distance: 10.0 # [m] + + # params for avoidance of vehicle type objects that are ambiguous as to whether they are parked. + force_avoidance: + enable: false # [-] + time_threshold: 1.0 # [s] + ignore_area: + traffic_light: + front_distance: 100.0 # [m] + crosswalk: + front_distance: 30.0 # [m] + behind_distance: 30.0 # [m] + + # params for filtering objects that are in intersection + intersection: + yaw_deviation: 0.349 # [rad] (default 20.0deg) + # For safety check safety_check: + # safety check target type + target_type: + car: true # [-] + truck: true # [-] + bus: true # [-] + trailer: true # [-] + unknown: false # [-] + bicycle: true # [-] + motorcycle: true # [-] + pedestrian: true # [-] # safety check configuration enable: true # [-] check_current_lane: false # [-] @@ -139,12 +173,16 @@ check_other_object: true # [-] # collision check parameters check_all_predicted_path: false # [-] - time_resolution: 0.5 # [s] - time_horizon_for_front_object: 3.0 # [s] - time_horizon_for_rear_object: 10.0 # [s] safety_check_backward_distance: 100.0 # [m] hysteresis_factor_expand_rate: 1.5 # [-] hysteresis_factor_safe_count: 10 # [-] + # predicted path parameters + min_velocity: 1.38 # [m/s] + max_velocity: 50.0 # [m/s] + time_resolution: 0.5 # [s] + time_horizon_for_front_object: 3.0 # [s] + time_horizon_for_rear_object: 10.0 # [s] + delay_until_departure: 0.0 # [s] # rss parameters expected_front_deceleration: -1.0 # [m/ss] expected_rear_deceleration: -1.0 # [m/ss] @@ -165,14 +203,23 @@ hard_road_shoulder_margin: 0.8 # [m] max_right_shift_length: 5.0 max_left_shift_length: 5.0 + max_deviation_from_lane: 0.5 # [m] # avoidance distance parameters longitudinal: - prepare_time: 2.0 # [s] - remain_buffer_distance: 30.0 # [m] + min_prepare_time: 1.0 # [s] + max_prepare_time: 2.0 # [s] min_prepare_distance: 1.0 # [m] min_slow_down_speed: 1.38 # [m/s] buf_slow_down_speed: 0.56 # [m/s] nominal_avoidance_speed: 8.33 # [m/s] + # return dead line + return_dead_line: + goal: + enable: true # [-] + buffer: 25.0 # [m] + traffic_light: + enable: true # [-] + buffer: 3.0 # [m] # For yield maneuver yield: @@ -184,6 +231,10 @@ stop_buffer: 1.0 # [m] policy: + # policy for rtc request. select "per_shift_line" or "per_avoidance_maneuver". + # "per_shift_line": request approval for each shift line. + # "per_avoidance_maneuver": request approval for avoidance maneuver (avoid + return). + make_approval_request: "per_shift_line" # policy for vehicle slow down behavior. select "best_effort" or "reliable". # "best_effort": slow down deceleration & jerk are limited by constraints. # but there is a possibility that the vehicle can't stop in front of the vehicle. @@ -215,12 +266,6 @@ max_jerk: 1.0 # [m/sss] max_acceleration: 1.0 # [m/ss] - target_velocity_matrix: - col_size: 2 - matrix: - [2.78, 13.9, # velocity [m/s] - 0.50, 1.00] # margin [m] - shift_line_pipeline: trim: quantize_filter_threshold: 0.1 diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lc/avoidance_by_lc.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lc/avoidance_by_lc.param.yaml index bd8545d9e6..74c6112c0e 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lc/avoidance_by_lc.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lc/avoidance_by_lc.param.yaml @@ -7,7 +7,6 @@ # avoidance is performed for the object type with true target_object: car: - is_target: true # [-] execute_num: 2 # [-] moving_speed_threshold: 1.0 # [m/s] moving_time_threshold: 1.0 # [s] @@ -16,7 +15,6 @@ avoid_margin_lateral: 0.0 # [m] safety_buffer_lateral: 0.0 # [m] truck: - is_target: true execute_num: 2 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -25,7 +23,6 @@ avoid_margin_lateral: 0.0 safety_buffer_lateral: 0.0 bus: - is_target: true execute_num: 2 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -34,7 +31,6 @@ avoid_margin_lateral: 0.0 safety_buffer_lateral: 0.0 trailer: - is_target: true execute_num: 2 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -43,7 +39,6 @@ avoid_margin_lateral: 0.0 safety_buffer_lateral: 0.0 unknown: - is_target: true execute_num: 1 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 @@ -52,7 +47,6 @@ avoid_margin_lateral: 0.0 safety_buffer_lateral: 0.0 bicycle: - is_target: false execute_num: 2 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 @@ -61,7 +55,6 @@ avoid_margin_lateral: 0.0 safety_buffer_lateral: 1.0 motorcycle: - is_target: false execute_num: 2 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -70,7 +63,6 @@ avoid_margin_lateral: 0.0 safety_buffer_lateral: 1.0 pedestrian: - is_target: false execute_num: 2 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 @@ -80,3 +72,16 @@ safety_buffer_lateral: 1.0 lower_distance_for_polygon_expansion: 0.0 # [m] upper_distance_for_polygon_expansion: 1.0 # [m] + + # For target object filtering + target_filtering: + # avoidance target type + target_type: + car: true # [-] + truck: true # [-] + bus: true # [-] + trailer: true # [-] + unknown: true # [-] + bicycle: false # [-] + motorcycle: false # [-] + pedestrian: false # [-] diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index 5de4c0d27b..8d93a95b37 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -1,9 +1,9 @@ /**: ros__parameters: verbose: false + max_iteration_num: 100 - groot_zmq_publisher_port: 1666 - groot_zmq_server_port: 1667 + traffic_light_signal_timeout: 1.0 planning_hz: 10.0 backward_path_length: 5.0 diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml index e6fab6e5aa..0558f6c606 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml @@ -5,15 +5,19 @@ drivable_area_left_bound_offset: 0.0 drivable_area_types_to_skip: [road_border] - # Dynamic expansion by projecting the ego footprint along the path + # Dynamic expansion by using the path curvature dynamic_expansion: enabled: true + print_runtime: false + max_expansion_distance: 0.0 # [m] maximum distance by which the drivable area can be expended (0.0 means no limit) + smoothing: + curvature_average_window: 3 # window size used for smoothing the curvatures using a moving window average + max_bound_rate: 1.0 # [m/m] maximum rate of change of the bound lateral distance over its arc length + extra_arc_length: 2.0 # [m] extra arc length where an expansion distance is initially applied ego: - extra_footprint_offset: - front: 1.5 # [m] extra length to add to the front of the ego footprint - rear: 0.5 # [m] extra length to add to the rear of the ego footprint - left: 0.5 # [m] extra length to add to the left of the ego footprint - right: 0.5 # [m] extra length to add to the rear of the ego footprint + extra_wheelbase: 0.0 # [m] extra length to add to the wheelbase + extra_front_overhang: 0.5 # [m] extra length to add to the front overhang + extra_width: 1.0 # [m] extra length to add to the width dynamic_objects: avoid: false # if true, the drivable area is not expanded in the predicted path of dynamic objects extra_footprint_offset: @@ -21,17 +25,12 @@ rear: 0.5 # [m] extra length to add to the rear of the dynamic object footprint left: 0.5 # [m] extra length to add to the left of the dynamic object footprint right: 0.5 # [m] extra length to add to the rear of the dynamic object footprint - expansion: - method: polygon # method used to expand the drivable area. Either 'lanelet' or 'polygon'. - # 'lanelet': add lanelets overlapped by the ego footprints - # 'polygon': add polygons built around sections of the ego footprint that go out of the drivable area - max_distance: 0.0 # [m] maximum distance by which the drivable area can be expended (0.0 means no limit) - max_path_arc_length: 80.0 # [m] maximum arc length along the path where the ego footprint is projected (0.0 means no limit) - extra_arc_length: 0.5 # [m] extra expansion arc length around an ego footprint + path_preprocessing: + max_arc_length: 100.0 # [m] maximum arc length along the path where the ego footprint is projected (0.0 means no limit) + resample_interval: 2.0 # [m] fixed interval between resampled path points (0.0 means path points are directly used) + reuse_max_deviation: 0.5 # [m] if the path changes by more than this value, the curvatures are recalculated. Otherwise they are reused. avoid_linestring: types: # linestring types in the lanelet maps that will not be crossed when expanding the drivable area - road_border - distance: 0.3 # [m] distance to keep between the drivable area and the linestrings to avoid - compensate: - enable: false # if true, when the drivable area cannot be expanded in one direction to completely include the ego footprint, it is expanded in the opposite direction - extra_distance: 3.0 # [m] extra distance to add to the compensation + - curbstone + distance: 0.0 # [m] distance to keep between the drivable area and the linestrings to avoid diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml index fe30397683..854c29aa89 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml @@ -16,6 +16,7 @@ motorcycle: true pedestrian: false + max_obstacle_vel: 100.0 # [m/s] min_obstacle_vel: 0.0 # [m/s] successive_num_to_entry_dynamic_avoidance_condition: 5 @@ -27,10 +28,12 @@ cut_in_object: min_time_to_start_cut_in: 1.0 # [s] min_lon_offset_ego_to_object: 0.0 # [m] + min_object_vel: 0.5 # [m/s] cut_out_object: max_time_from_outside_ego_path: 2.0 # [s] min_object_lat_vel: 0.3 # [m/s] + min_object_vel: 0.5 # [m/s] crossing_object: min_overtaking_object_vel: 1.0 @@ -40,9 +43,11 @@ front_object: max_object_angle: 0.785 + min_object_vel: -0.5 # [m/s] The value is negative considering the noisy velocity of the stopped vehicle. + max_ego_path_lat_cover_ratio: 0.3 # [-] The object will be ignored if the ratio of the object covering the ego's path is higher than this value. drivable_area_generation: - polygon_generation_method: "object_path_base" # choose "ego_path_base" and "object_path_base" + polygon_generation_method: "ego_path_base" # choose "ego_path_base" and "object_path_base" object_path_base: min_longitudinal_polygon_margin: 3.0 # [m] diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml index 6cd6b1f06d..fefbe85607 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml @@ -2,28 +2,32 @@ ros__parameters: goal_planner: # general params - minimum_request_length: 10.0 th_arrived_distance: 1.0 th_stopped_velocity: 0.01 th_stopped_time: 2.0 # It must be greater than the state_machine's. + center_line_path_interval: 1.0 # goal search goal_search: - search_priority: "efficient_path" # "efficient_path" or "close_goal" + goal_priority: "minimum_weighted_distance" # "minimum_weighted_distance" or "minimum_longitudinal_distance" + minimum_weighted_distance: + lateral_weight: 40.0 + prioritize_goals_before_objects: true parking_policy: "left_side" # "left_side" or "right_side" - forward_goal_search_length: 20.0 + forward_goal_search_length: 40.0 backward_goal_search_length: 20.0 goal_search_interval: 2.0 longitudinal_margin: 3.0 - max_lateral_offset: 0.5 - lateral_offset_interval: 0.25 - ignore_distance_from_lane_start: 15.0 + max_lateral_offset: 1.0 + lateral_offset_interval: 0.5 + ignore_distance_from_lane_start: 0.0 margin_from_boundary: 0.75 # occupancy grid map occupancy_grid: - use_occupancy_grid: true - use_occupancy_grid_for_longitudinal_margin: false + use_occupancy_grid_for_goal_search: true + use_occupancy_grid_for_goal_longitudinal_margin: false + use_occupancy_grid_for_path_collision_check: false occupancy_grid_collision_check_margin: 0.0 theta_size: 360 obstacle_threshold: 60 @@ -33,14 +37,18 @@ use_object_recognition: true object_recognition_collision_check_margin: 0.6 # this should be larger than `surround_check_distance` of surround_obstacle_checker object_recognition_collision_check_max_extra_stopping_margin: 1.0 + th_moving_object_velocity: 1.0 # pull over pull_over: + minimum_request_length: 10.0 pull_over_velocity: 3.0 pull_over_minimum_velocity: 1.38 decide_path_distance: 10.0 maximum_deceleration: 1.0 maximum_jerk: 1.0 + path_priority: "efficient_path" # "efficient_path" or "close_goal" + efficient_path_order: ["SHIFT", "ARC_FORWARD", "ARC_BACKWARD"] # only lane based pull over(exclude freespace parking) # shift parking shift_parking: @@ -104,6 +112,76 @@ neighbor_radius: 8.0 margin: 1.0 + stop_condition: + maximum_deceleration_for_stop: 1.0 + maximum_jerk_for_stop: 1.0 + path_safety_check: + # EgoPredictedPath + ego_predicted_path: + min_velocity: 1.0 + min_acceleration: 1.0 + max_velocity: 1.0 + time_horizon_for_front_object: 10.0 + time_horizon_for_rear_object: 10.0 + time_resolution: 0.5 + delay_until_departure: 1.0 + # For target object filtering + target_filtering: + safety_check_time_horizon: 5.0 + safety_check_time_resolution: 1.0 + # detection range + object_check_forward_distance: 100.0 + object_check_backward_distance: 100.0 + ignore_object_velocity_threshold: 1.0 + # ObjectTypesToCheck + object_types_to_check: + check_car: true + check_truck: true + check_bus: true + check_trailer: true + check_bicycle: true + check_motorcycle: true + check_pedestrian: true + check_unknown: false + # ObjectLaneConfiguration + object_lane_configuration: + check_current_lane: true + check_right_side_lane: true + check_left_side_lane: true + check_shoulder_lane: true + check_other_lane: false + include_opposite_lane: false + invert_opposite_lane: false + check_all_predicted_path: true + use_all_predicted_path: true + use_predicted_path_outside_lanelet: false + + # For safety check + safety_check_params: + # safety check configuration + enable_safety_check: true + method: "integral_predicted_polygon" + keep_unsafe_time: 3.0 + # collision check parameters + check_all_predicted_path: true + publish_debug_marker: false + rss_params: + rear_vehicle_reaction_time: 2.0 + rear_vehicle_safety_time_margin: 1.0 + lateral_distance_max_threshold: 2.0 + longitudinal_distance_min_threshold: 3.0 + longitudinal_velocity_delta_time: 0.8 + integral_predicted_polygon_params: + forward_margin: 1.0 + backward_margin: 1.0 + lat_margin: 1.0 + time_horizon: 10.0 + # hysteresis factor to expand/shrink polygon with the value + hysteresis_factor_expand_rate: 1.0 + # temporary + backward_path_length: 30.0 + forward_path_length: 100.0 + # debug debug: print_debug_info: false diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml index b9f03f6b9f..ce9477b173 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml @@ -5,6 +5,7 @@ prepare_duration: 3.0 # [s] backward_length_buffer_for_end_of_lane: 0.5 # [m] + backward_length_buffer_for_blocking_object: 3.0 # [m] lane_change_finish_judge_buffer: 0.0 # [m] lane_changing_lateral_jerk: 0.75 # [m/s3] @@ -28,15 +29,36 @@ # safety check safety_check: - expected_front_deceleration: -1.0 - expected_rear_deceleration: -1.0 - expected_front_deceleration_for_abort: -1.0 - expected_rear_deceleration_for_abort: -2.0 - rear_vehicle_reaction_time: 2.0 - rear_vehicle_safety_time_margin: 1.0 - lateral_distance_max_threshold: 2.0 - longitudinal_distance_min_threshold: 3.0 - longitudinal_velocity_delta_time: 0.8 + allow_loose_check_for_cancel: true + execution: + expected_front_deceleration: -1.0 + expected_rear_deceleration: -1.0 + rear_vehicle_reaction_time: 2.0 + rear_vehicle_safety_time_margin: 1.0 + lateral_distance_max_threshold: 2.0 + longitudinal_distance_min_threshold: 3.0 + longitudinal_velocity_delta_time: 0.8 + cancel: + expected_front_deceleration: -1.0 + expected_rear_deceleration: -2.0 + rear_vehicle_reaction_time: 1.5 + rear_vehicle_safety_time_margin: 0.8 + lateral_distance_max_threshold: 1.0 + longitudinal_distance_min_threshold: 2.5 + longitudinal_velocity_delta_time: 0.6 + stuck: + expected_front_deceleration: -1.0 + expected_rear_deceleration: -1.0 + rear_vehicle_reaction_time: 2.0 + rear_vehicle_safety_time_margin: 1.0 + lateral_distance_max_threshold: 2.0 + longitudinal_distance_min_threshold: 3.0 + longitudinal_velocity_delta_time: 0.8 + + # lane expansion for object filtering + lane_expansion: + left_offset: 0.0 # [m] + right_offset: 0.0 # [m] # lateral acceleration map lateral_acceleration: @@ -62,6 +84,17 @@ check_objects_on_other_lanes: true use_all_predicted_path: true + # lane change regulations + regulation: + crosswalk: false + intersection: false + traffic_light: true + + # ego vehicle stuck detection + stuck_detection: + velocity: 0.5 # [m/s] + stop_time: 3.0 # [s] + # lane change cancel cancel: enable_on_prepare_phase: true diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager.param.yaml index c48943bc9d..0090a29926 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/scene_module_manager.param.yaml @@ -4,81 +4,81 @@ /**: ros__parameters: external_request_lane_change_left: - enable_module: false - enable_rtc: true + enable_rtc: false enable_simultaneous_execution_as_approved_module: false - enable_simultaneous_execution_as_candidate_module: false - priority: 7 + enable_simultaneous_execution_as_candidate_module: true + keep_last: false + priority: 6 max_module_size: 1 external_request_lane_change_right: - enable_module: false - enable_rtc: true + enable_rtc: false enable_simultaneous_execution_as_approved_module: false - enable_simultaneous_execution_as_candidate_module: false - priority: 7 + enable_simultaneous_execution_as_candidate_module: true + keep_last: false + priority: 6 max_module_size: 1 lane_change_left: - enable_module: true - enable_rtc: true + enable_rtc: false enable_simultaneous_execution_as_approved_module: true - enable_simultaneous_execution_as_candidate_module: false - priority: 6 + enable_simultaneous_execution_as_candidate_module: true + keep_last: false + priority: 5 max_module_size: 1 lane_change_right: - enable_module: true - enable_rtc: true + enable_rtc: false enable_simultaneous_execution_as_approved_module: true - enable_simultaneous_execution_as_candidate_module: false - priority: 6 + enable_simultaneous_execution_as_candidate_module: true + keep_last: false + priority: 5 max_module_size: 1 start_planner: - enable_module: true - enable_rtc: true - enable_simultaneous_execution_as_approved_module: false + enable_rtc: false + enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: false + keep_last: false priority: 0 max_module_size: 1 side_shift: - enable_module: false - enable_rtc: true + enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: false + keep_last: false priority: 2 max_module_size: 1 goal_planner: - enable_module: true - enable_rtc: true + enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: false + keep_last: true priority: 1 max_module_size: 1 avoidance: - enable_module: true - enable_rtc: true - enable_simultaneous_execution_as_approved_module: false + enable_rtc: false + enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: false - priority: 5 + keep_last: false + priority: 4 max_module_size: 1 avoidance_by_lc: - enable_module: true - enable_rtc: true + enable_rtc: false enable_simultaneous_execution_as_approved_module: false enable_simultaneous_execution_as_candidate_module: false - priority: 4 + keep_last: false + priority: 3 max_module_size: 1 dynamic_avoidance: - enable_module: false - enable_rtc: true + enable_rtc: false enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: true - priority: 3 + keep_last: true + priority: 7 max_module_size: 1 diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml index 7317221820..9190f55f6b 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/start_planner/start_planner.param.yaml @@ -1,12 +1,15 @@ /**: ros__parameters: start_planner: + th_arrived_distance: 1.0 th_stopped_velocity: 0.01 th_stopped_time: 1.0 collision_check_margin: 1.0 collision_check_distance_from_end: 1.0 th_moving_object_velocity: 1.0 + th_distance_to_middle_of_the_road: 0.5 + center_line_path_interval: 1.0 # shift pull out enable_shift_pull_out: true check_shift_path_lane_departure: false @@ -19,7 +22,7 @@ maximum_curvature: 0.07 # geometric pull out enable_geometric_pull_out: true - divide_pull_out_path: false + divide_pull_out_path: true geometric_pull_out_velocity: 1.0 arc_path_interval: 1.0 lane_departure_margin: 0.2 @@ -72,3 +75,83 @@ max_planning_time: 150.0 neighbor_radius: 8.0 margin: 1.0 + + stop_condition: + maximum_deceleration_for_stop: 1.0 + maximum_jerk_for_stop: 1.0 + path_safety_check: + # EgoPredictedPath + ego_predicted_path: + min_velocity: 0.0 + min_acceleration: 1.0 + time_horizon_for_front_object: 10.0 + time_horizon_for_rear_object: 10.0 + time_resolution: 0.5 + delay_until_departure: 1.0 + # For target object filtering + target_filtering: + safety_check_time_horizon: 5.0 + safety_check_time_resolution: 1.0 + # detection range + object_check_forward_distance: 10.0 + object_check_backward_distance: 100.0 + ignore_object_velocity_threshold: 1.0 + # ObjectTypesToCheck + object_types_to_check: + check_car: true + check_truck: true + check_bus: true + check_trailer: true + check_bicycle: true + check_motorcycle: true + check_pedestrian: true + check_unknown: false + # ObjectLaneConfiguration + object_lane_configuration: + check_current_lane: true + check_right_side_lane: true + check_left_side_lane: true + check_shoulder_lane: true + check_other_lane: false + include_opposite_lane: false + invert_opposite_lane: false + check_all_predicted_path: true + use_all_predicted_path: true + use_predicted_path_outside_lanelet: false + + # For safety check + safety_check_params: + # safety check configuration + enable_safety_check: true + # collision check parameters + check_all_predicted_path: true + publish_debug_marker: false + rss_params: + rear_vehicle_reaction_time: 2.0 + rear_vehicle_safety_time_margin: 1.0 + lateral_distance_max_threshold: 2.0 + longitudinal_distance_min_threshold: 3.0 + longitudinal_velocity_delta_time: 0.8 + # hysteresis factor to expand/shrink polygon + hysteresis_factor_expand_rate: 1.0 + # temporary + backward_path_length: 30.0 + forward_path_length: 100.0 + + surround_moving_obstacle_check: + search_radius: 10.0 + th_moving_obstacle_velocity: 1.0 + # ObjectTypesToCheck + object_types_to_check: + check_car: true + check_truck: true + check_bus: true + check_trailer: true + check_bicycle: true + check_motorcycle: true + check_pedestrian: true + check_unknown: false + + # debug + debug: + print_debug_info: false diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml index ebddd0c75c..aa51c38b55 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml @@ -8,19 +8,3 @@ system_delay: 0.5 delay_response_time: 0.5 is_publish_debug_path: false # publish all debug path with lane id in each module - launch_modules: - - behavior_velocity_planner::CrosswalkModulePlugin - - behavior_velocity_planner::WalkwayModulePlugin - - behavior_velocity_planner::TrafficLightModulePlugin - - behavior_velocity_planner::IntersectionModulePlugin # Intersection module should be before merge from private to declare intersection parameters. - - behavior_velocity_planner::MergeFromPrivateModulePlugin - - behavior_velocity_planner::BlindSpotModulePlugin - - behavior_velocity_planner::DetectionAreaModulePlugin - # behavior_velocity_planner::VirtualTrafficLightModulePlugin - - behavior_velocity_planner::NoStoppingAreaModulePlugin # No stopping area module requires all the stop line. Therefore this modules should be placed at the bottom. - - behavior_velocity_planner::StopLineModulePlugin # Permanent stop line module should be after no stopping area - # behavior_velocity_planner::OcclusionSpotModulePlugin - - behavior_velocity_planner::RunOutModulePlugin - # behavior_velocity_planner::SpeedBumpModulePlugin - - behavior_velocity_planner::OutOfLaneModulePlugin - # behavior_velocity_planner::NoDrivableLaneModulePlugin diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml index 8a57bfeabd..7bd7d88230 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/blind_spot.param.yaml @@ -8,4 +8,5 @@ max_future_movement_time: 10.0 # [second] threshold_yaw_diff: 0.523 # [rad] adjacent_extend_width: 1.5 # [m] - enable_rtc: true # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc. + opposite_adjacent_extend_width: 1.5 # [m] + enable_rtc: false # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc. diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml index 0c12624f3b..e7bdda45de 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml @@ -5,11 +5,11 @@ show_processing_time: false # [-] whether to show processing time # param for input data traffic_light_state_timeout: 3.0 # [s] timeout threshold for traffic light signal - enable_rtc: true # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc. + enable_rtc: false # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc. # param for stop position stop_position: - stop_position_threshold: 1.0 # [m] threshold to check whether the vehicle stops in front of crosswalk for yielding + stop_position_threshold: 1.0 # [m] If the ego vehicle has stopped near the stop line than this value, this module assumes itself to have achieved yielding. # For the Lanelet2 map with no explicit stop lines stop_distance_from_crosswalk: 3.5 # [m] make stop line away from crosswalk @@ -18,23 +18,24 @@ # For the case where the stop position is determined according to the object position. stop_distance_from_object: 2.0 # [m] the vehicle decelerates to be able to stop in front of object with margin - # param for ego's slow down velocity + # params for ego's slow down velocity. These params are not used for the case of "enable_rtc: false". slow_down: min_slow_down_velocity: 2.78 # [m/s] target vehicle velocity when module receive slow down command from FOA (2.78 m/s = 10.0 kmph) max_slow_down_jerk: -1.5 # [m/sss] minimum jerk deceleration for safe brake max_slow_down_accel: -2.5 # [m/ss] minimum accel deceleration for safe brake no_relax_velocity: 2.78 # [m/s] if the current velocity is less than X m/s, ego always stops at the stop position(not relax deceleration constraints 2.78 m/s = 10 kmph) - # param for stuck vehicles + # params to prevent stopping on crosswalks due to another vehicle ahead stuck_vehicle: - stuck_vehicle_velocity: 1.0 # [m/s] maximum velocity threshold whether the vehicle is stuck - max_stuck_vehicle_lateral_offset: 2.0 # [m] maximum lateral offset for stuck vehicle position should be looked - stuck_vehicle_attention_range: 10.0 # [m] the detection area is defined as X meters behind the crosswalk - min_acc: -1.0 # min acceleration [m/ss] - min_jerk: -1.0 # min jerk [m/sss] - max_jerk: 1.0 # max jerk [m/sss] + enable_stuck_check_in_intersection: false # [-] flag to enable stuck vehicle checking for crosswalk which is in intersection + stuck_vehicle_velocity: 1.0 # [m/s] threshold velocity whether other vehicles are assumed to be stuck or not. + max_stuck_vehicle_lateral_offset: 2.0 # [m] The feature does not handle the vehicles farther than this value to the ego's path. + stuck_vehicle_attention_range: 10.0 # [m] Ego does not enter the crosswalk area if a stuck vehicle exists within this distance from the end of the crosswalk on the ego's path. + min_acc: -1.0 # min acceleration [m/ss] + min_jerk: -1.0 # min jerk [m/sss] + max_jerk: 1.0 # max jerk [m/sss] - # param for pass judge logic + # params for the pass judge logic against the crosswalk users such as pedestrians or bicycles pass_judge: ego_pass_first_margin_x: [0.0] # [[s]] time to collision margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) ego_pass_first_margin_y: [6.0] # [[s]] time to vehicle margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) @@ -43,23 +44,26 @@ ego_pass_later_margin_y: [10.0] # [[s]] time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) ego_pass_later_additional_margin: 0.5 # [s] additional time margin for object pass first situation to suppress chattering - no_stop_decision: + no_stop_decision: # parameters to determine if it is safe to attempt stopping before the crosswalk max_offset_to_crosswalk_for_yield: 0.0 # [m] maximum offset from ego's front to crosswalk for yield. Positive value means in front of the crosswalk. - min_acc: -1.0 # min acceleration [m/ss] - min_jerk: -1.0 # min jerk [m/sss] - max_jerk: 1.0 # max jerk [m/sss] + min_acc: -1.0 # min acceleration [m/ss] + min_jerk: -1.0 # min jerk [m/sss] + max_jerk: 1.0 # max jerk [m/sss] stop_object_velocity_threshold: 0.28 # [m/s] velocity threshold for the module to judge whether the objects is stopped (0.28 m/s = 1.0 kmph) min_object_velocity: 1.39 # [m/s] minimum object velocity (compare the estimated velocity by perception module with this parameter and adopt the larger one to calculate TTV. 1.39 m/s = 5.0 kmph) ## param for yielding - disable_stop_for_yield_cancel: false # for the crosswalk where there is a traffic signal - disable_yield_for_new_stopped_object: false # for the crosswalk where there is a traffic signal - timeout_no_intention_to_walk: 3.0 # [s] if the pedestrian does not move for X seconds after stopping before the crosswalk, the module judge that ego is able to pass first. - timeout_ego_stop_for_yield: 3.0 # [s] the amount of time which ego should be stopping to query whether it yields or not + disable_stop_for_yield_cancel: false # for the crosswalks with traffic signal + disable_yield_for_new_stopped_object: false # for the crosswalks with traffic signal + # If the pedestrian does not move for X seconds after the ego has stopped in front the crosswalk, the module judge that the pedestrian has no intention to walk and allows the ego to proceed. + distance_map_for_no_intention_to_walk: [1.0, 5.0] # [m] ascending order + timeout_map_for_no_intention_to_walk: [3.0, 0.0] # [s] + timeout_ego_stop_for_yield: 3.0 # [s] If the ego maintains the stop for this amount of time, then the ego proceeds, assuming it has stopped long time enough. # param for target object filtering object_filtering: crosswalk_attention_range: 1.0 # [m] the detection area is defined as -X meters before the crosswalk to +X meters behind the crosswalk + vehicle_object_cross_angle_threshold: 0.5 # [rad] threshold judging object is crossing walkway as a pedestrian or passing over as a vehicle target_object: unknown: true # [-] whether to look and stop by UNKNOWN objects bicycle: true # [-] whether to look and stop by BICYCLE objects diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml index 55b627cce7..ddd8b934d2 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/detection_area.param.yaml @@ -8,4 +8,4 @@ state_clear_time: 2.0 hold_stop_margin_distance: 0.0 distance_to_judge_over_stop_line: 0.5 - enable_rtc: true # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc. + enable_rtc: false # if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc. diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index 83d188719a..1e00d2f4a4 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -2,58 +2,94 @@ ros__parameters: intersection: common: - attention_area_margin: 0.75 # [m] - attention_area_length: 200.0 # [m] - attention_area_angle_threshold: 0.785 # [rad] - stop_line_margin: 3.0 - intersection_velocity: 2.778 # 2.778m/s = 10.0km/h - intersection_max_accel: 0.5 # m/ss - stop_overshoot_margin: 0.5 # [m] overshoot margin for stuck, collision detection + attention_area_length: 200.0 + attention_area_margin: 0.75 + attention_area_angle_threshold: 0.785 use_intersection_area: false - path_interpolation_ds: 0.1 # [m] - consider_wrong_direction_vehicle: false + default_stopline_margin: 3.0 + stopline_overshoot_margin: 0.5 + path_interpolation_ds: 0.1 + max_accel: -2.8 + max_jerk: -5.0 + delay_response_time: 0.5 + stuck_vehicle: - use_stuck_stopline: true # stopline generated before the first conflicting area - stuck_vehicle_detect_dist: 3.0 # this should be the length between cars when they are stopped. The actual stuck vehicle detection length will be this value + vehicle_length. - stuck_vehicle_ignore_dist: 10.0 # obstacle stop max distance(5.0m) + stuck vehicle size / 2 (0.0m-) - stuck_vehicle_vel_thr: 0.833 # 0.833m/s = 3.0km/h - # enable_front_car_decel_prediction: false # By default this feature is disabled - # assumed_front_car_decel: 1.0 # [m/ss] the expected deceleration of front car when front car as well as ego are turning - timeout_private_area: 3.0 # [s] cancel stuck vehicle stop in private area + turn_direction: + left: true + right: true + straight: true + use_stuck_stopline: true + stuck_vehicle_detect_dist: 5.0 + stuck_vehicle_velocity_threshold: 0.833 + # enable_front_car_decel_prediction: false + # assumed_front_car_decel: 1.0 + timeout_private_area: 3.0 + enable_private_area_stuck_disregard: false + + yield_stuck: + turn_direction: + left: true + right: true + straight: false + distance_threshold: 5.0 collision_detection: - state_transit_margin_time: 1.0 + consider_wrong_direction_vehicle: false + collision_detection_hold_time: 0.5 min_predicted_path_confidence: 0.05 - minimum_ego_predicted_velocity: 1.388 # [m/s] - normal: - collision_start_margin_time: 4.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object - collision_end_margin_time: 6.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object - relaxed: + keep_detection_velocity_threshold: 0.833 + velocity_profile: + use_upstream: true + minimum_upstream_velocity: 0.01 + default_velocity: 2.778 + minimum_default_velocity: 1.388 + fully_prioritized: collision_start_margin_time: 2.0 collision_end_margin_time: 0.0 - keep_detection_vel_thr: 0.833 # == 3.0km/h. keep detection if ego is ego.vel < keep_detection_vel_thr + partially_prioritized: + collision_start_margin_time: 3.0 + collision_end_margin_time: 2.0 + not_prioritized: + collision_start_margin_time: 3.0 + collision_end_margin_time: 2.0 + yield_on_green_traffic_light: + distance_to_assigned_lanelet_start: 10.0 + duration: 3.0 + object_dist_to_stopline: 10.0 + ignore_on_amber_traffic_light: + object_expected_deceleration: 2.0 + ignore_on_red_traffic_light: + object_margin_to_path: 2.0 occlusion: enable: false - occlusion_attention_area_length: 70.0 # [m] - enable_creeping: false # flag to use the creep velocity when reaching occlusion limit stop line - occlusion_creep_velocity: 0.8333 # the creep velocity to occlusion limit stop line - peeking_offset: -0.5 # [m] offset for peeking into detection area + occlusion_attention_area_length: 70.0 free_space_max: 43 occupied_min: 58 - do_dp: true - before_creep_stop_time: 0.1 # [s] - min_vehicle_brake_for_rss: -2.5 # [m/s^2] - max_vehicle_velocity_for_rss: 16.66 # [m/s] == 60kmph - denoise_kernel: 1.0 # [m] - possible_object_bbox: [1.5, 2.5] # [m x m] - ignore_parked_vehicle_speed_threshold: 0.8333 # == 3.0km/h - stop_release_margin_time: 1.5 # [s] + denoise_kernel: 1.0 + attention_lane_crop_curvature_threshold: 0.25 + attention_lane_curvature_calculation_ds: 0.5 + creep_during_peeking: + enable: false + creep_velocity: 0.8333 + peeking_offset: -0.5 + occlusion_required_clearance_distance: 55 + possible_object_bbox: [1.5, 2.5] + ignore_parked_vehicle_speed_threshold: 0.8333 + occlusion_detection_hold_time: 1.5 + temporal_stop_time_before_peeking: 0.1 + temporal_stop_before_attention_area: false + creep_velocity_without_traffic_light: 1.388 + static_occlusion_with_traffic_light_timeout: 0.5 + + debug: + ttc: [0] enable_rtc: - intersection: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval - intersection_to_occlusion: true + intersection: false + intersection_to_occlusion: false merge_from_private: stop_line_margin: 0.5 stop_duration_sec: 1.0 + stop_distance_threshold: 1.0 diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml index f550188d4f..c84848f8cc 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/no_stopping_area.param.yaml @@ -8,4 +8,4 @@ stop_line_margin: 1.0 # [m] margin to auto-gen stop line at no stopping area detection_area_length: 200.0 # [m] used to create detection area polygon stuck_vehicle_front_margin: 6.0 # [m] obstacle stop max distance(5.0m) - enable_rtc: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval + enable_rtc: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml index dd4c1c6102..b55c3b21de 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml @@ -2,7 +2,7 @@ ros__parameters: out_of_lane: # module to stop or slowdown before overlapping another lane with other objects mode: ttc # mode used to consider a conflict with an object. "threshold", "intervals", or "ttc" - skip_if_already_overlapping: true # do not run this module when ego already overlaps another lane + skip_if_already_overlapping: false # do not run this module when ego already overlaps another lane threshold: time_threshold: 5.0 # [s] consider objects that will reach an overlap within this time @@ -17,6 +17,7 @@ use_predicted_paths: true # if true, use the predicted paths to estimate future positions. # if false, assume the object moves at constant velocity along *all* lanelets it currently is located in. predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value. + distance_buffer: 1.0 # [m] distance buffer used to determine if a collision will occur in the other lane overlap: minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered @@ -24,9 +25,9 @@ action: # action to insert in the path if an object causes a conflict at an overlap skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed - strict: true # if true, when a decision is taken to avoid entering a lane, the stop point will make sure no lane at all is entered by ego - # if false, ego stops just before entering a lane but may then be overlapping another lane. + precision: 0.1 # [m] precision when inserting a stop pose in the path distance_buffer: 1.5 # [m] buffer distance to try to keep between the ego footprint and lane + min_duration: 1.0 # [s] minimum duration needed before a decision can be canceled slowdown: distance_threshold: 30.0 # [m] insert a slowdown when closer than this distance from an overlap velocity: 2.0 # [m/s] slowdown velocity @@ -34,6 +35,7 @@ distance_threshold: 15.0 # [m] insert a stop when closer than this distance from an overlap ego: + min_assumed_velocity: 2.0 # [m/s] minimum velocity used to calculate the enter and exit times of ego extra_front_offset: 0.0 # [m] extra front distance extra_rear_offset: 0.0 # [m] extra rear distance extra_right_offset: 0.0 # [m] extra right distance diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml index ff67360785..ccd263bf3a 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml @@ -3,6 +3,7 @@ run_out: detection_method: "Object" # [-] candidate: Object, ObjectWithoutPath, Points use_partition_lanelet: true # [-] whether to use partition lanelet map data + suppress_on_crosswalk: true # [-] whether to suppress on crosswalk lanelet: specify_decel_jerk: false # [-] whether to specify jerk when ego decelerates stop_margin: 2.5 # [m] the vehicle decelerates to be able to stop with this margin passing_margin: 1.1 # [m] the vehicle begins to accelerate if the vehicle's front in predicted position is ahead of the obstacle + this margin @@ -21,14 +22,17 @@ # parameter to create abstracted dynamic obstacles dynamic_obstacle: - use_mandatory_area: false # [-] whether to use mandatory detection area - min_vel_kmph: 0.0 # [km/h] minimum velocity for dynamic obstacles - max_vel_kmph: 5.0 # [km/h] maximum velocity for dynamic obstacles - diameter: 0.1 # [m] diameter of obstacles. used for creating dynamic obstacles from points - height: 2.0 # [m] height of obstacles. used for creating dynamic obstacles from points - max_prediction_time: 10.0 # [sec] create predicted path until this time - time_step: 0.5 # [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path - points_interval: 0.1 # [m] divide obstacle points into groups with this interval, and detect only lateral nearest point. used only for Points method + use_mandatory_area: false # [-] whether to use mandatory detection area + assume_fixed_velocity: + enable: false # [-] If enabled, the obstacle's velocity is assumed to be within the minimum and maximum velocity values specified below + min_vel_kmph: 0.0 # [km/h] minimum velocity for dynamic obstacles + max_vel_kmph: 5.0 # [km/h] maximum velocity for dynamic obstacles + std_dev_multiplier: 1.96 # [-] min and max velocity of the obstacles are calculated from this value and covariance + diameter: 0.1 # [m] diameter of obstacles. used for creating dynamic obstacles from points + height: 2.0 # [m] height of obstacles. used for creating dynamic obstacles from points + max_prediction_time: 10.0 # [sec] create predicted path until this time + time_step: 0.5 # [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path + points_interval: 0.1 # [m] divide obstacle points into groups with this interval, and detect only lateral nearest point. used only for Points method # approach if ego has stopped in the front of the obstacle for a certain amount of time approaching: @@ -48,3 +52,8 @@ enable: false max_jerk: -0.7 # [m/s^3] minimum jerk deceleration for safe brake. max_acc : -2.0 # [m/s^2] minimum accel deceleration for safe brake. + + # prevent abrupt stops caused by false positives in perception + ignore_momentary_detection: + enable: true + time_threshold: 0.15 # [sec] ignores detections that persist for less than this duration diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml index e8e0357daa..23746a61b6 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml @@ -3,6 +3,7 @@ traffic_light: stop_margin: 0.0 tl_state_timeout: 1.0 + stop_time_hysteresis: 0.1 yellow_lamp_period: 2.75 enable_pass_judge: true - enable_rtc: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval + enable_rtc: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_replayer/rtc_replayer.param.yaml similarity index 100% rename from autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_replayer/rtc_replayer.param.yaml diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index 0a44d8aabd..55939fd00b 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -8,7 +8,7 @@ debug: # flag to publish - enable_pub_debug_marker: true # publish debug marker + enable_pub_debug_marker: false # publish debug marker enable_pub_extra_debug_marker: false # publish extra debug marker # flag to show diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index 3409e2d250..7c2e59e58d 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -20,6 +20,10 @@ nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index min_behavior_stop_margin: 3.0 # [m] + stop_on_curve: + enable_approaching: false + additional_safe_distance_margin: 3.0 # [m] + min_safe_distance_margin: 3.0 # [m] suppress_sudden_obstacle_stop: true stop_obstacle_type: @@ -66,9 +70,6 @@ behavior_determination: decimate_trajectory_step_length : 2.0 # longitudinal step length to calculate trajectory polygon for collision checking - goal_extension_length: 5.0 # extension length for collision check around the goal - goal_extension_interval: 1.0 # extension interval for collision check around the goal - prediction_resampling_time_interval: 0.1 prediction_resampling_time_horizon: 10.0 @@ -102,6 +103,13 @@ successive_num_to_entry_slow_down_condition: 5 successive_num_to_exit_slow_down_condition: 5 + # consider the current ego pose (it is not the nearest pose on the reference trajectory) + # Both the lateral error and the yaw error are assumed to decrease to zero by the time duration "time_to_convergence" + # The both errors decrease with constant rates against the time. + consider_current_pose: + enable_to_consider_current_pose: true + time_to_convergence: 1.5 #[s] + cruise: pid_based_planner: use_velocity_limit_based_planner: true @@ -168,10 +176,22 @@ slow_down: # parameters to calculate slow down velocity by linear interpolation - min_lat_margin: 0.2 - max_lat_margin: 0.7 - min_ego_velocity: 2.0 - max_ego_velocity: 8.0 + labels: + - "default" + default: + moving: + min_lat_margin: 0.2 + max_lat_margin: 0.7 + min_ego_velocity: 2.0 + max_ego_velocity: 8.0 + static: + min_lat_margin: 0.2 + max_lat_margin: 0.7 + min_ego_velocity: 2.0 + max_ego_velocity: 8.0 + + moving_object_speed_threshold: 0.5 # [m/s] how fast the object needs to move to be considered as "moving" + moving_object_hysteresis_range: 0.1 # [m/s] hysteresis range used to prevent chattering when obstacle moves close to moving_object_speed_threshold time_margin_on_target_velocity: 1.5 # [s] diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_smoother/elastic_band_smoother.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_smoother/elastic_band_smoother.param.yaml index 8e77420dd4..c67d29c418 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_smoother/elastic_band_smoother.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_smoother/elastic_band_smoother.param.yaml @@ -40,7 +40,7 @@ enable: true # if true, only perform smoothing when the input changes significantly max_path_shape_around_ego_lat_dist: 2.0 # threshold of path shape change around ego [m] max_path_shape_forward_lon_dist: 100.0 # forward point to check lateral distance difference [m] - max_path_shape_forward_lat_dist: 0.1 # threshold of path shape change around forward point [m] + max_path_shape_forward_lat_dist: 0.2 # threshold of path shape change around forward point [m] max_ego_moving_dist: 5.0 # threshold of ego's moving distance for replan [m] # make max_goal_moving_dist long to keep start point fixed for pull over max_goal_moving_dist: 15.0 # threshold of goal's moving distance for replan [m] diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml index 4834a7c673..5ec10572ff 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml @@ -1,11 +1,56 @@ /**: ros__parameters: - # obstacle check - use_pointcloud: false # use pointcloud as obstacle check - use_dynamic_object: true # use dynamic object as obstacle check - surround_check_distance: 0.5 # if objects exist in this distance, transit to "exist-surrounding-obstacle" status [m] - surround_check_recover_distance: 0.8 # if no object exists in this distance, transit to "non-surrounding-obstacle" status [m] + # surround_check_*_distance: if objects exist in this distance, transit to "exist-surrounding-obstacle" status [m] + # surround_check_hysteresis_distance: if no object exists in this hysteresis distance added to the above distance, transit to "non-surrounding-obstacle" status [m] + pointcloud: + enable_check: false + surround_check_front_distance: 0.5 + surround_check_side_distance: 0.5 + surround_check_back_distance: 0.5 + unknown: + enable_check: true + surround_check_front_distance: 0.5 + surround_check_side_distance: 0.5 + surround_check_back_distance: 0.5 + car: + enable_check: true + surround_check_front_distance: 0.5 + surround_check_side_distance: 0.0 + surround_check_back_distance: 0.5 + truck: + enable_check: true + surround_check_front_distance: 0.5 + surround_check_side_distance: 0.0 + surround_check_back_distance: 0.5 + bus: + enable_check: true + surround_check_front_distance: 0.5 + surround_check_side_distance: 0.0 + surround_check_back_distance: 0.5 + trailer: + enable_check: true + surround_check_front_distance: 0.5 + surround_check_side_distance: 0.0 + surround_check_back_distance: 0.5 + motorcycle: + enable_check: true + surround_check_front_distance: 0.5 + surround_check_side_distance: 0.0 + surround_check_back_distance: 0.5 + bicycle: + enable_check: true + surround_check_front_distance: 0.5 + surround_check_side_distance: 0.5 + surround_check_back_distance: 0.5 + pedestrian: + enable_check: true + surround_check_front_distance: 0.5 + surround_check_side_distance: 0.5 + surround_check_back_distance: 0.5 + + surround_check_hysteresis_distance: 0.3 + state_clear_time: 2.0 # ego stop state @@ -13,3 +58,4 @@ # debug publish_debug_footprints: true # publish vehicle footprint & footprints with surround_check_distance and surround_check_recover_distance offsets + debug_footprint_label: "car" diff --git a/autoware_launch/config/system/component_state_monitor/topics.yaml b/autoware_launch/config/system/component_state_monitor/topics.yaml index c00203dbb6..f8c6f9685f 100644 --- a/autoware_launch/config/system/component_state_monitor/topics.yaml +++ b/autoware_launch/config/system/component_state_monitor/topics.yaml @@ -50,6 +50,19 @@ error_rate: 1.0 timeout: 1.0 +- module: localization + mode: [online, logging_simulation] + type: autonomous + args: + node_name_suffix: pose_estimator_pose + topic: /localization/pose_estimator/pose_with_covariance + topic_type: geometry_msgs/msg/PoseWithCovarianceStamped + best_effort: false + transient_local: false + warn_rate: 5.0 + error_rate: 1.0 + timeout: 1.0 + - module: perception mode: [online, logging_simulation] type: launch @@ -76,6 +89,19 @@ error_rate: 1.0 timeout: 1.0 +- module: perception + mode: [online, logging_simulation] + type: autonomous + args: + node_name_suffix: traffic_light_recognition_traffic_signals + topic: /perception/traffic_light_recognition/traffic_signals + topic_type: autoware_perception_msgs/msg/TrafficSignalArray + best_effort: false + transient_local: false + warn_rate: 5.0 + error_rate: 1.0 + timeout: 1.0 + - module: planning mode: [online, logging_simulation, planning_simulation] type: autonomous diff --git a/autoware_launch/config/system/duplicated_node_checker/duplicated_node_checker.param.yaml b/autoware_launch/config/system/duplicated_node_checker/duplicated_node_checker.param.yaml new file mode 100644 index 0000000000..54b4f691b6 --- /dev/null +++ b/autoware_launch/config/system/duplicated_node_checker/duplicated_node_checker.param.yaml @@ -0,0 +1,4 @@ +/**: + ros__parameters: + update_rate: 10.0 + add_duplicated_node_names_to_msg: false # if true, duplicated node names are added to msg diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml new file mode 100644 index 0000000000..2f98f9d0e2 --- /dev/null +++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.awsim.param.yaml @@ -0,0 +1,52 @@ +# Description: +# name: diag name +# sf_at: diag level where it becomes Safe Fault +# lf_at: diag level where it becomes Latent Fault +# spf_at: diag level where it becomes Single Point Fault +# auto_recovery: Determines whether the system will automatically recover when it recovers from an error. +# +# Note: +# empty-value for sf_at, lf_at and spf_at is "none" +# default values are: +# sf_at: "none" +# lf_at: "warn" +# spf_at: "error" +# auto_recovery: "true" +--- +/**: + ros__parameters: + required_modules: + autonomous_driving: + /autoware/control/autonomous_driving/node_alive_monitoring: default + /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default + /autoware/control/control_command_gate/node_alive_monitoring: default + + /autoware/localization/node_alive_monitoring: default + /autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } + /autoware/localization/performance_monitoring/localization_accuracy: { sf_at: "warn", lf_at: "none", spf_at: "none" } + + /autoware/map/node_alive_monitoring: default + + /autoware/perception/node_alive_monitoring: default + + /autoware/planning/node_alive_monitoring: default + /autoware/planning/performance_monitoring/trajectory_validation: default + + # /autoware/sensing/node_alive_monitoring: default + + /autoware/system/node_alive_monitoring: default + /autoware/system/emergency_stop_operation: default + /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } + # /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "none", spf_at: "none" } + + /autoware/vehicle/node_alive_monitoring: default + + external_control: + /autoware/control/control_command_gate/node_alive_monitoring: default + /autoware/control/external_control/external_command_selector/node_alive_monitoring: default + + /autoware/system/node_alive_monitoring: default + /autoware/system/emergency_stop_operation: default + /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } + + /autoware/vehicle/node_alive_monitoring: default diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml index d1035f3606..a5689f4ccf 100644 --- a/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml +++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml @@ -26,6 +26,7 @@ /autoware/localization/node_alive_monitoring: default /autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" } /autoware/localization/performance_monitoring/localization_accuracy: default + /autoware/localization/performance_monitoring/sensor_fusion_status: { sf_at: "error", lf_at: "none", spf_at: "none" } # Map (from map.param.yaml) /autoware/map/node_alive_monitoring: default @@ -48,6 +49,7 @@ /autoware/system/emergency_stop_operation: default /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "none", spf_at: "none" } + /autoware/system/duplicated_node_checker: default /autoware/system/fms_connection: { sf_at: "warn", lf_at: "none", spf_at: "none" } # Vehicle (from vehicle.param.yaml in universe and vehicle.param.yaml in system_launch) diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml index 1f68242f3d..38dec9259a 100644 --- a/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml +++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.planning_simulation.param.yaml @@ -39,6 +39,7 @@ /autoware/system/emergency_stop_operation: default /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } # /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "error", spf_at: "none" } + /autoware/system/duplicated_node_checker: default /autoware/vehicle/node_alive_monitoring: default diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index d4ece803de..990ff17d13 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -6,6 +6,10 @@ + + + + @@ -33,6 +37,7 @@ + @@ -91,12 +96,16 @@ - + + + - + + + diff --git a/autoware_launch/launch/components/tier4_control_component.launch.xml b/autoware_launch/launch/components/tier4_control_component.launch.xml index 8b29135048..d15e050d7a 100644 --- a/autoware_launch/launch/components/tier4_control_component.launch.xml +++ b/autoware_launch/launch/components/tier4_control_component.launch.xml @@ -5,6 +5,7 @@ + @@ -42,5 +43,7 @@ + + diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml index dd39fb2141..7fb68a02f5 100644 --- a/autoware_launch/launch/components/tier4_perception_component.launch.xml +++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml @@ -8,6 +8,7 @@ default="obstacle_pointcloud" description="options: obstacle_pointcloud, occupancy_grid (occupancy_grid_map_method must be laserscan_based_occupancy_grid_map)" /> + @@ -19,6 +20,7 @@ + @@ -29,16 +31,11 @@ - - + + + + + + + + + - + - + diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml index b7035a5d0b..5fb17541cd 100644 --- a/autoware_launch/launch/components/tier4_planning_component.launch.xml +++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml @@ -1,20 +1,8 @@ - - - - - - - - - - - - - - + + @@ -22,52 +10,52 @@ + - - - + - - - - - - - - - - + + + + + + + + + + + + - + + + + + + + + + + + + + + + + @@ -76,15 +64,10 @@ - - - - - - + diff --git a/autoware_launch/launch/components/tier4_simulator_component.launch.xml b/autoware_launch/launch/components/tier4_simulator_component.launch.xml index 0e395f7251..7669b8ba03 100644 --- a/autoware_launch/launch/components/tier4_simulator_component.launch.xml +++ b/autoware_launch/launch/components/tier4_simulator_component.launch.xml @@ -41,10 +41,35 @@ name="object_recognition_tracking_multi_object_tracker_data_association_matrix_param_path" value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml" /> + + + + + + + diff --git a/autoware_launch/launch/components/tier4_system_component.launch.xml b/autoware_launch/launch/components/tier4_system_component.launch.xml index 3cfc6d8541..a90fdb89a5 100644 --- a/autoware_launch/launch/components/tier4_system_component.launch.xml +++ b/autoware_launch/launch/components/tier4_system_component.launch.xml @@ -1,5 +1,7 @@ + + @@ -8,9 +10,10 @@ + - + diff --git a/autoware_launch/launch/e2e_simulator.launch.xml b/autoware_launch/launch/e2e_simulator.launch.xml index b33e325f14..c2fdd1b855 100644 --- a/autoware_launch/launch/e2e_simulator.launch.xml +++ b/autoware_launch/launch/e2e_simulator.launch.xml @@ -4,6 +4,10 @@ + + + + @@ -18,12 +22,19 @@ + + + @@ -34,6 +45,9 @@ + + + @@ -52,10 +66,12 @@ + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 95bae47ee9..c0a8cea41b 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -5,6 +5,10 @@ + + + + @@ -40,6 +44,8 @@ + + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 12fb5e256a..4430e8a0f8 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -4,6 +4,10 @@ + + + + @@ -37,6 +41,9 @@ + + + diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index f1173bfbd5..a8329b1e5c 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -16,8 +16,6 @@ Panels: Expanded: ~ Name: Views Splitter Ratio: 0.5 - - Class: tier4_localization_rviz_plugin/InitialPoseButtonPanel - Name: InitialPoseButtonPanel - Class: AutowareDateTimePanel Name: AutowareDateTimePanel - Class: rviz_plugins::AutowareStatePanel @@ -321,6 +319,22 @@ Visualization Manager: Value: true Enabled: true Name: Vehicle + - Class: rviz_plugins/MrmSummaryOverlayDisplay + Enabled: false + Font Size: 10 + Left: 512 + Max Letter Num: 100 + Name: MRM Summary + Text Color: 25; 255; 240 + Top: 64 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /system/emergency/hazard_status + Value: false + Value height offset: 0 Enabled: true Name: System - Class: rviz_common/Group @@ -387,6 +401,7 @@ Visualization Manager: walkway_lanelets: true hatched_road_markings_bound: true hatched_road_markings_area: false + intersection_area: false Topic: Depth: 5 Durability Policy: Transient Local @@ -888,7 +903,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Best Effort - Value: /perception/traffic_light_recognition/debug/rois + Value: /perception/traffic_light_recognition/traffic_light/debug/rois Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true @@ -2125,6 +2140,18 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/virtual_wall Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: VirtualWall (MotionVelocitySmoother) + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/motion_velocity_smoother/virtual_wall + Value: true Enabled: true Name: VirtualWall - Class: rviz_common/Group @@ -2418,6 +2445,1193 @@ Visualization Manager: Value: false Enabled: true Name: Control + - Class: rviz_common/Group + Displays: + - Class: rviz_common/Group + Displays: ~ + Enabled: true + Name: Map + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/Camera + Enabled: true + Far Plane Distance: 100 + Image Rendering: background and overlay + Name: PointcloudOnCamera + Overlay Alpha: 0.5 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /sensing/camera/camera6/image_raw + Value: true + Visibility: + Control: + Debug/AEB: true + Debug/MPC: true + Debug/PurePursuit: true + Predicted Trajectory: true + Value: false + Debug: + Control: true + Localization: + EKFPoseHistory: true + NDT pointclouds: true + NDTLoadedPCDMap: true + NDTPoseHistory: true + Value: true + Map: true + Perception: + CameraLidarFusion(purple): true + Centerpoint(red1): true + CenterpointROIFusion(red2): true + CenterpointValidator(red3): true + Detection(yellow): true + DetectionByTracker(cyan): true + PointPainting(light_green1): true + PointPaintingROIFusion(light_green2): true + PointPaintingValidator(light_green3): true + Prediction(light_blue): true + RadarFarObjects(white): true + Tracking(green): true + Value: true + Planning: true + Sensing: + ConcatenatePointCloud: true + PointcloudOnCamera: true + RadarRawObjects(white): true + Value: true + Value: true + Localization: + EKF: + PoseHistory: true + Value: true + NDT: + Aligned: true + Initial: true + MonteCarloInitialPose: true + PoseHistory: true + PoseWithCovAligned: true + PoseWithCovInitial: true + Value: true + Value: false + Map: + Lanelet2VectorMap: true + PointCloudMap: true + Value: false + Perception: + ObjectRecognition: + Detection: + DetectedObjects: true + Value: true + Prediction: + Maneuver: true + PredictedObjects: true + Value: true + Tracking: + TrackedObjects: true + Value: true + Value: true + OccupancyGrid: + Map: true + Value: true + Segmentation: + NoGroundPointCloud: true + Value: true + TrafficLight: + MapBasedDetectionResult: true + RecognitionResultOnImage: true + Value: true + Value: false + Planning: + Diagnostic: + PlanningErrorMarker: true + Value: true + MissionPlanning: + GoalPose: true + RouteArea: true + Value: true + ScenarioPlanning: + LaneDriving: + BehaviorPlanning: + (old)PathChangeCandidate_LaneChange: true + Bound: true + DebugMarker: + Arrow: true + Avoidance: true + Blind Spot: true + Crosswalk: true + DetectionArea: true + DynamicAvoidance: true + GoalPlanner: true + Intersection: true + LaneFollowing: true + LeftLaneChange: true + NoDrivableLane: true + NoStoppingArea: true + OcclusionSpot: true + OutOfLane: true + RightLaneChange: true + RunOut: true + SideShift: true + SpeedBump: true + StartPlanner: true + StopLine: true + TrafficLight: true + Value: true + VirtualTrafficLight: true + InfoMarker: + Info (Avoidance): true + Info (AvoidanceByLC): true + Info (DynamicAvoidance): true + Info (ExtLaneChangeLeft): true + Info (ExtLaneChangeRight): true + Info (GoalPlanner): true + Info (LaneChangeLeft): true + Info (LaneChangeRight): true + Info (StartPlanner): true + Value: true + Path: true + PathChangeCandidate_Avoidance: true + PathChangeCandidate_AvoidanceByLC: true + PathChangeCandidate_ExternalRequestLaneChangeLeft: true + PathChangeCandidate_ExternalRequestLaneChangeRight: true + PathChangeCandidate_GoalPlanner: true + PathChangeCandidate_LaneChangeLeft: true + PathChangeCandidate_LaneChangeRight: true + PathChangeCandidate_StartPlanner: true + PathReference_Avoidance: true + PathReference_AvoidanceByLC: true + PathReference_GoalPlanner: true + PathReference_LaneChangeLeft: true + PathReference_LaneChangeRight: true + PathReference_StartPlanner: true + Value: true + VirtualWall: + Value: true + VirtualWall (Avoidance): true + VirtualWall (AvoidanceByLC): true + VirtualWall (BlindSpot): true + VirtualWall (Crosswalk): true + VirtualWall (DetectionArea): true + VirtualWall (ExtLaneChangeLeft): true + VirtualWall (ExtLaneChangeRight): true + VirtualWall (GoalPlanner): true + VirtualWall (Intersection): true + VirtualWall (LaneChangeLeft): true + VirtualWall (LaneChangeRight): true + VirtualWall (MergeFromPrivateArea): true + VirtualWall (NoDrivableLane): true + VirtualWall (NoStoppingArea): true + VirtualWall (OcclusionSpot): true + VirtualWall (OutOfLane): true + VirtualWall (RunOut): true + VirtualWall (SpeedBump): true + VirtualWall (StartPlanner): true + VirtualWall (StopLine): true + VirtualWall (TrafficLight): true + VirtualWall (VirtualTrafficLight): true + VirtualWall (Walkway): true + MotionPlanning: + DebugMarker: + ObstacleAvoidance: true + ObstacleCruise: + CruiseVirtualWall: true + DebugMarker: true + SlowDownVirtualWall: true + Value: true + ObstacleStop: true + SurroundObstacleChecker: + Footprint: true + FootprintOffset: true + FootprintRecoverOffset: true + SurroundObstacleCheck: true + Value: true + Value: true + Trajectory: true + Value: true + VirtualWall: + Value: true + VirtualWall (ObstacleAvoidance): true + VirtualWall (ObstacleCruise): true + VirtualWall (ObstacleStop): true + VirtualWall (SurroundObstacle): true + Value: true + ModifiedGoal: true + Parking: + Costmap: true + PartialPoseArray: true + PoseArray: true + Value: true + ScenarioTrajectory: true + Value: true + Value: false + Sensing: + GNSS: + PoseWithCovariance: true + Value: true + LiDAR: + ConcatenatePointCloud: true + MeasurementRange: true + Value: true + Value: true + System: + Grid: true + MRM Summary: true + TF: true + Value: false + Vehicle: + AccelerationMeter: true + ConsoleMeter: true + MaxVelocity: true + PolarGridDisplay: true + SteeringAngle: true + TurnSignal: true + Value: true + VehicleModel: true + VelocityHistory: true + Value: true + Zoom Factor: 1 + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 5 + Min Value: -1 + Value: false + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: AxisColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: ConcatenatePointCloud + Position Transformer: XYZ + Selectable: false + Size (Pixels): 3 + Size (m): 0.019999999552965164 + Style: Points + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /sensing/lidar/concatenated/pointcloud + Use Fixed Frame: false + Use rainbow: true + Value: true + - BUS: + Alpha: 0.5 + Color: 255; 255; 255 + CAR: + Alpha: 0.5 + Color: 255; 255; 255 + CYCLIST: + Alpha: 0.5 + Color: 255; 255; 255 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.029999999329447746 + MOTORCYCLE: + Alpha: 0.5 + Color: 255; 255; 255 + Name: RadarRawObjects(white) + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.5 + Color: 255; 255; 255 + Polygon Type: 3d + TRAILER: + Alpha: 0.5 + Color: 255; 255; 255 + TRUCK: + Alpha: 0.5 + Color: 255; 255; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /sensing/radar/detected_objects + UNKNOWN: + Alpha: 0.5 + Color: 255; 255; 255 + Value: true + Visualization Type: Normal + Enabled: false + Name: Sensing + - Class: rviz_common/Group + Enabled: true + Name: Localization + Displays: + - Alpha: 0.9990000128746033 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 85; 255; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 85; 255; 127 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: NDT pointclouds + Position Transformer: XYZ + Selectable: false + Size (Pixels): 10 + Size (m): 0.5 + Style: Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/points_aligned + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: "" + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: NDTLoadedPCDMap + Position Transformer: "" + Selectable: true + Size (Pixels): 3 + Size (m): 0.1 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/debug/loaded_pointcloud_map + Use Fixed Frame: true + Use rainbow: true + Value: true + - Buffer Size: 200 + Class: rviz_plugins::PoseHistory + Enabled: true + Line: + Alpha: 0.9990000128746033 + Color: 170; 255; 127 + Value: true + Width: 0.10000000149011612 + Name: NDTPoseHistory + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/pose + Value: true + - Buffer Size: 1000 + Class: rviz_plugins::PoseHistory + Enabled: true + Line: + Alpha: 0.9990000128746033 + Color: 0; 255; 255 + Value: true + Width: 0.10000000149011612 + Name: EKFPoseHistory + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_twist_fusion_filter/pose + Value: true + - Class: rviz_common/Group + Displays: + - BUS: + Alpha: 0.9990000128746033 + Color: 255; 138; 128 + CAR: + Alpha: 0.9990000128746033 + Color: 255; 138; 128 + CYCLIST: + Alpha: 0.9990000128746033 + Color: 255; 138; 128 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.10000000149011612 + MOTORCYCLE: + Alpha: 0.9990000128746033 + Color: 255; 138; 128 + Name: Centerpoint(red1) + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.9990000128746033 + Color: 255; 138; 128 + Polygon Type: 3d + TRAILER: + Alpha: 0.9990000128746033 + Color: 255; 138; 128 + TRUCK: + Alpha: 0.9990000128746033 + Color: 255; 138; 128 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/detection/centerpoint/objects + UNKNOWN: + Alpha: 0.9990000128746033 + Color: 255; 138; 128 + Value: false + Visualization Type: Normal + - BUS: + Alpha: 0.9990000128746033 + Color: 255; 82; 82 + CAR: + Alpha: 0.9990000128746033 + Color: 255; 82; 82 + CYCLIST: + Alpha: 0.9990000128746033 + Color: 255; 82; 82 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.10000000149011612 + MOTORCYCLE: + Alpha: 0.9990000128746033 + Color: 255; 82; 82 + Name: CenterpointROIFusion(red2) + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.9990000128746033 + Color: 255; 82; 82 + Polygon Type: 3d + TRAILER: + Alpha: 0.9990000128746033 + Color: 255; 82; 82 + TRUCK: + Alpha: 0.9990000128746033 + Color: 255; 82; 82 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/detection/centerpoint/roi_fusion/objects + UNKNOWN: + Alpha: 0.9990000128746033 + Color: 255; 82; 82 + Value: false + Visualization Type: Normal + - BUS: + Alpha: 0.9990000128746033 + Color: 213; 0; 0 + CAR: + Alpha: 0.9990000128746033 + Color: 213; 0; 0 + CYCLIST: + Alpha: 0.9990000128746033 + Color: 213; 0; 0 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.10000000149011612 + MOTORCYCLE: + Alpha: 0.9990000128746033 + Color: 213; 0; 0 + Name: CenterpointValidator(red3) + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.9990000128746033 + Color: 213; 0; 0 + Polygon Type: 3d + TRAILER: + Alpha: 0.9990000128746033 + Color: 213; 0; 0 + TRUCK: + Alpha: 0.9990000128746033 + Color: 213; 0; 0 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/detection/centerpoint/validation/objects + UNKNOWN: + Alpha: 0.9990000128746033 + Color: 213; 0; 0 + Value: false + Visualization Type: Normal + - BUS: + Alpha: 0.9990000128746033 + Color: 178; 255; 89 + CAR: + Alpha: 0.9990000128746033 + Color: 178; 255; 89 + CYCLIST: + Alpha: 0.9990000128746033 + Color: 178; 255; 89 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.10000000149011612 + MOTORCYCLE: + Alpha: 0.9990000128746033 + Color: 178; 255; 89 + Name: PointPainting(light_green1) + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.9990000128746033 + Color: 178; 255; 89 + Polygon Type: 3d + TRAILER: + Alpha: 0.9990000128746033 + Color: 178; 255; 89 + TRUCK: + Alpha: 0.9990000128746033 + Color: 178; 255; 89 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/detection/pointpainting/objects + UNKNOWN: + Alpha: 0.9990000128746033 + Color: 178; 255; 89 + Value: false + Visualization Type: Normal + - BUS: + Alpha: 0.9990000128746033 + Color: 118; 255; 3 + CAR: + Alpha: 0.9990000128746033 + Color: 118; 255; 3 + CYCLIST: + Alpha: 0.9990000128746033 + Color: 118; 255; 3 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.10000000149011612 + MOTORCYCLE: + Alpha: 0.9990000128746033 + Color: 118; 255; 3 + Name: PointPaintingROIFusion(light_green2) + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.9990000128746033 + Color: 118; 255; 3 + Polygon Type: 3d + TRAILER: + Alpha: 0.9990000128746033 + Color: 118; 255; 3 + TRUCK: + Alpha: 0.9990000128746033 + Color: 118; 255; 3 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/detection/pointpainting/roi_fusion/objects + UNKNOWN: + Alpha: 0.9990000128746033 + Color: 118; 255; 3 + Value: false + Visualization Type: Normal + - BUS: + Alpha: 0.9990000128746033 + Color: 100; 221; 23 + CAR: + Alpha: 0.9990000128746033 + Color: 100; 221; 23 + CYCLIST: + Alpha: 0.9990000128746033 + Color: 100; 221; 23 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.10000000149011612 + MOTORCYCLE: + Alpha: 0.9990000128746033 + Color: 100; 221; 23 + Name: PointPaintingValidator(light_green3) + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.9990000128746033 + Color: 100; 221; 23 + Polygon Type: 3d + TRAILER: + Alpha: 0.9990000128746033 + Color: 100; 221; 23 + TRUCK: + Alpha: 0.9990000128746033 + Color: 100; 221; 23 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/detection/pointpainting/validation/objects + UNKNOWN: + Alpha: 0.9990000128746033 + Color: 100; 221; 23 + Value: false + Visualization Type: Normal + - BUS: + Alpha: 0.9990000128746033 + Color: 255; 145; 0 + CAR: + Alpha: 0.9990000128746033 + Color: 255; 145; 0 + CYCLIST: + Alpha: 0.9990000128746033 + Color: 255; 145; 0 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.10000000149011612 + MOTORCYCLE: + Alpha: 0.9990000128746033 + Color: 255; 145; 0 + Name: DetectionByTracker(orange) + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.9990000128746033 + Color: 255; 145; 0 + Polygon Type: 3d + TRAILER: + Alpha: 0.9990000128746033 + Color: 255; 145; 0 + TRUCK: + Alpha: 0.9990000128746033 + Color: 255; 145; 0 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/detection/detection_by_tracker/objects + UNKNOWN: + Alpha: 0.9990000128746033 + Color: 255; 145; 0 + Value: false + Visualization Type: Normal + - BUS: + Alpha: 0.9990000128746033 + Color: 213; 0; 249 + CAR: + Alpha: 0.9990000128746033 + Color: 213; 0; 249 + CYCLIST: + Alpha: 0.9990000128746033 + Color: 213; 0; 249 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.10000000149011612 + MOTORCYCLE: + Alpha: 0.9990000128746033 + Color: 213; 0; 249 + Name: CameraLidarFusion(purple) + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.9990000128746033 + Color: 213; 0; 249 + Polygon Type: 3d + TRAILER: + Alpha: 0.9990000128746033 + Color: 213; 0; 249 + TRUCK: + Alpha: 0.9990000128746033 + Color: 213; 0; 249 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/detection/clustering/camera_lidar_fusion/objects + UNKNOWN: + Alpha: 0.9990000128746033 + Color: 213; 0; 249 + Value: false + Visualization Type: Normal + - BUS: + Alpha: 0.9990000128746033 + Color: 255; 255; 255 + CAR: + Alpha: 0.9990000128746033 + Color: 255; 255; 255 + CYCLIST: + Alpha: 0.9990000128746033 + Color: 255; 255; 255 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.10000000149011612 + MOTORCYCLE: + Alpha: 0.9990000128746033 + Color: 255; 255; 255 + Name: RadarFarObjects(white) + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.9990000128746033 + Color: 255; 255; 255 + Polygon Type: 3d + TRAILER: + Alpha: 0.9990000128746033 + Color: 255; 255; 255 + TRUCK: + Alpha: 0.9990000128746033 + Color: 255; 255; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/detection/radar/far_objects + UNKNOWN: + Alpha: 0.9990000128746033 + Color: 255; 255; 255 + Value: false + Visualization Type: Normal + - BUS: + Alpha: 0.9990000128746033 + Color: 255; 234; 0 + CAR: + Alpha: 0.9990000128746033 + Color: 255; 234; 0 + CYCLIST: + Alpha: 0.9990000128746033 + Color: 255; 234; 0 + Class: autoware_auto_perception_rviz_plugin/DetectedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.10000000149011612 + MOTORCYCLE: + Alpha: 0.9990000128746033 + Color: 255; 234; 0 + Name: Detection(yellow) + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.9990000128746033 + Color: 255; 234; 0 + Polygon Type: 3d + TRAILER: + Alpha: 0.9990000128746033 + Color: 255; 234; 0 + TRUCK: + Alpha: 0.9990000128746033 + Color: 255; 234; 0 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/detection/objects + UNKNOWN: + Alpha: 0.9990000128746033 + Color: 255; 234; 0 + Value: false + Visualization Type: Normal + - BUS: + Alpha: 0.9990000128746033 + Color: 0; 230; 118 + CAR: + Alpha: 0.9990000128746033 + Color: 0; 230; 118 + CYCLIST: + Alpha: 0.9990000128746033 + Color: 0; 230; 118 + Class: autoware_auto_perception_rviz_plugin/TrackedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: true + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.10000000149011612 + MOTORCYCLE: + Alpha: 0.9990000128746033 + Color: 0; 230; 118 + Name: Tracking(green) + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.9990000128746033 + Color: 0; 230; 118 + Polygon Type: 3d + TRAILER: + Alpha: 0.9990000128746033 + Color: 0; 230; 118 + TRUCK: + Alpha: 0.9990000128746033 + Color: 0; 230; 118 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/tracking/objects + UNKNOWN: + Alpha: 0.9990000128746033 + Color: 0; 230; 118 + Value: false + Visualization Type: Normal + - BUS: + Alpha: 0.9990000128746033 + Color: 0; 176; 255 + CAR: + Alpha: 0.9990000128746033 + Color: 0; 176; 255 + CYCLIST: + Alpha: 0.9990000128746033 + Color: 0; 176; 255 + Class: autoware_auto_perception_rviz_plugin/PredictedObjects + Display Acceleration: true + Display Label: true + Display PoseWithCovariance: false + Display Predicted Path Confidence: true + Display Predicted Paths: true + Display Twist: true + Display UUID: true + Display Velocity: true + Enabled: true + Line Width: 0.10000000149011612 + MOTORCYCLE: + Alpha: 0.9990000128746033 + Color: 0; 176; 255 + Name: Prediction(light_blue) + Namespaces: + {} + PEDESTRIAN: + Alpha: 0.9990000128746033 + Color: 0; 176; 255 + Polygon Type: 3d + TRAILER: + Alpha: 0.9990000128746033 + Color: 0; 176; 255 + TRUCK: + Alpha: 0.9990000128746033 + Color: 0; 176; 255 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /perception/object_recognition/objects + UNKNOWN: + Alpha: 0.9990000128746033 + Color: 0; 176; 255 + Value: false + Visualization Type: Normal + Enabled: true + Name: Perception + - Class: rviz_common/Group + Displays: + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: LaneChangeLeft + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/debug/objects_of_interest/lane_change_left + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: LaneChangeRight + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/debug/objects_of_interest/lane_change_right + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: AvoidanceLeft + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/debug/objects_of_interest/avoidance_left + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: AvoidanceRight + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/debug/objects_of_interest/avoidance_right + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: AvoidanceByLCLeft + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/debug/objects_of_interest/avoidance_by_lc_left + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: AvoidanceByLCRight + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/debug/objects_of_interest/avoidance_by_lc_right + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: StartPlanner + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/debug/objects_of_interest/start_planner + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: GoalPlanner + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/debug/objects_of_interest/goal_planner + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: Crosswalk + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/debug/objects_of_interest/crosswalk + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: Intersection + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/debug/objects_of_interest/intersection + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: BlindSpot + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/debug/objects_of_interest/blind_spot + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: TrafficLight + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/debug/objects_of_interest/traffic_light + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: DetectionArea + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/debug/objects_of_interest/detection_area + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: NoStoppingArea + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/debug/objects_of_interest/no_stopping_area + Value: true + Enabled: true + Name: Objects Of Interest + Enabled: true + Name: Planning + - Class: rviz_common/Group + Displays: ~ + Enabled: true + Name: Control + Enabled: false + Name: Debug Enabled: true Global Options: Background Color: 10; 10; 10