Skip to content

Commit 6a21393

Browse files
authored
chore: bump version to 0.42.0 (#1366)
Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>
2 parents dd447d9 + 016ca40 commit 6a21393

File tree

20 files changed

+441
-16
lines changed

20 files changed

+441
-16
lines changed

.github/CODEOWNERS-manual

+3-3
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@ autoware_launch/** yukihiro.saito@tier4.jp ryohsuke.mitsudome@tier4.jp mfc@leodr
44
autoware_launch/config/control/** takayuki.murooka@tier4.jp fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp kosuke.takeuchi@tier4.jp yuki.takagi@tier4.jp alqudah.mohammad@tier4.jp kyoichi.sugahara@tier4.jp zulfaqar.azmi@tier4.jp maxime.clement@tier4.jp mamoru.sobue@tier4.jp yukinari.hisaki.2@tier4.jp
55
autoware_launch/config/localization/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp ryu.yamamoto@tier4.jp kento.yabuuchi.2@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp anh.nguyen.2@tier4.jp
66
autoware_launch/config/map/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp ryu.yamamoto@tier4.jp kento.yabuuchi.2@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp anh.nguyen.2@tier4.jp
7-
autoware_launch/config/perception/** shunsuke.miura@tier4.jp yoshi.ri@tier4.jp koji.minoda@tier4.jp taekjin.lee@tier4.jp
7+
autoware_launch/config/perception/** yoshi.ri@tier4.jp koji.minoda@tier4.jp taekjin.lee@tier4.jp
88
autoware_launch/config/planning/** takayuki.murooka@tier4.jp fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp kosuke.takeuchi@tier4.jp yuki.takagi@tier4.jp alqudah.mohammad@tier4.jp kyoichi.sugahara@tier4.jp zulfaqar.azmi@tier4.jp maxime.clement@tier4.jp mamoru.sobue@tier4.jp yukinari.hisaki.2@tier4.jp
99
autoware_launch/config/simulator/** takayuki.murooka@tier4.jp fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp
1010
autoware_launch/config/system/** fumihito.ito@tier4.jp isamu.takagi@tier4.jp
@@ -13,9 +13,9 @@ autoware_launch/launch/components/tier4_autoware_api_component.launch.xml isamu.
1313
autoware_launch/launch/components/tier4_control_component.launch.xml takayuki.murooka@tier4.jp fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp kosuke.takeuchi@tier4.jp yuki.takagi@tier4.jp alqudah.mohammad@tier4.jp kyoichi.sugahara@tier4.jp zulfaqar.azmi@tier4.jp maxime.clement@tier4.jp mamoru.sobue@tier4.jp yukinari.hisaki.2@tier4.jp
1414
autoware_launch/launch/components/tier4_localization_component.launch.xml masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp ryu.yamamoto@tier4.jp kento.yabuuchi.2@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp anh.nguyen.2@tier4.jp
1515
autoware_launch/launch/components/tier4_map_component.launch.xml masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp ryu.yamamoto@tier4.jp kento.yabuuchi.2@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp anh.nguyen.2@tier4.jp
16-
autoware_launch/launch/components/tier4_perception_component.launch.xml shunsuke.miura@tier4.jp yoshi.ri@tier4.jp koji.minoda@tier4.jp taekjin.lee@tier4.jp
16+
autoware_launch/launch/components/tier4_perception_component.launch.xml yoshi.ri@tier4.jp koji.minoda@tier4.jp taekjin.lee@tier4.jp
1717
autoware_launch/launch/components/tier4_planning_component.launch.xml takayuki.murooka@tier4.jp fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp kosuke.takeuchi@tier4.jp yuki.takagi@tier4.jp alqudah.mohammad@tier4.jp kyoichi.sugahara@tier4.jp zulfaqar.azmi@tier4.jp maxime.clement@tier4.jp mamoru.sobue@tier4.jp yukinari.hisaki.2@tier4.jp
18-
autoware_launch/launch/components/tier4_sensing_component.launch.xml shunsuke.miura@tier4.jp yoshi.ri@tier4.jp koji.minoda@tier4.jp
18+
autoware_launch/launch/components/tier4_sensing_component.launch.xml yoshi.ri@tier4.jp koji.minoda@tier4.jp
1919
autoware_launch/launch/components/tier4_simulator_component.launch.xml takayuki.murooka@tier4.jp fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp
2020
autoware_launch/launch/components/tier4_system_component.launch.xml fumihito.ito@tier4.jp isamu.takagi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
2121
autoware_launch/rviz/** # no codeowners

autoware_launch/CHANGELOG.rst

+56
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,62 @@
22
Changelog for package autoware_launch
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
0.42.0 (2025-03-03)
6+
-------------------
7+
* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
8+
* chore(ekf_localizer): increase z_filter_proc_dev for large gradient road (`#1337 <https://github.com/autowarefoundation/autoware_launch/issues/1337>`_)
9+
increase z_filter_proc_dev
10+
* feat(autoware_motion_velocity_obstacle_slow_down_module): params for obstacle stop and slow down modules (`#1330 <https://github.com/autowarefoundation/autoware_launch/issues/1330>`_)
11+
* fix
12+
* style(pre-commit): autofix
13+
* fix
14+
---------
15+
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
16+
* feat(goal_planner): align vehicle center to be parallel to lane boundary (`#1335 <https://github.com/autowarefoundation/autoware_launch/issues/1335>`_)
17+
* chore(autoware_map_based_prediction): delete unused function and parameter (`#1326 <https://github.com/autowarefoundation/autoware_launch/issues/1326>`_)
18+
* chore(traffic_light): rename enable_fine_detection (`#1310 <https://github.com/autowarefoundation/autoware_launch/issues/1310>`_)
19+
* chore: rename enable_fine_detection
20+
* feat: add new tlr param
21+
* change back to fine_detector
22+
* fix: typo
23+
* add args
24+
* style(pre-commit): autofix
25+
* change default param to fine detector
26+
* style(pre-commit): autofix
27+
---------
28+
Co-authored-by: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com>
29+
Co-authored-by: MasatoSaeki <masato.saeki@tier4.jp>
30+
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
31+
* chore(traffic_light_multi_camera_fusion): read parameters from yaml file (`#1331 <https://github.com/autowarefoundation/autoware_launch/issues/1331>`_)
32+
* chore(traffic_light_multi_camera_fusion): read parameters from yaml file
33+
* style(pre-commit): autofix
34+
* remove camera namespace parameter from config file
35+
---------
36+
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
37+
* feat(tier4_perception_component): change tlr pedestrian classifier model (`#1329 <https://github.com/autowarefoundation/autoware_launch/issues/1329>`_)
38+
change model name
39+
* fix(ground_segmentation): bring junction parameter from param file to launch argument (`#1327 <https://github.com/autowarefoundation/autoware_launch/issues/1327>`_)
40+
* refactor(ground_segmentation): remove single frame filter and keep time series filter disabled
41+
* feat(tier4_perception): add single frame and time series filters for obstacle segmentation
42+
---------
43+
* feat(autoware_probabilistic_occupancy_grid_map): disabled the subsample filters for the ogm (`#1319 <https://github.com/autowarefoundation/autoware_launch/issues/1319>`_)
44+
feat: disabled the subsample filters for the ogm since its creation is faster now
45+
* feat: use motion_velocity_obstacle\_<stop/slow_down/cruise>_module (`#1315 <https://github.com/autowarefoundation/autoware_launch/issues/1315>`_)
46+
Revert "enable obstacle_cruise_planner"
47+
This reverts commit cbd6873e7786bf139796b20a30ada5d90bd8407b.
48+
* feat(autoware_behavior_velocity_traffic_light_module): adjust velocity threshold for ensure stop at yellow light (`#1322 <https://github.com/autowarefoundation/autoware_launch/issues/1322>`_)
49+
* refactor(goal_planner): remove use_object_recognition because it is default (`#1318 <https://github.com/autowarefoundation/autoware_launch/issues/1318>`_)
50+
* feat(rviz): update autoware.rviz for motion_velocity_obstacle\_<stop/slow_down/cruise>_module (`#1314 <https://github.com/autowarefoundation/autoware_launch/issues/1314>`_)
51+
* feat: add motion_velocity_obstacle_stop/slow_down/cruise_module
52+
* update autoware.rviz
53+
* update rviz
54+
* disable obstacle_cruise_planner
55+
* update motion velocity planner params
56+
* add module.param.yaml
57+
* enable obstacle_cruise_planner
58+
---------
59+
* Contributors: Arjun Jagdish Ram, Kento Yabuuchi, Kenzo Lobos Tsunekawa, Mamoru Sobue, Masato Saeki, Taekjin LEE, Takayuki Murooka, Tomohito ANDO, Tomoya Kimura, badai nguyen, github-actions
60+
561
0.41.0 (2025-01-29)
662
-------------------
763
* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base

autoware_launch/config/localization/ekf_localizer.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@
2828

2929
simple_1d_filter_parameters:
3030
#Simple1DFilter parameters
31-
z_filter_proc_dev: 1.0
31+
z_filter_proc_dev: 5.0
3232
roll_filter_proc_dev: 0.1
3333
pitch_filter_proc_dev: 0.1
3434

autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml

-1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
/**:
22
ros__parameters:
3-
enable_delay_compensation: true
43
prediction_time_horizon:
54
vehicle: 15.0 #[s]
65
pedestrian: 10.0 #[s]

autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml

-2
Original file line numberDiff line numberDiff line change
@@ -2,8 +2,6 @@
22
ros__parameters:
33
additional_lidars: []
44
ransac_input_topics: []
5-
use_single_frame_filter: False
6-
use_time_series_filter: True
75

86
common_crop_box_filter:
97
parameters:

autoware_launch/config/perception/occupancy_grid_map/pointcloud_based_occupancy_grid_map.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@
99
max_height: 2.0
1010

1111
# downsample input pointcloud
12-
downsample_input_pointcloud: true
12+
downsample_input_pointcloud: false
1313
downsample_voxel_size: 0.125 # [m]
1414

1515
enable_single_frame_mode: false
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
/**:
2+
ros__parameters:
3+
message_lifespan: 0.09
4+
approximate_sync: false

autoware_launch/config/planning/preset/default_preset.yaml

+10-1
Original file line numberDiff line numberDiff line change
@@ -93,6 +93,15 @@ launch:
9393
# none
9494

9595
# motion velocity planner modules
96+
- arg:
97+
name: launch_obstacle_stop_module
98+
default: "true"
99+
- arg:
100+
name: launch_obstacle_slow_down_module
101+
default: "true"
102+
- arg:
103+
name: launch_obstacle_cruise_module
104+
default: "true"
96105
- arg:
97106
name: launch_dynamic_obstacle_stop_module
98107
default: "true"
@@ -105,7 +114,7 @@ launch:
105114

106115
- arg:
107116
name: motion_stop_planner_type
108-
default: obstacle_cruise_planner
117+
default: none
109118
# option: obstacle_stop_planner
110119
# obstacle_cruise_planner
111120
# none

autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml

+1-2
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,6 @@
3939

4040
# object recognition
4141
object_recognition:
42-
use_object_recognition: true
4342
collision_check_soft_margins: [5.0, 4.5, 4.0, 3.5, 3.0, 2.5, 2.0, 1.5, 1.0] # the maximum margin when ego and objects are oriented.
4443
collision_check_hard_margins: [0.6] # this should be larger than `surround_check_distance` of surround_obstacle_checker
4544
object_recognition_collision_check_max_extra_stopping_margin: 1.0
@@ -69,7 +68,7 @@
6968
maximum_lateral_jerk: 2.0
7069
minimum_lateral_jerk: 0.5
7170
deceleration_interval: 15.0
72-
after_shift_straight_distance: 1.0
71+
after_shift_straight_distance: 1.5
7372

7473
# parallel parking path
7574
parallel_parking:

autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/traffic_light.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -5,5 +5,6 @@
55
tl_state_timeout: 1.0
66
stop_time_hysteresis: 0.1
77
yellow_lamp_period: 2.75
8+
yellow_light_stop_velocity: 1.0 # Velocity threshold (m/s) below which the vehicle will always stop before the traffic light when the signal turns yellow, regardless of the pass_judge decision.
89
enable_pass_judge: true
910
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
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,14 @@
11
/**:
22
ros__parameters:
33
smooth_velocity_before_planning: true # [-] if true, smooth the velocity profile of the input trajectory before planning
4+
5+
trajectory_polygon_collision_check:
6+
decimate_trajectory_step_length : 2.0 # longitudinal step length to calculate trajectory polygon for collision checking
7+
goal_extended_trajectory_length: 6.0
8+
9+
# consider the current ego pose (it is not the nearest pose on the reference trajectory)
10+
# Both the lateral error and the yaw error are assumed to decrease to zero by the time duration "time_to_convergence"
11+
# The both errors decrease with constant rates against the time.
12+
consider_current_pose:
13+
enable_to_consider_current_pose: true
14+
time_to_convergence: 1.5 #[s]
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,120 @@
1+
/**:
2+
ros__parameters:
3+
obstacle_cruise:
4+
option:
5+
planning_algorithm: "pid_base" # currently supported algorithm is "pid_base"
6+
7+
cruise_planning:
8+
idling_time: 2.0 # idling time to detect front vehicle starting deceleration [s]
9+
min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss]
10+
min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss]
11+
safe_distance_margin : 5.0 # This is also used as a stop margin [m]
12+
13+
pid_based_planner:
14+
use_velocity_limit_based_planner: true
15+
error_function_type: quadratic # choose from linear, quadratic
16+
17+
velocity_limit_based_planner:
18+
# PID gains to keep safe distance with the front vehicle
19+
kp: 10.0
20+
ki: 0.0
21+
kd: 2.0
22+
23+
output_ratio_during_accel: 0.6 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-]
24+
vel_to_acc_weight: 12.0 # target acceleration is calculated by (target_velocity - current_velocity) * vel_to_acc_weight [-]
25+
26+
enable_jerk_limit_to_output_acc: false
27+
28+
disable_target_acceleration: true
29+
30+
velocity_insertion_based_planner:
31+
kp_acc: 6.0
32+
ki_acc: 0.0
33+
kd_acc: 2.0
34+
35+
kp_jerk: 20.0
36+
ki_jerk: 0.0
37+
kd_jerk: 0.0
38+
39+
output_acc_ratio_during_accel: 0.6 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-]
40+
output_jerk_ratio_during_accel: 1.0 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-]
41+
42+
enable_jerk_limit_to_output_acc: true
43+
44+
min_accel_during_cruise: -2.0 # minimum acceleration during cruise to slow down [m/ss]
45+
min_cruise_target_vel: 0.0 # minimum target velocity during slow down [m/s]
46+
time_to_evaluate_rss: 0.0
47+
48+
lpf_normalized_error_cruise_dist_gain: 0.2
49+
50+
optimization_based_planner:
51+
dense_resampling_time_interval: 0.2
52+
sparse_resampling_time_interval: 2.0
53+
dense_time_horizon: 5.0
54+
max_time_horizon: 25.0
55+
velocity_margin: 0.2 #[m/s]
56+
57+
# Parameters for safe distance
58+
t_dangerous: 0.5
59+
60+
# For initial Motion
61+
replan_vel_deviation: 5.0 # velocity deviation to replan initial velocity [m/s]
62+
engage_velocity: 0.25 # engage velocity threshold [m/s] (if the trajectory velocity is higher than this value, use this velocity for engage vehicle speed)
63+
engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement)
64+
engage_exit_ratio: 0.5 # exit engage sequence to normal velocity planning when the velocity exceeds engage_exit_ratio x engage_velocity.
65+
stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m]
66+
67+
# Weights for optimization
68+
max_s_weight: 100.0
69+
max_v_weight: 1.0
70+
over_s_safety_weight: 1000000.0
71+
over_s_ideal_weight: 50.0
72+
over_v_weight: 500000.0
73+
over_a_weight: 5000.0
74+
over_j_weight: 10000.0
75+
76+
obstacle_filtering:
77+
object_type:
78+
inside:
79+
unknown: true
80+
car: true
81+
truck: true
82+
bus: true
83+
trailer: true
84+
motorcycle: true
85+
bicycle: true
86+
pedestrian: false
87+
88+
outside:
89+
unknown: false
90+
car: true
91+
truck: true
92+
bus: true
93+
trailer: true
94+
motorcycle: true
95+
bicycle: false
96+
pedestrian: false
97+
98+
max_lat_margin: 1.0 # lateral margin between obstacle and trajectory band with ego's width
99+
100+
# if crossing vehicle is determined as target obstacles or not
101+
crossing_obstacle:
102+
obstacle_velocity_threshold : 1.0 # velocity threshold for crossing obstacle for cruise or stop [m/s]
103+
obstacle_traj_angle_threshold : 0.523599 # [rad] = 70 [deg], yaw threshold of crossing obstacle against the nearest trajectory point for cruise or stop
104+
105+
outside_obstacle:
106+
obstacle_velocity_threshold : 1.5 # minimum velocity threshold of obstacles outside the trajectory to cruise or stop [m/s]
107+
ego_obstacle_overlap_time_threshold : 0.2 # time threshold to decide cut-in obstacle for cruise or stop [s]
108+
max_prediction_time_for_collision_check : 10.0 # prediction time to check collision between obstacle and ego
109+
max_lateral_time_margin: 5.0 # time threshold of lateral margin between obstacle and trajectory band with ego's width [s]
110+
num_of_predicted_paths: 1 # number of the highest confidence predicted path to check collision between obstacle and ego
111+
yield:
112+
enable_yield: true
113+
lat_distance_threshold: 5.0 # lateral margin between obstacle in neighbor lanes and trajectory band with ego's width for yielding
114+
max_lat_dist_between_obstacles: 2.5 # lateral margin between moving obstacle in neighbor lanes and stopped obstacle in front of it
115+
max_obstacles_collision_time: 10.0 # how far the blocking obstacle
116+
stopped_obstacle_velocity_threshold: 0.5
117+
118+
# hysteresis for cruise and stop
119+
obstacle_velocity_threshold_from_cruise : 3.0 # stop planning is executed to the obstacle whose velocity is less than this value [m/s]
120+
obstacle_velocity_threshold_to_cruise : 3.5 # stop planning is executed to the obstacle whose velocity is less than this value [m/s]
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
/**:
2+
ros__parameters:
3+
obstacle_slow_down:
4+
slow_down_planning:
5+
slow_down_min_acc: -1.0 # slow down min deceleration [m/ss]
6+
slow_down_min_jerk: -1.0 # slow down min jerk [m/sss]
7+
8+
lpf_gain_slow_down_vel: 0.99 # low-pass filter gain for slow down velocity
9+
lpf_gain_lat_dist: 0.999 # low-pass filter gain for lateral distance from obstacle to ego's path
10+
lpf_gain_dist_to_slow_down: 0.7 # low-pass filter gain for distance to slow down start
11+
12+
time_margin_on_target_velocity: 1.5 # [s]
13+
14+
# parameters to calculate slow down velocity by linear interpolation
15+
object_type_specified_params:
16+
types:
17+
- "default"
18+
default:
19+
moving:
20+
min_lat_margin: 0.2
21+
max_lat_margin: 1.0
22+
min_ego_velocity: 2.0
23+
max_ego_velocity: 8.0
24+
static:
25+
min_lat_margin: 0.2
26+
max_lat_margin: 1.0
27+
min_ego_velocity: 4.0
28+
max_ego_velocity: 8.0
29+
30+
moving_object_speed_threshold: 0.5 # [m/s] how fast the object needs to move to be considered as "moving"
31+
moving_object_hysteresis_range: 0.1 # [m/s] hysteresis range used to prevent chattering when obstacle moves close to moving_object_speed_threshold
32+
33+
obstacle_filtering:
34+
object_type:
35+
unknown: false
36+
car: true
37+
truck: true
38+
bus: true
39+
trailer: true
40+
motorcycle: true
41+
bicycle: true
42+
pedestrian: true
43+
pointcloud: false
44+
45+
pointcloud:
46+
pointcloud_voxel_grid_x: 0.05
47+
pointcloud_voxel_grid_y: 0.05
48+
pointcloud_voxel_grid_z: 100000.0
49+
pointcloud_cluster_tolerance: 1.0
50+
pointcloud_min_cluster_size: 1
51+
pointcloud_max_cluster_size: 100000
52+
53+
min_lat_margin: 0.0 # lateral margin between obstacle and trajectory band with ego's width to avoid the conflict with the obstacle_stop
54+
max_lat_margin: 1.1 # lateral margin between obstacle and trajectory band with ego's width
55+
lat_hysteresis_margin: 0.2
56+
57+
successive_num_to_entry_slow_down_condition: 5
58+
successive_num_to_exit_slow_down_condition: 5

0 commit comments

Comments
 (0)