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 bc3213081d..c39088753f 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/perception/object_recognition/prediction/map_based_prediction.param.yaml b/autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml
index 260ae45da2..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
@@ -29,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..ae1e9d31e6
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/multi_object_tracker_node.param.yaml
@@ -0,0 +1,18 @@
+/**:
+ 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_flag: false
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 f3f04270d6..c68c10f2a9 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
@@ -27,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]
@@ -38,7 +37,6 @@
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
@@ -49,7 +47,6 @@
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
@@ -60,7 +57,6 @@
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
@@ -71,7 +67,6 @@
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: true
unknown:
- is_target: true
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
@@ -82,7 +77,6 @@
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
@@ -93,7 +87,6 @@
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
@@ -104,7 +97,6 @@
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
@@ -119,6 +111,16 @@
# For target object filtering
target_filtering:
+ # 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_goal_distance: 20.0 # [m]
# filtering parking objects
@@ -146,8 +148,22 @@
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 # [-]
@@ -215,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.
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/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 bf9c815405..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
@@ -28,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
@@ -41,8 +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: "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 295c9caf84..06fe74e3b7 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
@@ -119,7 +119,7 @@
# EgoPredictedPath
ego_predicted_path:
min_velocity: 1.0
- acceleration: 1.0
+ min_acceleration: 1.0
max_velocity: 1.0
time_horizon_for_front_object: 10.0
time_horizon_for_rear_object: 10.0
@@ -130,7 +130,7 @@
safety_check_time_horizon: 5.0
safety_check_time_resolution: 1.0
# detection range
- object_check_forward_distance: 10.0
+ object_check_forward_distance: 100.0
object_check_backward_distance: 100.0
ignore_object_velocity_threshold: 1.0
# ObjectTypesToCheck
@@ -159,7 +159,9 @@
# For safety check
safety_check_params:
# safety check configuration
- enable_safety_check: false # Don't set to true if auto_mode is enabled
+ 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
@@ -169,6 +171,11 @@
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
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 c83be4ea15..514d61e225 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
@@ -2,8 +2,6 @@
ros__parameters:
start_planner:
- verbose: false
-
th_arrived_distance: 1.0
th_stopped_velocity: 0.01
th_stopped_time: 1.0
@@ -85,8 +83,7 @@
# EgoPredictedPath
ego_predicted_path:
min_velocity: 0.0
- acceleration: 1.0
- max_velocity: 1.0
+ min_acceleration: 1.0
time_horizon_for_front_object: 10.0
time_horizon_for_rear_object: 10.0
time_resolution: 0.5
@@ -125,7 +122,7 @@
# For safety check
safety_check_params:
# safety check configuration
- enable_safety_check: false # Don't set to true if auto_mode is enabled
+ enable_safety_check: true
# collision check parameters
check_all_predicted_path: true
publish_debug_marker: false
@@ -140,3 +137,21 @@
# 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/crosswalk.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml
index d99c70c5f6..d9d2c407bb 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
@@ -27,6 +27,7 @@
# param for stuck vehicles
stuck_vehicle:
+ 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] 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
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 22f68733a3..1e6ce843de 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,42 +2,47 @@
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:
turn_direction:
left: true
right: true
straight: true
- use_stuck_stopline: true # stopline generated before the first conflicting area
- stuck_vehicle_detect_dist: 5.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_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
- enable_private_area_stuck_disregard: false #In the intersections which labeled as "private area", the obstacle vehicles judged as "stuck" are neglected if this param is set as true.
- yield_stuck:
- turn_direction:
- left: true
- right: false
- straight: false
- distance_thr: 1.0 # [m]
+ 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: false
+ straight: false
+ distance_threshold: 1.0
collision_detection:
- state_transit_margin_time: 0.5
+ 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]
+ 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
@@ -45,52 +50,46 @@
collision_start_margin_time: 3.0
collision_end_margin_time: 2.0
not_prioritized:
- collision_start_margin_time: 3.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object
- collision_end_margin_time: 2.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object
- keep_detection_vel_thr: 0.833 # == 3.0km/h. keep detection if ego is ego.vel < keep_detection_vel_thr
- use_upstream_velocity: true # flag to use the planned velocity profile from the upstream module
- minimum_upstream_velocity: 0.01 # [m/s] minimum velocity to avoid null division for the stop line from the upstream velocity
+ 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 # [m]
+ object_dist_to_stopline: 10.0
ignore_on_amber_traffic_light:
- object_expected_deceleration: 2.0 # [m/ss]
+ 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]
- temporal_stop_before_attention_area: false
- absence_traffic_light:
- creep_velocity: 1.388 # [m/s]
- maximum_peeking_distance: 6.0 # [m]
+ 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: 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
+ intersection: false
intersection_to_occlusion: false
merge_from_private:
- stop_line_margin: 3.0
+ stopline_margin: 3.0
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/run_out.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml
index ca24c59598..f265594a38 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
@@ -21,14 +21,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:
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 bb64006656..9ab8f42bcf 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 4c9f84d5eb..90e897fda3 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
@@ -70,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
diff --git a/autoware_launch/config/system/component_state_monitor/topics.yaml b/autoware_launch/config/system/component_state_monitor/topics.yaml
index 5672d13dcb..f8c6f9685f 100644
--- a/autoware_launch/config/system/component_state_monitor/topics.yaml
+++ b/autoware_launch/config/system/component_state_monitor/topics.yaml
@@ -89,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/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index ece7bee52c..49156fba51 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -81,6 +81,10 @@
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"
/>
+