From 068a604b674bc9c7c6c069127df6d0cd8f4c52f7 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Thu, 14 Nov 2024 11:24:03 +0900 Subject: [PATCH 01/25] feat(psim, dummy_diag, diagnostic_graph_aggregator)!: launch dummy_diag_publisher (#1220) Signed-off-by: Yuki Takagi --- .../autoware-psim.yaml | 2 -- .../dummy_diag_publisher.param.yaml | 21 ++++++++++++++++++- .../autoware-psim.yaml | 10 --------- .../launch/planning_simulator.launch.xml | 4 ++-- 4 files changed, 22 insertions(+), 15 deletions(-) delete mode 100644 autoware_launch/config/system/diagnostic_graph_aggregator/autoware-psim.yaml delete mode 100644 autoware_launch/config/system/system_diagnostic_monitor/autoware-psim.yaml diff --git a/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-psim.yaml b/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-psim.yaml deleted file mode 100644 index 20c95af6e9..0000000000 --- a/autoware_launch/config/system/diagnostic_graph_aggregator/autoware-psim.yaml +++ /dev/null @@ -1,2 +0,0 @@ -files: - - { path: $(find-pkg-share autoware_launch)/config/system/system_diagnostic_monitor/autoware-psim.yaml } diff --git a/autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml b/autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml index 43edd109b5..0ed824d3c8 100644 --- a/autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml +++ b/autoware_launch/config/system/dummy_diag_publisher/dummy_diag_publisher.param.yaml @@ -14,4 +14,23 @@ /**: ros__parameters: required_diags: - dummy_diag_empty: default + # map + ## /autoware/map/topic_rate_check/pointcloud_map + "topic_state_monitor_pointcloud_map: map_topic_status": default + + # localization + ## /autoware/localization/scan_matching_status + "ndt_scan_matcher: scan_matching_status": default + + ## /autoware/localization/accuracy + "localization_error_monitor: ellipse_error_status": default + + ## /autoware/localization/sensor_fusion_status + "localization: ekf_localizer": default + + ## /autoware/localization/topic_rate_check/pose_twist_fusion + "topic_state_monitor_pose_twist_fusion_filter_pose: localization_topic_status": default + + # perception + ## /autoware/perception/topic_rate_check/pointcloud + "topic_state_monitor_obstacle_segmentation_pointcloud: perception_topic_status": default diff --git a/autoware_launch/config/system/system_diagnostic_monitor/autoware-psim.yaml b/autoware_launch/config/system/system_diagnostic_monitor/autoware-psim.yaml deleted file mode 100644 index fc17c74173..0000000000 --- a/autoware_launch/config/system/system_diagnostic_monitor/autoware-psim.yaml +++ /dev/null @@ -1,10 +0,0 @@ -files: - - { path: $(dirname)/autoware-main.yaml } - -edits: - - { type: remove, path: /autoware/map/topic_rate_check/pointcloud_map } - - { type: remove, path: /autoware/localization/scan_matching_status } - - { type: remove, path: /autoware/localization/accuracy } - - { type: remove, path: /autoware/localization/sensor_fusion_status } - - { type: remove, path: /autoware/localization/topic_rate_check/pose_twist_fusion } - - { type: remove, path: /autoware/perception/topic_rate_check/pointcloud } diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 798e6ec99b..bc601cb30f 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -18,7 +18,7 @@ - + @@ -68,7 +68,7 @@ - + From a9da3ea2d8c06e16d77527dfa639210c654b74df Mon Sep 17 00:00:00 2001 From: Yutaka Kondo Date: Thu, 14 Nov 2024 13:47:26 +0900 Subject: [PATCH 02/25] chore(package.xml): bump version to 0.38.0 (#1226) (#1229) * add changelog * unify package.xml version to 0.37.0 * 0.38.0 * fix organization --------- Signed-off-by: Yutaka Kondo --- autoware_launch/CHANGELOG.rst | 2315 +++++++++++++++++++++++++++++++++ autoware_launch/package.xml | 2 +- 2 files changed, 2316 insertions(+), 1 deletion(-) create mode 100644 autoware_launch/CHANGELOG.rst diff --git a/autoware_launch/CHANGELOG.rst b/autoware_launch/CHANGELOG.rst new file mode 100644 index 0000000000..60079b9448 --- /dev/null +++ b/autoware_launch/CHANGELOG.rst @@ -0,0 +1,2315 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_launch +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.38.0 (2024-11-13) +------------------- +* feat(start/goal_planner): increse max dry steering angle (`#1200 `_) +* fix(start_planner): set ignore_distance_from_lane_end param to 0.0 since it is not needed (`#1198 `_) + set param to 0.0 since it is not needed +* chore(tier4_perception_launch): enable to use argument `centerpoint_model_name` (`#1182 `_) + * add arguments + * adopt transfusion + * add lidar_detection_model_type + * integrate all in lidar_detection_model + * adopt universe + * fix typo + * change description + * change description + * for pre-commit + --------- +* feat(processing_time_checker): add five module. (`#1192 `_) +* feat(autonomous_emergency_braking): change params to cater to urban scenario (`#1197 `_) + update scenarios +* feat(control_validator): add hold and lpf (`#1193 `_) +* chore(simple_planning_simulator): add stop_filter_param_path (`#1195 `_) +* feat(crosswalk_module): set the velocity of occluded objects to 2.0m/s (`#1194 `_) +* fix(pointcloud_map_filter): add threshold for split map grid size (`#1184 `_) + * fix(pointcloud_map_filter): add param + * fix: disable dynamic map loader for default unsplit-map + --------- +* refactor(rviz): add VirtualWall display for Autonomous Emergency Braking (`#1187 `_) + feat(rviz): add VirtualWall display for Autonomous Emergency Braking +* revert(obstacle_cruisse): revert "fix(obstacle_cruise_planner): guarantee the stop margin (`#1076 `_)" (`#1185 `_) +* feat(obstacle_cruise_planner): improve stop and cruise behavior for cut-in & out (`#1142 `_) +* chore(crop_box_filter): add missing default parameter (`#1155 `_) + fix: add missing parameter after crop_box_filter rework +* feat(autonomous_emergency_braking): set max imu path length (`#1183 `_) + * set param for max imu path distance + * change param + --------- +* fix(obstacle_cruise_planner): tune obstacle_cruise_planner for cruising front NPCs in dense urban ODD scenarios (`#1166 `_) + fix(obstacle_cruise_planner): tune obstacle_cruise_planner for cruising front NPCs in dense urban ODD scenarios +* feat(pose_initializer): add new parameter for check error between initial pose and GNSS pose (`#1180 `_) + * add pose_error_check_enabled parameter + * change default value + --------- +* feat(autonomous_emergency_braking): initiate speed_calculation_expansion_margin parameter (`#1168 `_) + initiate speed_calculation_expansion_margin parameter +* feat(system_error_monitor): delete system error monitor (`#1178 `_) + feat: delete system error monitor +* revert: feat: change visualization of localization results from PoseHistory to PoseWithCovarianceHistory (`#1164 `_) (`#1179 `_) + Revert "feat: change visualization of localization results from PoseHistory to PoseWithCovarianceHistory (`#1164 `_)" + This reverts commit 593ad1f6c2ad967d8d04b349d7970deeed3f47a1. +* fix(perception): adopt awsim (tlr) camera topic (`#1177 `_) +* feat(lane_change): add lane change parameter (`#1157 `_) + add parameter to enable/disable bound check +* fix(avoidance_by_lane_change): remove unused parameter (`#1176 `_) + remove unused parameter +* feat(emergency_handler): delete package (`#1173 `_) + * feat(emergency_handler): delete package +* refactor(system_monitor/net_monitor): remove-missing-patameters (`#1175 `_) + refactor: remove-missing-patameters +* refactor(system_monitor/ntp_monitor): add-missing-parameters (`#1174 `_) + refactor: add-missing-parameters +* refactor(behavior_path_planner): remove unnecessary parameters (`#1172 `_) +* feat(tier4_perception_launch): enable to use multi camera on traffic light recognition (`#1144 `_) + change the way to declare camera num +* style(rviz-config): use colors consistent with new theme (`#1169 `_) +* feat: change visualization of localization results from PoseHistory to PoseWithCovarianceHistory (`#1164 `_) + * PoseHistory to PoseWithCovarianceHistory + * style(pre-commit): autofix + * fix param of alpha related to PoseWithCovarianceHistory + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(crosswalk)!: update stop position caluculation (`#1162 `_) +* feat: add an env variable to enable the new rviz2 theme (`#1017 `_) +* feat(start_planner): add option to skip rear vehicle check (`#1165 `_) +* feat(run_out): speed up run out response (`#1163 `_) + speed up run out response +* feat(mission_planner): add option to prevent rerouting in autonomous driving mode (`#1153 `_) +* feat: add parameters for restart suppression in crosswalk (`#1160 `_) + * feat: add parameters for restart suppression in crosswalk + * update parameter + --------- +* feat(goal_planner): dense goal candidate sampling in BusStopArea (`#1156 `_) +* chore(tier4_pereption_component): add image_segmentation_based_filter option param (`#1158 `_) +* feat(occupancy_grid_map): add option for time keeper (`#1138 `_) + * add option for time keeper + * set default to false + --------- + Co-authored-by: Taekjin LEE +* feat(ground_segmentation): add option for time keeper (`#1134 `_) + add option for time keeper + Co-authored-by: Taekjin LEE +* feat(occupancy_grid_map_outlier_filter): add option for time keeper (`#1147 `_) + add timekeeper option + Co-authored-by: Taekjin LEE +* feat(autoware_mpc_lateral_controller): add resampled reference trajectory for debug purpose (`#1114 `_) + * chore: add debug_publish_resampled_reference_trajectory to parameter + * feat: add use_delayed_initial_state flag to lateral MPC configuration + --------- +* feat(autoware_launch): add expansion params (`#1133 `_) + make expansion optional +* feat: add simulator rviz config (`#1150 `_) +* feat(autoware_lidar_transfusion): add transfusion config (`#1093 `_) +* fix(static_obstacle_avoidance): increase prepare time (`#1148 `_) +* fix(static_obstacle_avoidance): tune parameters (`#1143 `_) +* fix(min-velocity-map-based-prediction): reduce min_velocity_for_map_based_prediction (`#994 `_) + fix(min-velocity-map-based-prediction): reduce min_velocity_for_map_based_prediction to let intersection module run with low speed npc +* chore(stop_filter): extract stop_filter.param.yaml to autoware_launch (`#1145 `_) + Extract stop_filter.param.yaml to autoware_launch +* feat: fix parameter type error in occupancy_grid_map_outlier_filter.param.yaml (`#1146 `_) + * feat: fix parameter type + * chore: change param name + --------- +* feat(detected_object_validation): copy parameter files update from universe (`#1126 `_) + feat: copy params from universe +* feat(pid_longitudinal_controller)!: add acceleration feedback block (`#1139 `_) + * add params + --------- +* feat(occupancy_grid_based_outlier_fillter): add config file to autoware_launch (`#1137 `_) + * feat: add config file + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(obstacle_pointcloud_based_validator): add enable_debugger parameter (`#1123 `_) + * feat: add enable debugger parameter + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(ekf_localizer): change roll, pitch proc dev (`#1140 `_) + change roll, pitch proc dev +* feat(out_of_lane): redesign to improve accuracy and performance (`#1117 `_) +* feat(localization): add lidar_marker_localizer (`#861 `_) + * add config files + * style(pre-commit): autofix + * add param marker_height_from_ground + * save log param + * apply PointXYZIRC + * to pass spell-check + * refactor + * change flag + * fix typo + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: SakodaShintaro +* feat(raw_vehicle_cmd_converter): disable actuation to steering (`#1132 `_) +* chore(e2e_launch): add launch_sensing_driver arg (`#1095 `_) +* feat(raw_vehicle_cmd_converter): add steer command conversion with VGR (`#1131 `_) +* feat(lane_change): consider deceleration in safety check for cancel (`#1068 `_) +* refactor(lane_change): rename prepare_segment_ignore_object_velocity_thresh (`#1125 `_) + change parameter name to a more expressive one +* feat(static_obstacle_avoidance): add parameter for envelope polygon creation (`#1130 `_) + * add threshold for eclipse long radius + * change parameter + --------- +* perf(goal_planner): faster path sorting and selection (`#1119 `_) +* chore(vehicle_cmd_gate): delete deprecated parameters (`#1127 `_) + delete deprecated params in vehicle_cmd_gate.param.yaml +* feat(freespace_planning_algorithms): add new parameters for astar planning algorithm (`#1120 `_) + * add new astar planner parameters + * add flag for obstacle confidence check + * reduce freespace planner th_arrived_distance_m param value + * reduce object polygon expand size in costmap generator + * reduce vehicle shape margin in freespace planner + * replace flag param by time threshold param + --------- +* feat(tier4_perception_launch): add transfusion option for lidar_detection_model (`#1124 `_) +* fix(lidar_model): add centerpoint_sigma param file (`#1086 `_) + fix: add centerpoint_sigma param file +* chore(autoware_multi_object_tracker): fix typo in input_channels (`#1121 `_) + chore: fix typo of lidar_pointpainitng channel +* feat(psim)!: preapre settings to launch localization modules on psim (`#1094 `_) +* fix(lane_change): parameter update (`#1115 `_) +* feat(autoware_map_based_prediction): add debug parameters for map-based prediction (`#1118 `_) + * feat: add debug parameters for map-based prediction + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(psim)!: change a setting parameter type from bool to string (`#1106 `_) + * change a param type, bool to string + --------- +* fix(goal_planner): fix lane departure check not working correctly due to uninitialized variable (`#1116 `_) +* feat(static_obstacle_avoidance): change policy for ambiguous avoidance situation (`#1113 `_) + * feat(static_obstacle_avoidance): change policy for ambiguous avoidance situation + * fix(static_obstacle_avoidance): tune ambiguous vehicle ignore area + --------- +* fix(lane_change): skip generating path if longitudinal distance difference is less than threshold (`#1108 `_) + add skip process lon dist diff threshold +* feat(tracking_object_merger): add merge frame (`#1112 `_) +* fix(mpc_lateral_controller): publish predicted trajectory in Frenet coordinate and visualize it on Rviz (`#1111 `_) +* feat: increase the number of processes monitored by process_monitor (`#1110 `_) +* feat(lane_change): use different rss param to deal with parked vehicle (`#1104 `_) + use separate rss for parked vehicle +* feat(lane_change): add param for lateral angle deviation (`#1087 `_) + * RT1-6514 adding lateral angle deviation param + * decrease angle deviation threshold to fix rtc issue + --------- +* feat(autonomous_emergency_braking): add info marker to aeb and state check override (`#1103 `_) + * add info marker and override for state + * make stop wall viz default + --------- +* feat(behavior_path _planner): divide planner manager modules into dependent slots (`#1091 `_) +* feat(autonomous_emergency_braking): enable AEB stop in vehicle_cmd_gate and diag_graph_agg (`#1099 `_) + * enable emergency handling for AEB stop + * update AEB params to work better at 30 kmph + --------- +* feat(static_obstacle_avoidance): add force deactivation duration time (`#1101 `_) + add force cancel duration time +* perf(freespace_planning_algorithms): tune freespace planner parameters (`#1097 `_) + * reduce longitudinal goal range + * tune parameters + --------- +* feat(dynamic_obstacle_avoidance): shorter predicted path for pedestrians (`#1084 `_) +* feat(crosswalk): more conservative when the ego pass first (`#1085 `_) + * feat: use obstacle_cruise_planner and change safe_distance_margin + * feat: set max_vel to 40km/h + * feat: enable surround_obstacle_checker + * feat: enable surround_obstacle_checker + * feat: enable dynamic_avoidance and disable outside_drivable_area_stop + * feat: disable AEB and set the maximum velocity to 40km/h + * enable intersection_occlusion detection + * chore(planning_launch): update motion module name (`#1014 `_) + * disable AEB diag check + * feat(diagnostic_graph_utils): launch logging node for diagnostic_graph + * feat(api): set launch_deprecated_api true (`#496 `_) + feat(api): launch_deprecated_api=true + * fix(api): disable rosbridge to fix duplicated node (`#497 `_) + * feat(crosswalk): more conservative when the ego pass first + --------- + Co-authored-by: tier4-autoware-public-bot[bot] <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> + Co-authored-by: Mamoru Sobue + Co-authored-by: Mamoru Sobue + Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Daniel Sanchez + Co-authored-by: danielsanchezaran + Co-authored-by: Takamasa Horibe + Co-authored-by: Kosuke Takeuchi +* perf(ndt_scan_matcher): change the temperature of multi_ndt_score to 0.05 (`#1096 `_) + Changed the temperature of multi_ndt_score +* feat(out_of_lane): add lateral buffer between the lane and stop pose (`#1098 `_) +* feat(freespace_planning_algorithm): update freespace planner params (`#1080 `_) + * update freespace planner params + * update goal planner params + * update start planner params + * rename parameter + * change parameter value + --------- +* feat(dynamic_drivable_area_expansion): min_bound_interval parameter (`#1092 `_) +* feat(pid_longitudinal_controller): re-organize diff limit structure (`#1052 `_) + * rearange params +* feat(start_planner): set end_pose_curvature_threshold 0.1 (`#1088 `_) +* feat(out_of_lane): add parameter to ignore objects behind ego (`#1062 `_) +* feat(start_planner): add end_pose_curvature_threshold (`#1059 `_) +* feat(vehicle_cmd_gate): change param to relax pedal rate limit when the vehicle velocity is slow enough (`#1077 `_) + * change param +* feat(ndt_scan_matcher): add scale_factor to covariance_estimation (`#1081 `_) + Added scale_factor to ndt_scan_matcher.covariance_estimation +* feat(simple_planning_simulator): add actuation command simulator (`#1078 `_) +* feat(e2e_simulator.launch): renamed carla interface package in e2e_launch (`#1075 `_) + renamed carla package to autoware_carla_interface +* feat(control_validator)!: add velocity check (`#1050 `_) + add param +* chore: add ml detectors' buffer size (`#1067 `_) +* fix(obstacle_cruise_planner): guarantee the stop margin (`#1076 `_) +* fix(static_obstacle_avoidance): check stopped time in freespace (`#1074 `_) +* feat(autoware_behavior_path_planner): remove max_iteration_num parameter (`#1064 `_) + Update the behavior_path_planner.param.yaml file to remove the max_iteration_num parameter +* feat: add config for processing_time_checker (`#1072 `_) +* feat(duplicated_node_checker): add duplicate nodes to ignore (`#1070 `_) + * feat(duplicated_node_checker): add duplicate nodes to ignore + * pre-commit + --------- + Co-authored-by: Dmitrii Koldaev + Co-authored-by: Tomoya Kimura +* feat(tier4_perception_component): refactored launch options (`#1060 `_) + * chore: refactored launch options + * modify launcher + * fix args + --------- + Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> +* feat(static_obstacle_avoidance): add new option to change policy (`#1065 `_) +* feat(map_loader, route_handler)!: add format_version validation (`#993 `_) + feat(map_loader): add format_version validation +* feat(autonomous_emergency_braking): add param for oublishing debug markers (`#1063 `_) + add param for oublishing debug markers +* feat(ndt_scan_matcher): add params (`#1038 `_) + * add params (ndt_scan_matcher) + * fix param + * rviz + * rviz + * rviz + * style(pre-commit): autofix + * true2false + * Add temperature to parameters in autoware_launch + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(goal_planner): prioritize pull over path by curvature (`#1048 `_) +* refactor(tier4_control_launch): replace python launch with xml (`#1047 `_) + migrate to control.launch.xml +* feat(obstacle_cruise_planner): support pointcloud-based obstacles (`#980 `_) + * feat: use obstacle_cruise_planner and change safe_distance_margin + * feat: set max_vel to 40km/h + * feat: enable surround_obstacle_checker + * feat: enable surround_obstacle_checker + * feat: enable dynamic_avoidance and disable outside_drivable_area_stop + * feat: disable AEB and set the maximum velocity to 40km/h + * enable intersection_occlusion detection + * add parameters for obstacle_cruise_planner + * add parameters for pointcloud filtering + * chore(planning_launch): update motion module name (`#1014 `_) + * move use_pointcloud to common parameter + * disable using pointcloud by default + * disable AEB diag check + * remove use_pointcloud parameter + * feat(diagnostic_graph_utils): launch logging node for diagnostic_graph + * reset to autowarefoundation:main + --------- + Co-authored-by: Takayuki Murooka + Co-authored-by: tier4-autoware-public-bot[bot] <98652886+tier4-autoware-public-bot[bot]@users.noreply.github.com> + Co-authored-by: Mamoru Sobue + Co-authored-by: Mamoru Sobue + Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Daniel Sanchez + Co-authored-by: danielsanchezaran + Co-authored-by: Takamasa Horibe +* chore(eagleye): add septentrio msg option in eagleye_config (`#1049 `_) + Added septentrio option for velocity_source in eagleye_config.param.yaml +* feat(behavior_path_planner): remove max_module_size param (`#1045 `_) + The max_module_size param has been removed from the behavior_path_planner scene_module_manager.param.yaml file. This param was unnecessary and has been removed to simplify the configuration. +* feat(ekf_localizer): add covariance ellipse diagnostics (`#1041 `_) + * Added ellipse diagnostics to ekf + * Fixed to ellipse_scale + --------- +* feat(autoware_launch): use mrm handler by default (`#1043 `_) +* refactor(static_obstacle_avoidance): organize params for drivable lane (`#1042 `_) +* feat(behavior_path_planner): add yaw threshold param (`#1040 `_) + add yaw threshold param +* feat(autonomous_emergency_braking): add and tune params (`#1037 `_) + * add and tune params + * set back voxel grid z + * fix grid to what it is in OSS launch + --------- +* feat(static_obstacle_avoidance)!: add param to select path generation method (`#1036 `_) + feat(static_obstacle_avoidance): add param to select path generation method +* fix(object_lanelet_filter): radar object lanelet filter parameter update (`#1032 `_) + fix: radar object lanelet filter parameter update + fix +* feat(autonomous_emergency_braking): add params to enable or disable PC and predicted objects (`#1031 `_) + * add params to enable or disable PC and predicted objects + * set predicted object usage to false + --------- +* feat: add use_waypoints parameter in map_loader (`#1028 `_) +* feat(autonomous_emergency_braking): add param to toggle on or off object speed calc for aeb (`#1029 `_) + add param to toggle on or off object speed calc for aeb +* refactor(ndt scan matcher): update parameter (`#1018 `_) + * rename to sensor_points.timeout_sec + * parameterize skipping_publish_num + * parameterize initial_to_result_distance_tolerance_m + * add new line + --------- +* refactor(dynamic_obstacle_stop): move to motion_velocity_planner (`#1025 `_) +* fix(start_planner): redefine the necessary parameters (`#1027 `_) + restore necessary param +* refactor(start_planner): remove unused parameters in start planner module (`#1022 `_) + refactor: remove unused parameters in start planner module +* feat(obstacle_velocity_limiter): move to motion_velocity_planner (`#1023 `_) +* refactor(raw_vehicle_cmd_converter)!: prefix package and namespace with autoware (`#1021 `_) + fix +* refactor(out_of_lane): remove from behavior_velocity (`#1020 `_) +* feat(autonomous_emergency_braking): add autoware prefix to AEB (`#1019 `_) + * rename AEB param folder + * change param path and add commented out emergency stop enabling + --------- +* feat(obstacle_cruise)!: type specified stop deccel limit and enabling abandon to stop (`#1003 `_) + abandon_to_stop +* feat(obstacle_curise): revert lateral stop margin for unknown objects (`#1015 `_) +* feat!: change from autoware_auto_msgs to autoware_msgs (`#1012 `_) + * feat(autoware_launch): replace autoware_auto_mapping_msg with autoware_map_msg (`#688 `_) + feat(autoware_launch): remove autoware auto mapping msg + * fix: planning_msg (`#717 `_) + fix:planning_msg + * feat(autoware_launch): replace autoware_control_msg with autoware_con… (`#725 `_) + feat(autoware_launch): replace autoware_control_msg with autoware_control_msg + * feat(autoware_launch): replace autoware_auto_vehicle_msgs with autoware_vehicle_msgs + * fix(topics.yaml): fix AUTO button bug + * feat(autoware_launch): rename autoware_auto_perception_rviz_plugin to autoware_perception_rviz_plugin + * feat: rename TrafficSignal messages to TrafficLightGroup + --------- + Co-authored-by: cyn-liu <104069308+cyn-liu@users.noreply.github.com> + Co-authored-by: shulanbushangshu <102840938+shulanbushangshu@users.noreply.github.com> + Co-authored-by: NorahXiong <103234047+NorahXiong@users.noreply.github.com> + Co-authored-by: liu cui + Co-authored-by: Ryohsuke Mitsudome +* chore(planning_launch): update motion module name (`#1014 `_) +* feat: rename autoware_auto_perception_rviz_plugin to autoware_perception_rviz_plugin (`#1013 `_) +* feat: update rviz layout (`#1004 `_) +* feat(lane_departure_checker): add params for lane departure margin (`#1011 `_) + * add params + * add param for start planner lane departure expansion margin + --------- +* refactor(image_projection_based_fusion): rework params (`#845 `_) +* feat(obstacle_cruise_planner)!: ignore to garze against unknwon objects (`#1009 `_) +* chore(planning_launch): update module name (`#1008 `_) + * chore(planning_launch): update module name + * chore(rviz): update rviz config + * chore(avoidance): update module name + --------- +* feat(motion_velocity_planner): add new motion velocity planning (`#992 `_) +* feat(map_based_prediction): use different time horizon (`#1005 `_) +* feat(behavior_path_planner_common,turn_signal_decider): add turn_signal_remaining_shift_length_threshold (`#1007 `_) + add turn_signal_remaining_shift_length_threshold +* revert(map_based_prediction): use different time horizon (`#967 `_) (`#1006 `_) +* feat(map_based_prediction): use different time horizon (`#967 `_) +* feat(blind_spot): consider time to collision (`#1002 `_) +* feat(object_lanelet_filter): update object_lanelet_filter parameter yaml (`#998 `_) + feat: update object_lanelet_filter parameter +* feat(autoware_launch): add diagnostic graph config for awsim (`#1000 `_) +* fix(rviz): remove StringStampedOverlayDisplay reference (`#1001 `_) +* feat(e2e_simulator.launch): add argument for running the CARLA interface (`#924 `_) +* feat: add diagnostic graph settings (`#991 `_) +* feat(multi_object_tracker): add multi object input config file (`#989 `_) + * feat: add multi-input channel config + * fix: component config + * fix: remove expected interval, add spawn + * fix: missing config, default value + --------- +* feat!(avoidance): make it selectable output debug marker from yaml (`#996 `_) + feat(avoidance): make it selectable output debug marker from yaml +* fix(avoidance): change lateral jerk param (`#995 `_) +* fix(ndt_scan_matchere): improved tpe (`#985 `_) + Improved tpe +* feat(out_of_lane): add option to ignore overlaps in lane changes (`#986 `_) +* feat(map_based_prediction): incorporate crosswalk user history (`#987 `_) +* feat(remaining_dist_eta): add MissionDetailsDisplay plugin rviz configuration (`#963 `_) +* fix: update widget size and position (`#982 `_) +* feat(path_planner): params to adjust hard constraints and path reuse (`#983 `_) +* fix(componet_state_monitor): remove ndt node alive monitoring (`#984 `_) + remove ndt node alive monitoring +* feat(autonomous_emergency_braking): add obstacle velocity estimation for aeb (`#978 `_) + * rebase to awf main + * set debug PC as false + * dictionary + * eliminate duplicate parameter + * eliminate duplicate parameter + --------- +* feat(crosswalk)!: change a hard coding number and set as param (`#977 `_) + * change param +* fix: update traffic topic in autoware.rviz (`#981 `_) +* chore(component_state_monitor): relax pose_estimator_pose timeout (`#979 `_) +* feat(system diags): rename diag of ndt scan matcher (`#973 `_) + rename ndt diag +* fix(avoidance): add target filtering threshold for merging/deviating vehicle (`#974 `_) +* fix(ekf_localizer): updated ekf gate_dist params (`#965 `_) + Updated ekf gate_dist +* fix(lidar_centerpoint): add param file for centerpoint_tiny (`#976 `_) + fix(lidar_centerpoint): add param file +* feat(probabilistic_occupancy_grid_map): add downsample filter option to ogm creation (`#962 `_) + * feat(probabilistic_occupancy_grid_map): add downsample filter option to ogm creation + * chore: do not use pointcloud filter when downsample is true + * Update autoware_launch/config/perception/occupancy_grid_map/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml + Co-authored-by: Yukihiro Saito + --------- + Co-authored-by: Yukihiro Saito +* refactor(centerpoint, pointpainting): rearrange ML model and package params (`#915 `_) + * chore: separate param files + * chore: fix launch + * chore: rearrange param + * style(pre-commit): autofix + * refactor: rearrange param file + * chore: move densification_params + * style(pre-commit): autofix + * fix(centerpoint): align param namespace with pointpainting + * fix: param + * fix: remove build_only from yaml + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(autoware_launch): add centerpoint_sigma param to pointpainting.param.yaml (`#955 `_) + fix: add has_variance to pointpainting.param.yaml +* feat(autonomous_emergency_braking): add params for aeb (`#966 `_) + * add params for aeb + * set collision keep time to be more conservative + --------- +* fix(roi_pointcloud_fusion): add param (`#956 `_) +* refactor(bpp): remove unused params (`#961 `_) +* feat(api): add launch option (`#960 `_) +* feat(dynamic_avoidance): avoid pedestrians (`#958 `_) + new feature +* chore(intersection_occlusion): more increase possible_object_bbox size to ignore small occlusion and ghost stop (`#959 `_) +* feat(obstacle_cruise): change stop lateral margin (`#948 `_) +* refactor(avoidance): unify redundant parameters (`#953 `_) + refactor(avoidance): remove unused parameters +* refactor(avoidance, AbLC): rebuild parameter structure (`#951 `_) + * refactor(avoidance): update yaml + * refactor(AbLC): update yaml + --------- +* chore(intersection_occlusion): increase possible_object_bbox size to ignore small occlusion and ghost stop (`#950 `_) +* fix(tier4_control_component_launch): fix duplicate declaration of controller parameter paths (`#940 `_) +* fix(trajectory_follower): accommodate the parameters of the controllers to the dynamics in the simulator. (`#941 `_) + correct the parameters of the controller. The parameters of the dynamics and the controller are identical after this commit +* feat(avoidance): limit acceleration during avoidance maneuver (`#947 `_) + * feat(avoidance): limit acceleration during avoidance maneuver + * fix(avoidance): tune longitudinal max acceleration + --------- +* chore(ground_segmentation): add tuning param (`#946 `_) +* feat(run_out): maintain stop wall for some seconds (`#944 `_) + update stop wall maintain time to 1 sec +* feat(lane_change): check prepare phase in turn direction lanes (`#943 `_) +* feat(autoware_launch): add centerpoint_sigma param (`#945 `_) + add: centerpoint_sigma.param +* fix(lane_change): collision check for prepare in intersection (`#930 `_) +* feat(start_planner): add path validation check (`#942 `_) + add param +* feat(pose_initilizer): set intial pose directly (`#937 `_) + * feat(pose_initilizer): set intial pose directly + * rename params + --------- +* feat(run_out): add params to exclude obstacles already on the ego's path (`#939 `_) + * add params + * add extra param + --------- +* feat(crosswalk): rename parameter to ignore traffic light (`#919 `_) +* feat(dynamic_obstacle_stop): split the duration buffer parameter in 2 (add/remove) (`#933 `_) +* chore: add option to select graph path depending on running mode (`#938 `_) + chore: add option of using graph path for simulation +* feat: add option to launch mrm handler (`#929 `_) +* feat(run_out): add obstacle types to run out (`#936 `_) + add obstacle types to run out +* feat(run_out_module): new params for run out, add ego cut lane (`#935 `_) + * new params for run out + * rename param + * update description + --------- +* feat: add dummy doors for planning simulator (`#921 `_) +* feat(AEB): add detection range params (`#934 `_) + * feat(AEB): add new params for detection_range + * fix(AEB): fix mistake + --------- +* feat(run_out): adjust parameter (`#931 `_) + chore(run_out): adjust parameter (`#777 `_) + Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> +* refactor(avoidance): update parameter namespace (`#928 `_) +* feat: add a param file of a mrm handler node (`#927 `_) +* feat(dynamic_obstacle_stop): add parameter to ignore unavoidable collisions (`#916 `_) +* fix(avoidance): wait and see objects (`#925 `_) +* refactor(obstacle_cruise_planner): move slow down params to a clear location (`#926 `_) + move slow down params to a clear location +* refactor(avoidance): rename param (`#923 `_) +* feat(crosswalk): increase minimum occlusion size that causes slowdown to 1m (`#909 `_) +* feat: add marker for control's stop reason, false by default (`#912 `_) +* chore(duplicated_node_checker): print duplication name (`#888 `_) +* feat(pointcloud_preprocessor, probabilistic_occupancy_grid_map): enable multi lidar occupancy grid map creation pipeline (`#740 `_) + * add multi lidar pointcloud based ogm creation + * enable sensing launch to control concatenate node + * style(pre-commit): autofix + * refactor : change concatenate node parameter name + * chore: set single lidar ogm to be default + * feat: update multi_lidar_ogm param file + * chore: remove sensing launch changes because it does not needed + * chore: fix multi lidar settings for sample sensor kit + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* chore: change default of low_height_crop filter use (`#918 `_) +* feat(ndt_scan_matcher): added a parameter of sensor points (`#908 `_) + * Added parameters of sensor points + * Added unit + --------- +* feat(obstacle_cruise_planner): enable obstacle cruise's yield function by default (`#917 `_) + enable obstacle cruise's yield function by default +* fix(avoidance): tune safety check params (`#914 `_) +* fix(avoidance): tune lateral margin params (`#913 `_) +* fix(component_state_monitor): change pose_estimator_pose rate (`#910 `_) +* feat(out_of_lane): add cut_beyond_red_traffic_lights parameter (`#885 `_) +* feat(planning_simulator): default use_sim_time arg to scenario_simulation (`#903 `_) +* fix(raw_vehicle_cmd_converter): csv paths are resolved in param.yaml (`#884 `_) +* feat(start_planner): prevent hindering rear vehicles (`#905 `_) + Add params to add extra margin to rear vehicle width +* feat(avoidance): change lateral margin based on if it's parked vehicle (`#894 `_) + * feat(avoidance): change lateral margin based on if it's parked vehicle + * fix(AbLC): update values + --------- +* chore: change max_z of cropbox filter to vehicle_height (`#906 `_) + chore: change max_z of cropbox filter to vehicle_heigh +* fix: the parameter name of max_vel (`#907 `_) +* feat: switch to obstacle_cruise_planner (`#765 `_) +* feat: enable autonomous emergency braking (`#764 `_) +* feat: set the max velocity to 15km/h (`#763 `_) +* feat(tier4_localization_component_launch): change the default input pointcloud of localization into the concatenated pointcloud (`#899 `_) + * Make concat pointcloud default + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(start_planner): add object_types_to_check_for_path_generation (`#902 `_) + add object_types_to_check_for_path_generation +* chore: update package maintainers for autoware_launch package (`#897 `_) +* revert: feat(autoware_launch): set use_sim_time parameter equal to true when (`#746 `_) (`#901 `_) +* feat(autoware_launch): add argument to enable/disable simulation time (`#886 `_) +* refactor(behavior_path_planner): remove unused drivable area parameters (`#883 `_) +* feat(start_planner): allow lane departure check override (`#893 `_) + new param added +* feat: add is_simulation variable in autoware.launch.xml (`#889 `_) +* feat(avoidance): wait next shift approval until the ego reaches shift length threshold (`#891 `_) + * feat(avoidance): wait next shift approval until the ego reaches shift length threshold + * fix(avoidance): param description + --------- +* feat(rviz): make rviz2 background lighter, lower the contrast (`#887 `_) +* feat(crosswalk): add parameters for occlusion slowdown feature (`#807 `_) +* feat(lane_change): cancel hysteresis (`#844 `_) + * feat(lane_change): cancel hysteresis + * reduce the hysteresis value + --------- +* feat(autoware_launch): set use_sim_time parameter equal to true when … (`#746 `_) +* fix: recovery default parameter (`#882 `_) +* feat(goal_planner): change pull over path candidate priority with soft and hard margins (`#874 `_) +* feat(traffic_light_arbiter): add parameter of signal match validator (`#879 `_) +* feat(strat_planner): add a prepare time for blinker before taking action for approval (`#881 `_) +* feat(avoidance): use free steer policy for safety check (`#865 `_) +* fix(system_error_monitor): changed settings of /autoware/localization/performance_monitoring (`#877 `_) + Fixed settings of /autoware/localization/performance_monitoring +* fix(start_planner): fix safety_check_time_horizon (`#875 `_) +* chore(start_planner): remove unused parameter (`#878 `_) +* fix(planning_validator): add missing params (`#876 `_) +* feat(tier4_control_launch): disable the trajectory extension (`#866 `_) + disable the trajectory extending for terminal yaw control +* refactor(blind_spot): find first_conflicting_lane just as intersection module (`#873 `_) + temp +* feat: define common max_vel (`#870 `_) +* feat(motion_velocity_smoother): increase engage_acceleration (`#736 `_) + * feat(motion_velocity_smoother): increase engage_acceleration + * Update autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml +* fix(localization): add ar tag based localizer param (`#871 `_) + Added ar_tag_based_localizer.param.yaml +* chore(crosswalk): change LATER param (`#868 `_) + crosswalk/change-LATER-param +* feat(planning_simulator): use fit_target=vector_map in planning_simulator (`#859 `_) + * Added fit_target + * Fixed arg name + --------- +* feat(goal_planne): check objects within the area between ego edge and boudary of pull_over_lanes (`#867 `_) +* fix(log-messages): reduce excessive log messages (`#760 `_) +* fix(avoidance): tuning shiftable ratio & deviation param (`#869 `_) +* chore(radar_object_tracker): move radar object tracker param to yaml (`#838 `_) + chore: move radar object tracker param to yaml +* feat(pid_longitudinal_controller): adjust slope compensation parameters (`#585 `_) +* feat(map based prediction, crosswalk)!: transplantation of pedestrians' behavior prediction against green signal (`#860 `_) + pedestrians' intention estimation feature against the green signal +* fix(autoware_launch): remove use_pointcloud_container flag completely (`#864 `_) +* chore(intersection): target type param (`#851 `_) +* feat: remove use_pointcloud_container (`#806 `_) + * feat!: remove use_pointcloud_container + * style(pre-commit): autofix + * remove unnecessary files + * revert: revert change in declaration of sample vehicle and sensor_kit + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(start/goal_planner): remove unused param and update time horizon for goal planner's safety check (`#863 `_) + * remove unused param + * update safety check time horizon + --------- +* chore(ndt_scan_matcher): rename config path (`#854 `_) + * chore(ndt_scan_matcher): rename config path + * rename path + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* refactor(rviz): update the class name and turn signal color (`#855 `_) +* feat(intersection): use different expected deceleration for bike/car (`#852 `_) +* chore(planning/control/vehicle): declare ROS params in yaml files (`#833 `_) + * update yaml +* chore(map): rework parameters of map (`#843 `_) + * Added reference to launch parameters to yaml files of map/ + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(lidar_centerpoint): remove build_only param from param.yaml (`#856 `_) +* refactor(pose_initializer): rework parameters (`#853 `_) +* feat(traffic_light_recognition): add tlr args in tier4_perception_component.launch.xml (`#840 `_) + * feat(traffic_light_recognition): add tlr args in tier4_perception_component.launch.xml + * fix dfault value of fusion_only to false + * fix arg passing way + --------- +* feat(behavior_path_sampling_planner): add sampling based planner to behavior path planner (`#810 `_) + * Add sampling based planner params + * update keep_last param + * change priority of sampling based planner + * Set parameters for frenet planner + * changes for testing + * change curvature weight for testing + * tuning params + * tuning + * for integ w/ other modules + * add support for soft constraints weight reconfig + * rebase + * temp + * update default params + * Tune params + * Set defaults back to normal + * fix name of ablc + * formatting fix + * set verbose to false + --------- +* refactor(map_tf_generator): rework parameters (`#835 `_) +* fix(pointpainting): update parameter (`#850 `_) +* chore(lidar_centerpoint): rework parameters (`#822 `_) + * chore(lidar_centerpoint): use config + * fix: remove build_only param + --------- + Co-authored-by: Kenzo Lobos Tsunekawa +* refactor(ekf_localizer): rework parameters (`#847 `_) + refactor: Add the classification names to yaml file +* feat(obstacle_cruise_planner): yield function for ocp (`#837 `_) + * add params for yield + * param name change + * add params + * refactoring + * fix typo, tuning + * update parameters + * delete unused param + * set cruise planner as default for testing + * add param for stopped obj speed threshold + * change back param + * set default false + --------- +* fix(planning_launch): align parameters to real vehicle (`#848 `_) + update param +* feat(map_based_prediction): consider crosswalks signals (`#849 `_) + add param +* chore(image_projection_based_fusion): rework parameters (`#824 `_) + chore(image_projection_based_fusion): use config +* feat: update rviz splash and vehicle UI display (`#836 `_) +* feat(detection): add container option (`#834 `_) + feat: use pointcloud_container +* chore(twist2accel): rework parameters (`#842 `_) + Added twist2accel.param.yaml +* refactor(ndt_scan_matcher): hierarchize parameters (`#830 `_) + * refactor(ndt_scan_matcher): hierarchize parameters + * add new lines + --------- +* fix(autoware_launch): add config file (`#829 `_) + * fix(autoware_launch): add config file + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* refactor(map_projection_loader): rework parameters (`#839 `_) + * Added launch argument map_projection_loader_param_path to tier4_map_component.launch.xml + Copied map_projection_loader.launch.xml from universe + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* chore(object_velocity_splitter): rework parameters (`#820 `_) + chore(object_velocity_splitter): add config +* feat(autoware_launch): set default vehicle/sensor models to sample ones (`#768 `_) +* chore(ground_segmentation): add default params (`#831 `_) + Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> +* feat(start_planner): add collision check distances for shift and geometric pull out (`#832 `_) + * Add collision check distances for shift and geometric pull out + --------- +* refactor(tier4_map_lcomponent): use map.launch.xml instead of map.launch.py (`#826 `_) +* fix(tracking_object_merger): fix bug and rework parameters (`#823 `_) + fix(tracking_object_merger): fix bug and use param file +* refactor(ndt_scan_matcher): rename de-grounded (`#827 `_) + * refactor(ndt_scan_matcher): rename de-grounded + * fix value + --------- +* chore(object_range_splitter): rework parameters (`#821 `_) + * chore(object_range_splitter): add config + * revert change + --------- +* feat(intersection): publish and visualize the reason for dangerous situation to blame past detection fault retrospectively (`#828 `_) +* fix(avoidance): change return dead line param (`#814 `_) +* feat(avoidance): add new flag to use freespace in avoidance module (`#818 `_) +* refactor(system_error_monitor): rename localization_accuracy (`#605 `_) + refactor: Rename localization_accuracy + to localization_error_ellipse +* fix(tracking_object_merger): fix unknown is not associated problem (`#825 `_) + fix: unknown is not associated problem +* feat(crosswalk)!: improve stuck prevention on crosswalk (`#816 `_) + * change a param definition +* feat(start_planner): change collision_check_distance_from_end to shorten back distance (`#757 `_)" (`#813 `_) + Revert "feat(start_planner): revert change collision_check_distance_from_end to shorten back distance (`#757 `_)" + This reverts commit 96f2f18d23ba829804415135b241065ecf53b13d. +* fix(ndt_scan_matcher): fix type of critical_upper_bound_exe_time_ms (`#819 `_) + * fix type + * fix order + --------- +* fix(avoidance): decrease velocity threshold for avoidance target objects (`#817 `_) +* fix(vehicle_launch): add raw_vehicle_cmd_converter parameter file (`#812 `_) +* chore(detection_by_tracker): organize parameter structure (`#811 `_) +* refactor(run_out): reorganize the parameter (`#784 `_) + * chore(run_out): reorganize the parameter + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* chore(intersection): align param to robotaxi (`#809 `_) +* feat(goal_planner): expand pull over lanes for detection area of path generation collision check (`#808 `_) +* chore(pointcloud_container): move glog_component to autoware_launch (`#805 `_) +* feat(planning): add enable_all_modules_auto_mode argument to launch files for planning modules (`#798 `_) + * Add auto mode setting for all modules +* chore(planning): change params to vehicle tested values (`#797 `_) + change params to vehicle tested values +* feat(map_based_prediction): use acc for map prediction (`#788 `_) + * add param to toggle on and off acc consideration + * add params + * set default to true for evaluator testing + * set back to false default + --------- +* feat: always separate lidar preprocessing from pointcloud_container (`#796 `_) + * feat!: replace use_pointcloud_container + * change default value + * remove from planning + * revert: revert change in planning.launch + * revert: revert rename of use_pointcloud_container + * revert: revert pointcloud_container launch + * style(pre-commit): autofix + * feat: move glog to pointcloud_container.launch.py + * revert: revert unnecessary change + * revert: revert glog porting + * fix: fix comment in localization launch + * style(pre-commit): autofix + * remove pointcloud_container_name from localization launcher + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(surround_obstacle_checker): use xx1 params (`#800 `_) +* chore(pointcloud_container): fix output log from screen to both (`#804 `_) +* feat(start_planner): enable shift path lane departure check (`#803 `_) + enable shift path lane departure check in start planner +* feat(intersection): consider 1st/2nd pass judge line (`#792 `_) +* chore: update roi_cluster_fusion default param (`#802 `_) +* feat(rviz): add marker to show bpp internal state (`#801 `_) +* fix(AbLC): fix module name inconsistency (`#795 `_) +* feat(avoidance/goal_planner): execute avoidance and pull over simultaneously (`#782 `_) +* fix: change the way to disable surround_obstacle_checker (`#794 `_) +* fix(image_projection_based_fusion): add image_porojection_based_fusion params (`#789 `_) + add image_porojection_based_fusion params +* feat(mpc): add parameter for debug trajectory publisher (`#790 `_) +* refactor(ekf_localizer): add Simple1DFilter params to parameter file (`#710 `_) + * feat(ekf_localizer): Add Simple1DFilter params to parameter file + * Update autoware_launch/config/localization/ekf_localizer.param.yaml + --------- + Co-authored-by: Kento Yabuuchi +* feat(start_planner): shorten max backward distance (`#734 `_) + Update start_planner.param.yaml +* feat(multi_object_tracker): fix typo in param name and change default value (`#785 `_) + * fix(multi_object_tracker): fix typo in param name + * feat: update default param + --------- +* chore(crosswalk): change params (`#780 `_) + * change params +* fix(intersection): fix bugs (`#781 `_) +* feat(start_planner): define collision check margin as list (`#770 `_) + * Update collision check margins in start planner configuration + --------- +* feat(ekf_localizer): add publish_tf arg (`#772 `_) +* feat(start_planner): keep distance against front objects (`#766 `_) + Add collision check margin from front object +* feat: tune parameters for optimization path planning (`#774 `_) + * feat: tune parameters for optimization path planning + * disable warm start + * Update autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml + --------- +* feat(surround_obstacle_checker): disable the surround obstacle checker (`#685 `_) +* fix(rviz): hide traffic light regulatory element id (`#777 `_) +* feat(behavior_velocity_planner): add new 'dynamic_obstacle_stop' module (`#730 `_) +* fix(pointpainting): update parameter structure (`#778 `_) + * fix(pointpainting): update parameter structure + * update roi_sync.param.yaml + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(lane_change): set lane change parameters to real vehicle environment (`#761 `_) +* feat: tune dynamic avoidance parameters with the real vehicle (`#775 `_) +* feat: add behavior_output_path_interval in behavior_velocity_planner (`#773 `_) +* refactor(ndt_scan_matcher, map_loader): remove unused parameters (`#769 `_) + Removed unused parameters +* feat: add parameters to avoid sudden steering in dynamic avoidance (`#756 `_) +* feat(autoware_launch): update traffic light recognition models (`#752 `_) + * fix: update model names + * fix: argument name + * Update autoware_launch/launch/components/tier4_perception_component.launch.xml + * fix: model name + * fix: add model path + * Update autoware_launch/launch/components/tier4_perception_component.launch.xml + --------- + Co-authored-by: Yusuke Muramatsu + Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> +* feat: make crosswalk decision more aggressive towards the real world's driving (`#762 `_) +* feat(map_based_prediction): map prediction with acc constraints (`#759 `_) + * Add params for acceleration constraints for map_based_prediction + * add new param + * tune params + * add parameter to switch on and off constraints check + * improve comment + --------- +* feat(obstacle_stop_planner): change stop distance after goal (`#758 `_) + * feat(obstacle_stop/cruise): change stop distance after goal + * Update autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml + --------- +* fix(avoidance): apply params used in xx1 vehicle (`#751 `_) + * fix(avoidance): use xx1 params + * fix(avoidance): expand safety check polygon lateral margin + --------- +* refactor(behavior_path_planner): rename parameter "extra_arc_length" to "arc_length_range" (`#755 `_) +* feat(start_planner): revert change collision_check_distance_from_end to shorten back distance (`#757 `_) + Revert "feat(start_planner): change collision_check_distance_from_end to shorten back distance" + This reverts commit 680fb05e9bebdff6cf2c9734631cb4e949d7c499. +* feat(start_planner): change collision_check_distance_from_end to shorten back distance ## Description (`#754 `_) + feat(start_planner): change collision_check_distance_from_end to shorten back distance +* feat: add stopped_object.max_object_vel in dynamic_avoidance (`#753 `_) +* revert: "fix(avoidance): shorten the parameter (`#745 `_)" (`#750 `_) + revert "fix(avoidance): shorten the parameter (`#745 `_)" + This reverts commit 024254c82f2687deddfadba716afe0f2b8a3a03c. +* feat: run_out does not plan to stop when there is enough time for stopping (`#749 `_) +* feat(avoidance): enable avoidance for objects that stop longer time than thresh (`#743 `_) +* feat(avoidance): enable avoidance for objects that stop longer time than thresh (`#747 `_) +* feat(intersection): disable stuck detection against private lane (`#744 `_) +* fix(avoidance): shorten the parameter (`#745 `_) +* feat(blind_spot): consider opposite adjacent lane for wrong vehicles (`#695 `_) +* feat(run_out)!: ignore the collision points on crosswalk (`#737 `_) + suppress on crosswalk +* fix(intersection): generate yield stuck detect area from multiple lanes (`#742 `_) +* refactor(autoware_launch): remove use_experimental_lane_change_function (`#741 `_) +* chore(image_projection_based_fusion): add param (`#739 `_) + * chore(image_projection_based_fusion): add param + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(crosswalk): ignore predicted path going across the crosswalk (`#733 `_) +* feat(rviz_config): add objects of interest marker (`#738 `_) +* refactor(localization_component_launch): rename lidar topic (`#722 `_) + rename lidar topic + Co-authored-by: yamato-ando +* feat(multi_object_tracker): update tracker parameter yaml (`#732 `_) + * add multi_object_tracker node param + * add additional node parameters for future update + * style(pre-commit): autofix + * fix default value + * update simulator component launch + * feat: update multi_object_tracker node param + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(crosswalk): fix inappropriate sync (`#731 `_) + fix in-appropriate sync +* chore(crosswalk): sync a config file to the univese one (`#729 `_) + update comment, by sync to the univese one +* feat(obstacle_cruise_planner): add slow down acc and jerk params (`#726 `_) + Add slow down acc and jerk params +* fix(traffic_light): stop if the traffic light signal timed out (`#727 `_) +* fix(multi_object_tracker): fix psim launcher related to tracking launch changes (`#724 `_) + * add multi_object_tracker node param + * add additional node parameters for future update + * style(pre-commit): autofix + * fix default value + * update simulator component launch + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(start_planner): add surround moving obstacle check (`#723 `_) + update start_planner.param.yaml +* feat: add polygon_generation_method in dynamic_avoidance (`#715 `_) +* feat(rviz): fix perception debug topics in Rviz (`#721 `_) + fix perception debug topics in Rviz +* feat(component_state_monitor): monitor traffic light recognition output (`#720 `_) +* refactor(start_planner): refactor debug and safety check logic (`#719 `_) + refactor(start_planner): refactor debug parameters + This commit removes the `verbose` parameter under `start_planner` and introduces a new `debug` section. The newly added `debug` section includes a `print_debug_info` parameter, set to false by default. This change provides a more structured way to handle debugging configurations for the start planner. +* refactor(multi_object_tracker): add multi_object_tracker node param (`#718 `_) + * add multi_object_tracker node param + * add additional node parameters for future update + * style(pre-commit): autofix + * fix default value + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* chore(obstacle_cruise)!: remove unused params (`#716 `_) + chore!: remove unused params +* refactor(intersection): rename param, update doc (`#708 `_) +* feat(avoidance): keep stopping until all shift lines are registered (`#699 `_) +* fix(crosswalk): don't stop in front of the crosswalk if vehicle stuck in intersection (`#714 `_) +* feat: add several min_object_vel in dynamic_avoidance (`#707 `_) +* feat: disable obstacle avoidance debug marker for optimization (`#711 `_) + feat: disable obstacle avoidance debug marker +* feat(avoidance): configurable object type for safety check (`#709 `_) +* feat: add parameters for the front object decision in dynamic_avoidance module (`#706 `_) +* feat(pid_longitudinal_controller): error integration on vehicle takeoff (`#698 `_) + * add parameter for PID integration time threshold + * add param to enable or disable low speed error integration + --------- +* feat(run_out): add parameter to decide whether to use the object's velocity (`#704 `_) +* feat(goal_planenr): enable safety check (`#705 `_) +* feat(goal_planner): safer safety checker (`#701 `_) + * feat(goal_planner): safer safety checker + fix + fix + fix + fix + * disable safety check + --------- +* feat(map_based_prediction): consider only routable neighbours for lane change (`#703 `_) +* feat(avoidance): add new parameter for target object filtering (`#668 `_) +* feat(start_planner): enable safety check for start planner (`#702 `_) + Enable safety check feature for start planner +* feat(goal_planner): add time hysteresis to keep unsafe (`#700 `_) + feat(goal_planner): add tiem hysteresis to keep unsafe +* fix(start_planner): disbale verbose flag to false in start_planner.param.yaml (`#696 `_) + Change verbose flag to false in start_planner.param.yaml +* refactor(start_planner): add verbose parameter for debug print (`#693 `_) + Add verbose option to start planner parameters +* feat(component_state_monitor): monitor pose_estimator output (`#692 `_) +* fix(lane_change): regulate at the traffic light (`#673 `_) +* feat: enable and tune drivable area expansion (`#689 `_) + enable drivable area expansion +* feat: lane_departure_checker with curbstones (`#687 `_) +* feat(out_of_lane): more stable decisions (`#612 `_) +* fix(avoidance): prevent sudden steering at yield maneuver (`#690 `_) +* feat(radar_object_clustering): move radar object clustering params to autoware_launch (`#672 `_) + * add radar object clustering param path + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(detected_object_validation): add param (`#669 `_) + * fix(detected_object_validation): add param + * fix: change to 2d validator use + --------- +* feat: add motion_velocity_smoother's virtual wall in rviz (`#684 `_) +* feat(duplicated_node_checker): enable duplicated_node_checker in simulation (`#686 `_) + Enable duplicated node checker in planning + simulation +* feat(obstacle_cruise_planner): use obstacle velocity based obstacle parameters (`#681 `_) + * add moving parameters for testing + * param tuning for tests + * wip params for velocity-based obscruise planner + * add different values for debugging + * set hysteresis-based obstacle moving classification + * set params to match previous values + * eliminate pedestrian mention + --------- +* fix(perception): add detection_by_tracker param file (`#676 `_) +* feat: enable the run_out module (`#683 `_) + feat: enable run_out +* refactor(launch): add new option to select planning preset (`#680 `_) + * chore(config): remove behavior launch modules + * refactor(config): add preset yaml file + * refactor(launch): add new option to select planning preset + * refactor(config): remove unused params + --------- +* feat(intersection): rectify initial accel/velocity profile in ego velocity profile (`#677 `_) + feat(intersection): rectify smoothed velocity +* chore(tier4_planning_launch): add costmap generator config (`#679 `_) +* feat(ndt_scan_matcher): add parameters of real-time covariance estimation (`#643 `_) + * add covariance_estimation + * fix + * fix + * fix: parameter names and explanations + * fix: A parameter that I forgot to add + * fix: remove white space + * fix: remove white spaces + --------- +* feat(ekf_localizer, system_error_monitor): system_error_monitor handles ekf diags (`#674 `_) + * fix(ekf_localizer): change default parameter for no update count + * update system_error_monitor + --------- +* chore(goal_planner): fix typo (`#670 `_) +* refactor(planning): update args name (`#675 `_) +* refactor(planning): update args name (`#671 `_) +* feat(vehicle_cmd_gate): improve debug marker activation (`#659 `_) + * feat(vehicle_cmd_gate): add filter activated threshold + * feat: update parameter + * feat: add condition for filtering marker + --------- +* feat(intersection): add ttc debug plotter (`#666 `_) +* feat(avoidance): return original lane by red traffic light (`#663 `_) +* refactor(avoidance): cleanup force avoidance params (`#667 `_) +* feat(radar_object_tracker): update and add parameter about radar_object_tracker for far away perecption (`#658 `_) + update and add parameter about radar_object_tracker for far away detection +* feat(behavior_path_planner): add traffic light recognition timeout threshold (`#662 `_) +* fix(lane_change): separate backward buffer for blocking object (`#661 `_) +* fix(rviz2): update traffic_light/debug/rois topic name (`#642 `_) +* feat(AEB): implement parameterized prediction time horizon and interval (`#657 `_) +* chore(rviz): hide interseciton area polygon as default (`#655 `_) +* feat: add use_conservative_buffer_longitudinal in avoidance (`#656 `_) +* feat(intersection): check path margin for overshoot vehicles on red light (`#654 `_) +* feat(rviz): add sensing/perception debug topics (`#653 `_) + * add perception debug topics + * add sensing debug topics + * change color of dbt to orange + --------- +* perf(elastic_band_smoother): increase lateral replan threshold (`#652 `_) +* feat(behavior_velocity_run_out): ignore momentary detection caused by false positive (`#647 `_) + * feat(behavior_velocity_run_out): ignore momentary detection caused by false positive + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(duplicated_node_checker): add duplicated node names to msg (`#651 `_) + add duplicated node names to msg +* feat(intersection): use own max acc/jerk param (`#650 `_) +* feat(duplicated_node_checker): disable duplicated_node_checker (`#649 `_) + * disable duplicated_node_checker + * enable duplicated_node_checker + --------- +* feat(intersection): timeout static occlusion with traffic light (`#646 `_) +* feat(map_based_prediction): enable to control lateral path convergence time (`#637 `_) + enable to control lateral path convergence time +* feat(planner_manager): limit iteration number by parameter (`#645 `_) +* feat(avoidance): add paramenters for dynamic detection area (`#634 `_) +* fix(intersection): lower state_transit_margi_time to 0 (`#638 `_) +* fix(drivable_area_expansion): disable by default (`#639 `_) +* fix(tier4_simulator_component): add lacked param path (`#640 `_) +* feat(lane_change): change stuck velocity to 0.5 (`#636 `_) +* feat(behavior_path_planner): curvature based drivable area expansion (`#632 `_) + * Modify parameters for curvature based dynamic drivable area expansion + * Add parameter to enable/disable printing the runtime + * Add smoothing.extra_arc_length param + --------- +* add tracking object merger for long range radar sensor (`#627 `_) + * add tracking object merger paramters + * fix typo + --------- +* feat(lane_change): add rss paramas for stuck (`#633 `_) +* feat(intersection): ignore decelerating vehicle on amber traffic light (`#635 `_) + * feat(intersection): ignore decelerating vehicle on amber traffic light + * tuning + --------- +* feat(duplicated_node_checker): add duplicated_node_checker (`#631 `_) + * add duplicated_node_checker + * add arguments for duplicated node checker, required by new PR on the universe + * fix type + * add config inside launch + * style(pre-commit): autofix + * the default should be set to 10 + --------- + Co-authored-by: Owen-Liuyuxuan + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(autoware_launch): add yield_stuck.distance_thr in intersection (`#628 `_) + * feat(autoware_launch): add yield_stuck.distance_thr in intersection + * use turn_direction + * update param + --------- +* feat(ndt_scan_matcher): added a new parameter "n_startup_trials" (`#602 `_) + * Added a new parameter "n_startup_trials" + * Changed default `n_startup_trials` to 20 + --------- +* chore(intersection): parameterize stuck vehicle detection turn_direction (`#630 `_) +* feat(avoidance): check if the avoidance path is in drivable area (`#584 `_) + * feat(avoidance): check if the avoidance path is in drivable area + * refactor(avoidance): remove unused param + --------- +* feat(rtc_auto_mode_manager): eliminate rtc auto mode manager (`#625 `_) + * disable RTC + * remove rtc auto mode manager + * fix file name + --------- +* feat(intersection): yield initially on green light (`#623 `_) +* feat(lane_change): separate execution and cancel safety check param (`#626 `_) +* feat(obstacle_cruise_planner): obstacle type dependent slow down for obstacle cruise planner param change (`#621 `_) + * set obstacle type dependant params + * Set obstacle cruise planner as default to test changes + * Change back testing parameters to default + --------- +* feat(intersection)!: disable the exception behavior in the private areas (`#622 `_) + feat: add enabling param for the private areas +* refactor(avoidance): use safety check parameter struct (`#617 `_) +* fix: add param file for obstacle pointcloud based validator (`#606 `_) + * fix: add param file for obstacle pointcloud based validator + * fix: tier4_perception launch + --------- +* feat(intersection): ignore occlusion beyond high curvature point (`#619 `_) +* perf(ndt_scan_matcher): changed default `initial_estimate_particles_num` to 200 (`#618 `_) + Changed initial_estimate_particles_num to 200 +* feat(intersection): aggressively peek into attention area if traffic light does not exist (`#611 `_) +* feat(autoware_launch): dynamic timeout for no intention to walk decision in crosswalk (`#610 `_) + * feat(autoware_launch): dynamic timeout for no intention to walk decision in crosswalk + * update config + * revert a parg of config + --------- +* fix(autoware_launch): improve stop decision in out_of_lane (`#615 `_) +* feat(localization_error_monitor): update parameter (`#614 `_) +* feat(behavior_path_planner): update rss param (`#604 `_) + update param +* feat(lane_change): expand target lanes for object filtering (`#601 `_) +* feat(autoware_launch): add predicted_path_checker package (`#385 `_) +* refactor(ndt_scan_matcher): modified ndt_scan_matcher.param.yaml to match with the one in universe (`#596 `_) + Modified ndt_scan_matcher.param.yaml to match with the one in universe +* feat(intersection): use planned velocity from upstream modules (`#597 `_) +* feat(goal_planner): prioritize goals before objects to avoid (`#594 `_) + * feat(goal_planner): extend goal search are + * feat(goal_planner): prioritize goals before objects to avoid + --------- +* feat(start_planner): change th_distance_to_middle_of_the_road 0.5 (`#599 `_) +* feat(start_planner): enable divide_pull_out_path (`#600 `_) +* feat(goal_planner): change minimum_request_length 0.0 (`#598 `_) +* feat(goal_planner): extend goal search area (`#592 `_) + feat(goal_planner): extend goal search are +* feat(autoware_launch): add max_obstacle_vel in dynamic_avoidance (`#595 `_) +* feat: add system monitor param file for awsim (`#568 `_) + * feat: add system monitor param file for awsim + * feat: use system_error_monitor.awsim.param in e2e_simulator.launch + --------- +* feat(autoware_launch): move dynamic_avoidance last (`#593 `_) +* feat(ndt_scan_matcher): adding exe time parameter (`#559 `_) + add critical_upper_bound_exe_time_ms for ndt +* feat(lane_change): enable lane change in crosswalk/intersection if ego vehicle gets stuck (`#590 `_) +* feat(goal_planner): sort goal candidates priority by weighted distance (`#591 `_) +* feat(intersection): ensure-temporal-stop-before-upcoming-lane (`#578 `_) +* feat(obstacle_cruise_planner): add parameters for a new feature (`#581 `_) + * feat: add parameters for the feature "cosider-current-ego-pose" + * set the params to be merged. + use stop planner as cruise planner type (conventional setting) + polygon expansion in obstacle_cruise_planner is true + --------- +* feat(autoware_launch): add traffic protected level for amber color in intersection (`#588 `_) + * feat(autoware_launch): add traffic protected level for amber color in intersection + * update + * update + --------- +* feat(autoware_launch): add stop_distance_threshold in merge_from_private (`#587 `_) +* feat(autoware_launch): add check_footprint_inside_lanes in mission_planner (`#589 `_) +* chore(motion_velocity_smoother): add enable curve filtering param (`#580 `_) +* fix(start/goal_planner): resample path and make params (`#586 `_) +* fix(motion_velocity_smoother): change curvature calculation distance parameter (`#556 `_) +* feat(planning_launch): add config for regulate lane change (`#582 `_) +* refactor(ndt_scan_matcher): match ndt_scan_matcher.param.yaml (`#583 `_) + * Added ndt_base_link parameter in ndt_scan_matcher.param.yaml + Deleted neighborhood_search_mathod paramter in ndt_scan_matcher.param.yaml + * Copy-pasted the ndt_scan_matcher.param.yaml from universe + * Correct spelling + --------- +* feat: prevent start planner execution in the middle of the road (`#579 `_) + * start planner:new param: dist th to middle of road + * refactor param order + --------- +* feat(vehicle_cmd_gate): add steering angle and rate filter (`#576 `_) +* feat(perception): add data_path argument to launch file (`#577 `_) + * feat(perception): add data_path argument to launch file + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(ekf_localizer): ignore dead band of velocity sensor (`#574 `_) + * feat(ekf_localizer): ignore dead band of velocity sensor + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(ekf_lolicazer): add diagnostics parameters (`#554 `_) + * feat(ekf_lolicazer): add diagnostics parameters + * remote param + --------- + Co-authored-by: yamato-ando +* fix(autoware_launch): add radar lanelet filter parameter (`#566 `_) +* refactor(perception): rearrange clustering pipeline parameters (`#567 `_) + * fix: use downsample before compare map + * fix: remove downsample after compare map + * fix: add low range crop filter param + * chore: refactor + * chore: typo + --------- +* feat(behavior_path_planner): set param ignore_object_velocity_threshold (`#573 `_) + set param ignore_object_velocity_threshold +* fix(behavior_path_planner): change safety check default disable (`#572 `_) + * change safety check default disable + * add warning message + --------- +* feat(behavior_path_planner): update start_goal_planner's parameter (`#571 `_) + update start_goal_planner's parameter +* fix(behavior_path_planner): define hysteresis_factor_expand_rate (`#569 `_) + * hysteresis_factor_expand_rate + * style(pre-commit): autofix + * add hysteresis_factor_expand_rate in SafetyCheckParams + * delete setting files + * revert unnecessary change + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(goal_planner): add options of occupancy grid map to use only for goal search (`#563 `_) +* feat(tier4_system_rviz_plugin): add package (`#564 `_) + * feat(tier4_system_rviz_plugin): add package + * fix + --------- +* chore(localization_error_monitor): update default parameter (`#565 `_) +* feat(goal_planner): use only static objects in pull over lanes to path generation (`#562 `_) +* feat(autoware_launch): add approaching stop on curve in obstacle cruise planner (`#560 `_) + * feat(autoware_launch): add approaching stop on curve in obstacle cruise planner + * update config + --------- +* fix(autoware.rviz): remove initial_pose_button_panel (`#561 `_) + Co-authored-by: yamato-ando +* feat(autoware_launch): additional margin parameters in surround obstacle checker (`#557 `_) + feat(autoware_launch): additional margin parameters in surround ostacle checker +* feat(ndt_scan_matcher): add param lidar_topic_timeout_sec (`#540 `_) + Co-authored-by: yamato-ando +* feat(lane_departure_checker): add border types to check (`#549 `_) + update lane_departure_checker.param.yaml +* feat: add traffic light recogition namespace to e2e sim launch (`#555 `_) +* feat(operation_transition_mannager): add param enable_engage_on_driving (`#553 `_) +* feat(goal_planner): do not use minimum_request_length for fixed goal … (`#546 `_) + feat(goal_planner): do not use minimum_request_length for fixed goal planner +* feat(goal_planner): set ignore_distance_from_lane_start 0.0 (`#552 `_) +* feat(behavior_path_planner): add safety check against dynamic objects for start/goal planner (`#550 `_) + add params for safety check +* feat(out_of_lane): add min_assumed_velocity parameter (`#548 `_) +* feat(behavior_path_planner): add path resampling interval param (`#522 `_) +* feat(interface): add new option `keep_last` (`#543 `_) + feat(planner_manager): keep last module +* chore(rviz_config): add localization debug config (`#544 `_) +* fix(control_validator): default false for publishing diag and display terminal (`#545 `_) + default false for publishing diag and display terminal +* feat(autoware_launch): enable emergency handling when resource monitoring state becomes error (`#542 `_) +* chore(rviz_config): add debug marker group (`#541 `_) +* feat(autoware_launch): remove polygon_generation_method from dynamic_avoidance (`#539 `_) +* feat(intersection): strict definition of stuck vehicle detection area (`#532 `_) +* feat(intersection): suppress intersection occlusion chattering (`#533 `_) +* feat(autoware_launch): add no stop decision parameters in crosswalk (`#537 `_) +* chore: add default args for TLR models (`#538 `_) +* feat(autoware_launch): add max_crosswalk_user_delta_yaw_threshold_for_lanelet in map_based_prediction (`#536 `_) +* feat(autoware_launch): add min_longitudinal_polygon_margin and use object_path_base in dynamic_avoidance (`#534 `_) +* feat(autoware_launch): set larger max_area for pedestrian with umbrella (`#535 `_) + set larger max_area for pedestrian with umbrella +* feat(avoidance): flexible avoidance safety check param (`#529 `_) +* feat(avoidance): add time series hysteresis (`#530 `_) +* refactor(map_based_prediction): update prediction yaml file (`#531 `_) + update prediction yaml file +* feat(autoware_launch): add suppress_sudden_obstacle_stop in obstacle_cruise_planner (`#525 `_) + * feat(autoware_launch): add suppress_sudden_obstacle_stop in obstacle_cruise_planner + * update + --------- +* fix(smoother): fix smoother jerk weight params (`#528 `_) +* fix(avoidance): avoidance shift line processing bug (`#527 `_) + fix(avoidance): safety check chattering +* feat(autoware_launch): add hold stop threshold in obstacle_cruise_planner (`#524 `_) + * feat(autoware_launch): add hold stop threshold in obstacle_cruise_planner + * update + --------- +* refactor(safety_check): use safety check common param struct (`#526 `_) +* fix(freespace_planner): fixed by adding parameters of RRTstar algorithm (`#517 `_) + * fix(freespace_planner): add parameters of RRTstar algorithm + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Kyoichi Sugahara +* feat(vehicle_cmd_gate): adaptive filter limit (`#510 `_) + * feat(vehicle_cmd_gate): adaptive filter limit + * update + --------- +* fix(autoware_launch): correct prediction_time_horizon default value (`#523 `_) + correct prediction_time_horizon value +* feat(goal_planner): add extra front margin for collision check considering stopping distance (`#520 `_) + * feat(goal_planner): add extra front margin for collision check considering stopping distance + * object_recognition_collision_check_margin: 0.6 + * rename args and params + * add comments + --------- +* feat(autoware_launch): add use_raw_remote_control_command_input argument (`#460 `_) + * update external_cmd_converter + * update default value + * update argument name + * move enable_cmd_limit_filter argument to param file + * update enable_cmd_filter default value + --------- +* feat(rviz): respawn rviz (`#518 `_) +* feat(merge_from_private): use separate param (`#521 `_) +* feat(start_planner): support freespace pull out (`#514 `_) +* fix(ekf_localizer): fix parameter first capital letter (`#519 `_) +* chore(tier4_simulator_component): add traffic light arbiter param path (`#502 `_) +* feat(control_validator): measure predicted path deviation from trajectory (`#509 `_) + * update launcher + * add config and modify launch file + * style(pre-commit): autofix + * feat(lane_departure_checker): add road_border departure checker (`#511 `_) + add param + * feat(system_error_monitor): check lateral deviation in sim (`#516 `_) + * restore rviz config change + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> +* feat(avoidance): reduce road shoulder margin if lateral distance is not enough to avoid (`#513 `_) +* feat(autoware_launch): add enable_pub_extra_debug_marker in obstacle_avoidance_planner (`#512 `_) +* feat(system_error_monitor): check lateral deviation in sim (`#516 `_) +* feat(lane_departure_checker): add road_border departure checker (`#511 `_) + add param +* feat(autoware_launch): add polygon_generation_method in dynamic_avoidance (`#508 `_) +* feat(avoidance): make it selectable avoidance policy (`#505 `_) +* feat(map_projection_loader): add map_projection_loader (`#483 `_) + feat(map_loader): add map_projection_loader +* feat(tier4_perception_launch): update pointpainting param (`#506 `_) +* feat(autoware_launch): use hatched road markings in dynamic avoidance (`#504 `_) + * feat(autoware_launch): add use_hatched_road_markings in dynamic_avoidance + * add parameters + * update + --------- +* feat(avoidance): enable avoidance cancel (`#476 `_) +* feat(autoware_launch): update dynamic_avoidance parameters (`#503 `_) +* feat(routing_no_drivable_lane_when_module_enabled): add solution for routing no_drivable_lane only when module enabled (`#457 `_) + * feat(routing_no_drivable_lane_when_module_enabled): add proposed solution + * style(pre-commit): autofix + * feat(routing_no_drivable_lane_when_module_enabled): improving comments regarding new parameter + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* refactor(autoware_launch): add an option for filtering and validation (`#479 `_) + * init commit + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(autoware_launch): add cut out parameters for dynamic avoidance (`#500 `_) +* feat(lane_change): remove an unused parameter (`#501 `_) +* feat(autoware_launch): add successive_num_to_exit_dynamic_avoidance_condition in dynamic_avoidance (`#484 `_) +* feat(rviz): add acceleration meter for debugging which is disabled by default (`#499 `_) + * feat: add acceleration meter for debugging, disabled by default; https://github.com/autowarefoundation/autoware.universe/pull/4506 + * not directly setting pixel numbers in rviz for display on screen with various resolutions + --------- + Co-authored-by: Owen-Liuyuxuan +* feat(start_planner): use stop objects in pull out lanes for collision check (`#498 `_) +* fix(object_merger): separate GIoU (`#497 `_) +* feat(autoware_launch): add gradable pass margin in crosswalk (`#496 `_) +* feat(autoware_launch): add pass juge line parameter in crosswalk (`#495 `_) +* feat(autoware_launch): add chattering suppression margin in crosswalk (`#494 `_) +* refactor(traffic_light_arbiter): add traffic_light_arbiter param file (`#489 `_) + Co-authored-by: Kenzo Lobos Tsunekawa +* feat(out_of_lane): add param for the min confidence of a predicted path (`#440 `_) + Co-authored-by: Takayuki Murooka +* feat(autoware_launch): add option of disable_yield_for_new_stopped_object in crosswalk (`#491 `_) +* feat(intersection_occlusion): ignore occlusion behind parked vehicles on the attention lane (`#492 `_) +* feat(autoware_launch): add acc/jerk parameters for stuck vehicle detection in crosswalk (`#487 `_) +* feat(avoidance): add parameter to configurate avoidance return point (`#493 `_) +* feat(intersection): extract occlusion contour as polygon (`#485 `_) +* refactor(tier4_localization_component): input_pointcloud param added (`#480 `_) + * refactor(tier4_localization_component): input_pointcloud param added + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(autoware_launch): add cut_in_object.min_lon_offset_ego_to_object in dynamic avoidance (`#481 `_) + * feat(autoware_launch): add cut_in_object.min_lon_offset_ego_to_object in dynamic avoidance + * update + --------- +* feat(autoware_launch): add enable_debug_info for dynamic_avoidance (`#478 `_) +* feat(path_smoother): add parameters for the replan checker (`#482 `_) +* refactor(avoidance): use common safety checker (`#477 `_) +* refactor(planning_launch): clean stop line parameters (`#475 `_) +* feat(autoware_launch): add dynamic avoidance parameters (`#474 `_) +* perf(path_sampler): tune lateral_deviation_weight for more stable planning (`#455 `_) + Set lateral_deviation_weight 0.1 -> 1.0 +* fix(compare_map_segmentation): add param for skip lower neighbor points comparision option (`#447 `_) + * fix(compare_map_segmentation): add param for check lower neighbor points option + * fix: update param for reduce z distance threshold + * fix: change param type + --------- +* feat(autoware_launch): update pointpainting param (`#473 `_) +* fix(autoware_launch): rename pull over to goal planner (`#472 `_) +* add radar tracker parameter files and settings (`#470 `_) + * add radar tracker parameter files and settings + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* refactor(autoware_launch): add lidar models params (`#450 `_) + * init commit + * add centerpoint params + * remove dupplicated commits + --------- +* feat(avoidance_by_lc): make it possible to configurate flexibly (`#469 `_) + feat(avodiance_by_lc): make it possible to configurate flexibly +* feat(behavior_velocity_planner): add flag to enable auto mode without rtc_auto_mode_manager (`#435 `_) + * add enable_rtc param + * fix typo + * revert change of rviz config + * revert change of rviz config + --------- +* refactor(avoidance): parameterize magic number (`#426 `_) +* feat(avoidance): flexible avoidance path generation (`#454 `_) +* refactor(autoware_launch): add object_merger param files (`#464 `_) + init commit +* chore(autoware_launch): zero margin for outside the drivable area (`#468 `_) +* fix(avoidance): update config to prevent unconfortable deceleration (`#466 `_) +* refactor(autoware_launch): rename crosswalk/walkway parameters (`#459 `_) +* refactor(autoware_launch): add walkway param yaml (`#458 `_) +* fix(tier4_simulator_component): add missing argument (`#465 `_) + update simulator launch component +* fix(obstacle_avoidance_planner): adding missing functionality for stop margin due to out of drivable area (`#438 `_) +* refactor(autoware_launch): add map_based_prediction param file (`#463 `_) + init commit +* feat(planning_launch): add safety check flags for lane change (`#462 `_) +* feat: use `pose_source` and `twist_source` for selecting localization methods (`#442 `_) + * feat: add pose and twist sources args for localization + * removed unnecessary params + * allow only one source + * Move configs to tier4_localization_component.launch.xml + * Remove unnecessary line + * fix comment + --------- +* feat(intersection): add behavior for arrow signal (`#456 `_) +* fix(occlusion_spot): add lacking param (`#452 `_) +* refactor(avoidance): update parameter names (`#453 `_) +* refactor(autoware_launch): add euclidean_clustering params (`#445 `_) + * add euclidean_clustering param + * style(pre-commit): autofix + * update and rearrange comments + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(autoware_launch): update lane change rviz configuration (`#451 `_) + * feat(autoware_launch): update autoware rviz + * update + --------- +* feat(autoware_launch): add disable_stop_for_yield_cancel in crosswalk (`#449 `_) + * feat(autoware_launch): add disable_stop_for_yield_cancel in crosswalk + * update + --------- +* feat(start_planner): add curvature limit for path generation (`#446 `_) + * add param for curvature shift start + * update + * change param + * maximum_curvature: 0.07 + --------- + Co-authored-by: kosuke55 +* feat(avoidance): enable zebra zone avoidance (`#448 `_) +* feat(avoidance): enable to use intersection area (`#443 `_) +* feat(avoidance): consider acceleration during avoidance maneuver (`#436 `_) + feat(avoidance): use improved path shifting logic +* refactor(behavior_path_planner): remove unused config files (`#441 `_) + * refactor(behavior_path_planner): remove unused config files + * refactor(behavior_path_planner): remove unnecessary code + --------- +* feat(avoidance): use intersection areas (`#439 `_) +* refactor(obstacle_avoidance_planner): move the elastic band smoothing to a new package (`#420 `_) +* feat(probabilistic_occupancy_grid_map): add projective raytracing option from scan_origin (`#434 `_) +* feat(behavior_path_planner): shorten the wating time of force avoidance (`#437 `_) +* feat(autoware_launch): add min_obj_lat_offset_to_ego_path in dynamic_avoidance (`#427 `_) +* feat(autoware_launch): add intersection param for wrong direction vehicles (`#394 `_) + add consider_wrong_direction_vehicle param + Co-authored-by: beyza +* feat(avoidance): insert slow down speed (`#429 `_) +* fix(avoidance): don't output new candidate path if there is huge offset between the ego and previous output path (`#431 `_) +* feat(avoidance): extend object ignore section (`#433 `_) + feat(avoidance): increase object ignore section +* feat(start_planner): add option for lane departure (`#432 `_) +* fix(autoware_launch): add missing pose_initializer param (`#430 `_) +* feat(autoware_launch): no slow down against unknown object (`#428 `_) +* feat(avoidance): update avoidance params (`#424 `_) +* fix(behavior_velocity_intersection_module): fix condition of use_stuck_stopline (`#425 `_) +* feat(lane_change): add param for a lateral distance margin where the abort can be performed (`#421 `_) +* refactor(lane_change): add namespace for lane-change-cancel (`#423 `_) + * refactor(lane_change): add namespace for lane-change-cancel + * update + --------- +* refactor(avoidance): rename ununderstandable params (`#422 `_) +* fix(autoware_launch): use experimental lane change function (`#418 `_) +* feat: use vehicle_stop_checker for judging vehicle stop vehicle_cmd_gate (`#417 `_) +* fix(occupancy grid): fix launcher (`#419 `_) + updated yaml +* feat(planning_launch): add parameters for delaying lane change (`#401 `_) +* feat(avoidance): set additional buffer margin independently (`#412 `_) +* revert: "feat(behavior_path_planner): relax longitudinal_velocity_delta_time" (`#415 `_) + Revert "feat(behavior_path_planner): relax longitudinal_velocity_delta_time (`#410 `_)" + This reverts commit e100e566ddae26173e4bc0d1e8aea40022bad658. +* feat(avoidance): enable avoidance for unknown object (`#416 `_) +* feat(autoware_launch): update dynamic avoidance param (`#413 `_) +* chore(probabilistic_occupancy_grid_map): revert map size (`#414 `_) +* refactor(probabilistic_occupancy_grid_map): move param to yaml (`#409 `_) +* feat(avoidance): avoid non car-like object (pedestrian, bicycle, motorcycle) (`#408 `_) + feat(avoidance): avoid non vehicle object +* feat(behavior_path_planner): relax longitudinal_velocity_delta_time (`#410 `_) +* feat(yabloc): add camera and vector map localization (`#393 `_) + * add yabloc_localization_component.launch.xml + * add pose_initializer.logging_simulator.yabloc.param.yaml + * add yabloc params + * add graph_segment.param.yaml + * integrate yabloc_loc_launch into tier_loc_launch + * fix some config files + * add conditional branch for yabloc + * add sample config for yabloc + * style(pre-commit): autofix + * removed some obsolete parameters + * style(pre-commit): autofix + * removed is_swap_mode from yabloc config + * rename AbstParaticleFilter in config files + * fixed typo + * removed optional param files + * refactored tier4_loc_comp.launch.xml + * changed localization_mode option names + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(intersection): timeout stuck vehicle stop in private area (`#406 `_) +* feat(start_planner): add length_ratio_for_turn_signal_deactivation_near_intersection (`#407 `_) +* fix(mpc): relax steering rate limit (`#405 `_) +* feat(start_planner): change lateral acceleration sampling num (`#404 `_) +* feat(start_planner): start with acceleration (`#402 `_) +* feat(avoidance): can set stop/move judge threshold for each object class (`#399 `_) +* feat(planning_launch): add a turn signal deactivation parameter for lane change (`#398 `_) +* feat(avoidance): change object_check_backward_distance from 100m to 10m (`#388 `_) +* feat(avoidance): additional buffer for perception noise (`#373 `_) + feat(avoidance): additional offset for perception noise +* feat(velocity_smoother): plan from ego velocity on manual mode (`#396 `_) +* feat(rviz): hide crosswalk areas (`#395 `_) +* feat(planning_launch): add a parameter for turn signal activation (`#397 `_) +* refactor: intersection module (`#391 `_) +* fix(autoware_launch): add missing parameter in autonmous emergency braking (`#392 `_) +* feat(behavior_path_planner): add flag to enable auto mode without rtc_auto_mode_manager (`#387 `_) + * add param + * enable rtc to false for default auto mode module + * update + * set avoidance module enable_rtc as false + * set all module enable_rtc param as true + --------- +* refactor(behavior_velocity_planner): load all module parameters (`#389 `_) + load all module parameters +* refactor(behavior_velocity_planner): update launch and parameter files for plugin (`#369 `_) + * feat: update parameter files + * feat: update param name + * feat: add disabled module as comment + * feat: use behavior_velocity_config_path + --------- +* refactor(start_planner): rename pull out to start planner (`#386 `_) +* fix(planning_launch): parameterize scale for lc safety check (`#384 `_) +* feat(avoidance): add option for yield during shifting (`#383 `_) +* feat(autoware_launch): suppress flickering to entry slow down (`#382 `_) +* feat(avoidance): add new parameter (`#374 `_) +* feat(autoware_launch): dynamic steer rate limit in mpc (`#381 `_) + * feat(autoware_launch): dynamic steer rate limit in mpc + * update + * update + --------- +* fix(trajectory_follower_nodes): mpc_follower does not send proper converged data under low steering rate limit (`#378 `_) +* feat(rtc_auto_mode_manager): delete external_request_lane_change from rtc auto mode manager config (`#379 `_) +* feat(pull_out): support pull out normal lane (`#377 `_) + * add th_blinker_on_lateral_offset: 1.0 + * minimum_shift_pull_out_distance: 0.0 + * minimum_lateral_jerk: 0.1 + --------- +* fix(tier4_perception_component_launch): add sync_param_path (`#350 `_) + * fix(tier4_perception_component_launch): add sync_param_path + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(lane_change): check lateral offset at lc finish judgement (`#375 `_) +* feat: first draft proposal implementation for handling invalid lanelets (`#235 `_) + * feat: first draft proposal implementation for handling invalid lanelets + * style(pre-commit): autofix + * feat: adding invalid lanelet for rviz visualization + * feat: fixing review comment + * feat: changing module name from invalid_lanelet to no_drivable_lane + * feat: fixing merge conflict mistakes + * feat: fixing merge conflict mistakes + * feat: fixing merge conflicts + * feat: removing rtc handing + * feat(no_drivable_lane): reflecting refactoring changes to no_drivable_lane + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* refactor(autoware_launch): remove duplicated path in planning launch (`#365 `_) +* feat(behavior_path_planner): relax margin_from_boundary in goal_planner param (`#371 `_) +* fix(intersection): add the flag for intersection_occlusion grid publication (`#372 `_) +* feat(planning_launch): add minimum reroute length (`#370 `_) +* fix(behavior_path_planner): fix lateral distance max threshold (`#368 `_) +* feat(planning_launch): add maximum and minimum longitudinal acceleration for the lane change (`#363 `_) +* feat(vehicle_cmd_gate): add moderate_stop_interface parameter (`#367 `_) +* feat(intersection): add the option to use intersection_area (`#366 `_) + add option to use intersection_area +* feat(autoware_launch): update obstacle_cruise_planner param (`#364 `_) + * feat(autoware_launch): update obstacle_cruise_planner param + * update + --------- +* feat(autoware_launch): remove min_acc in obstacle_cruise_planner for slow down (`#356 `_) +* feat(autoware_launch): add time margins for dynamic avoidance (`#360 `_) +* feat(avoidance): don't avoid objects around crosswalks (`#362 `_) +* feat(autoware_launch): time margin for slow down (`#359 `_) +* feat(autoware_launch): add hysteresis for slow down decision (`#354 `_) +* feat(intersection): denoise occlusion by morphology open process (`#361 `_) + parameterize kernel size +* feat(planning_launch): change lane change sampling number (`#358 `_) +* feat(behavior): increase dynamic avoidance module priority (`#355 `_) +* feat(planning_launch): add lateral acceleration map (`#352 `_) + * feat(planning_launch): add lateral acceleration map + * udpate + --------- +* feat(autoware_launch): add lane change abort param (`#351 `_) + * feat(autoware_launch): add lane change abort param + * fix(autoware_launch): restore some parameters + --------- +* feat(path_sampler): add parameter file for the `path_sampler` node (`#322 `_) +* fix(planning_launch): add backward_path_length_parameter (`#346 `_) +* feat(planning_launch): side shift debug marker (`#298 `_) + * feat(planning_launch): side shift debug marker + * delete blank line + * style(pre-commit): autofix + --------- + Co-authored-by: kyoichi-sugahara + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* refactor(avoidance): remove redundant parameter (`#340 `_) + * refactor(avoidance): rename parameter + * fix(avoidance): remove redundant parameter + --------- +* feat(obstacle_stop_planner): add filtering feature for predicted objects (`#330 `_) +* feat(autoware_launch): add marker of dynamic avoidance (`#345 `_) + * feat(autoware_launch): add marker of dynamic avoidance + * update + --------- +* feat(autoware_launch): add a flag to use hatched road markings for av… (`#337 `_) + feat(autoware_launch): add a flag to use hatched road markings for avoidance +* chore(autoware_launch): update rviz for hatched road markings (`#343 `_) + * chore(autoware_launch): update rviz for hatched road markings + * fix typo + --------- +* refactor(avoidance): remove hard code params in shift line triming process (`#341 `_) +* fix(behavior): don't show behaivor module's marker (`#342 `_) + fix(rviz): hide all info markers +* feat(avoidance): hide detail information (`#339 `_) +* refactor(behavior_path_planner): refactoring goal_planner and pull_out params (`#338 `_) +* feat(behavior): add interface in order to publish marker that is always shown in rviz (`#333 `_) + feat(behavior): output module info markers +* feat(autoware_launch): add min_drivable_width (`#334 `_) + * feat(autoware_launch): add min_drivable_width + * update + --------- +* feat(autoware_launch): avoid oncoming vehicles (`#335 `_) +* perf(mpc_lateral_controller): mpc works more stably (`#336 `_) +* feat(autoware_launch): dynamic obstacle avoidance (`#299 `_) + * add param + * update launch + * update for dynamic avoidance + * update + * update + * disable dynamic avoidance module + * pre-commit + --------- +* feat(behavior_velocity_planner::intersection): add intersection occlusion gridmap marker (`#332 `_) +* feat(autoware.rviz): disable right and left bound (`#329 `_) + * feat(autoware.rviz): disable right and left bound + * update + --------- +* feat: add gnss/imu localizer (`#200 `_) + * Add gnss_imu_localizar + * Eagleye parameter update fot sample data + * Restore perception/planning/control parameters in lsim + * Change use_gnss_mode + * Fix spell + * Fix spell + * Delete unnecessary white spaces + * Remove unnecessary trailing spaces + * Prettier format + * prettier format + * clang-format + * Revert "clang-format" + This reverts commit 46cd907089e6551a975bcff2f3971679598da24c. + * Rename GNSS/Lidar localization switching parameters + * Remove conditional branching by pose_estimatar_mode in system_error_monitor + * Change launch directory structure + * Delete unnecessary parameters and files + * Integrate map4_localization_component1,2 + * Fix comment out in localization launch + --------- +* refactor(planning_launch): remove duplicated lane change parameter (`#328 `_) +* fix(lanelet2_map_loader): update comment for available projector type (`#327 `_) +* refactor(rviz): fix typo (`#326 `_) +* feat(rviz): add behavior path virtual wall (`#325 `_) +* refactor(behavior_path_planner): rename pull_over to goal_planner (`#313 `_) + refactor(behavior_path_planenr): renaem pull_over to goal_planenr +* feat(autoware_launch): expand ogm size from 100m to 150m (`#324 `_) + expand ogm size from 100m to 150m +* chore(autoware_launch): tune intersection parameters (`#323 `_) +* refactor(planning_launch): remove minimum prepare length (`#319 `_) +* feat(behavior_path_planner): run avoidance and pull out simultaneously (`#321 `_) +* feat(behavior_velocity_planner::intersection): add parameter for occlusion peeking offset (`#320 `_) +* refactor(planning_launch): use common params for lane change (`#317 `_) +* fix(autoware_launch): old architecture lane change path in rviz (`#316 `_) +* feat(intersection): add flag to enable creep towards intersection occlusion (`#315 `_) +* feat(behavior_velocity_planner::intersection): add occlusion detection feature (`#305 `_) + * migrated + * fixed param + * remove some params + * organized param + * disable occlusion feature off by default + --------- +* feat(autoware_launch): make drivable area expansion parameters common (`#310 `_) +* chore(autoware_launch): make backward detection length for avoidance longer (`#312 `_) + * chore(autoware_launch): make backward detection length for avoidance longer + * make longer + --------- +* feat(obstacle_avoidance_planner): replan when forward path shape changes (`#309 `_) + * feat(obstacle_avoidance_planner): replan when forward path shape changes + * update + --------- +* feat(autoware_launch): add time to fix reference points's boundary width (`#311 `_) +* chore(autoware_launch): visualize thin predicted trajectory on rviz (`#314 `_) +* refactor(planning_launch): remove minimum lane changing length (`#308 `_) + * refactor(planning_launch): remove minimum lane changing length + * fix + --------- +* feat(tier4_simulator_launch): add use_baselink_z option for dummy_perception_publisher (`#304 `_) +* fix(planning_launch): change minimum prepare length (`#307 `_) +* feat(planning_launch): add reroute safety check parameter (`#306 `_) +* refactor(occupancy_grid_map): add occupancy_grid_map method/param var to launcher (`#294 `_) + add occcupancy_grid_map method/param var to launcher and use those ones in autoware_launch by default +* feat(autoware_launch): visualization for slow down (`#303 `_) +* feat(behavior_path_planner): move lane_following_params to behavior path params (`#302 `_) +* fix: compare map filter param (`#291 `_) +* feat(behavior_path_planner): pull over support road_lane and right_hand_traffic (`#300 `_) +* feat(obstacle_cruise_planner): implement slow down planner (`#288 `_) + * feat(obstacle_cruise_planner): add param for slow down + * update + --------- +* refactor(behavior_velocity_planner::intersection): organize param intersection (`#297 `_) + reorganize intersection param for readability +* refactor(behavior_velocity_planner): removed external input from behavior_velocity (`#296 `_) + removed external input from behavior_velocity +* feat(rviz): add rough goal (`#295 `_) +* feat(avoidance): margin can be set independently for each class (`#286 `_) +* feat(map_loader): add param for selected_map_loader (`#285 `_) + feat(map_loader): add param for selected_nap_loader +* refactor(obstacle_cruise_planner): clean up a part of the code (`#287 `_) + * modify parameters + * use cruise planner temporarily + * update + * use obstacle_stop_planner by default + --------- +* fix(behavior_path_planner): pull over deceleration (`#273 `_) +* fix(rviz): fix debug marker topic name (`#289 `_) +* feat(behavior_velocity_planner): add out of lane module (`#269 `_) + * Add initial param file for new out_of_lane module + * Add params for extending the ego footprint + * Add more parameters + * add a few more params + * Add/rename parameters for new version with 3 methods (thr, inter, ttc) + * Add parameters for "skip_if\_*", "strict", and "use_predicted_path" + * Update default parameters + * style(pre-commit): autofix + * Fix typo + * Change param ego.extra_front_offset 1.0 -> 0.0 + * Update rviz config with "out_of_lane" virtual wall and debug markers + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(behavior_path_planner): add new lateral acceleration (`#283 `_) +* feat: add option of enable_cog_on_centerline (`#278 `_) +* feat(behavior_path_planner): multiple candidate modules can run simultaneously (`#266 `_) +* refactor(behavior_path_planner): rename lane chagne parameters (`#284 `_) +* refactor(behavior_path_planner): rename lane change parameters (`#282 `_) + update +* fix(behavior_path_planner): remove unnecessary lane change parameter (`#280 `_) +* feat(behavior_path_planner): enable LC+Avoidacne simultaneous execution (`#271 `_) +* refactor(behavior_path_planner): remove lane change planner parameters (`#281 `_) +* refactor(behavior_velocity_planner): add default values (`#272 `_) + * fix(behavior): add missing params + * fix(behavior): add missing params + * fix(behavior): add missing params + * fix(behavior): add missing params + * fix(behavior): add missing params + * fix typo + --------- + Co-authored-by: satoshi-ota + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> +* feat(avoidance_by_lc): add new module to avoid obstacle by lane change (`#261 `_) + * feat(avoidance_by_lc): add config + * feat(launch): add avoidance by lc param path + * feat(rviz): add marker for avoidance by lc + --------- +* feat(behavior_velocity_planner::blind_spot): consider adjacent lane (`#267 `_) +* fix(autoware_launch): fix external lane change name (`#276 `_) + * fix(autoware_launch): fix external lane change name + * update rviz + --------- +* feat(autoware_launch): ext_lane_change -> external_lane_change in rtc (`#274 `_) + * fix + * empty commit + --------- +* refactor(behavior_path_planner): separate config file (`#270 `_) + feat(behavior_path_planner): add new config for manager +* feat(avoidance): update avoidance param (`#263 `_) + * feat(avoidance): enable safety check and yield + * feat(avoidance): update lateral margin + --------- +* feat(lane_following): consider lane ego angle diff (`#250 `_) + feat(lane_following): consider lane-ego angle diff +* feat(compare_map_segmentation): add param for dynamic map loading (`#257 `_) +* feat(autoware_launch): consider behavior's drivable area violation (`#254 `_) +* fix(behavior_velocity_planner): fix detection area being ignored when the ego vehicle stops over the stop line (`#260 `_) + * chore(behavior_velocity_planner): follow the latest implementation + (hold_stop_margin_distance) + * feat(behavior_velocity_planner): add a parameter for judging over the stop line + --------- +* feat(autoware_launch): add check_external_emergency_heartbeat option (`#253 `_) +* fix(behavior_path_planner): enable simlunateous executione (`#258 `_) +* chore(ekf_localizer): move parameters to its dedicated yaml file (`#244 `_) + * chores(ekf_localizer): move parameters to its dedicated yaml file + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(planning_launch): disable external lc module in new framework (`#262 `_) +* feat(autoware_launch): add missing stop line parameter (`#252 `_) +* chore(ground_segmentation): add optional param (`#259 `_) +* fix(rviz): fix lane change topic name (`#256 `_) + * fix(rviz): fix lane change topic name + * fix(rviz): rename + --------- +* feat(control_launch): add parameter for aeb (`#232 `_) +* fix(behavior_velocity_planner): disable launch_virtual_traffic_light parameter by default (`#251 `_) +* feat(autoware_launch): enable pose initialization while running (only for sim) (`#243 `_) + * feat(autoware_launch): enable pose initialization while running (only for sim) + * style(pre-commit): autofix + * update localization param + * both logsim and psim params + * only one pose_initializer_param_path arg + * style(pre-commit): autofix + * use two param files for pose_initializer + * style(pre-commit): autofix + * debug + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(lane_change): support param for new framework (include external lc) (`#248 `_) + * feat(lane_change): support param for new framework (include external lc) + * rename external lane change + --------- +* feat(rviz): add path reference marker (`#245 `_) + * feat(rviz): add path reference (hide as default) + * fix(rviz): fix typo + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + * differentiate path color + --------- + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + Co-authored-by: Muhammad Zulfaqar Azmi +* feat(autoware_launch): add option to use akima spline at first (`#247 `_) + * feat(autoware_launch): enable akima spline for xy only first + * disable akima spline + --------- +* fix(autoware_launch): perception mode (`#249 `_) +* fix(pull_over): add params (`#246 `_) + * fix(pull_over): add params + * Update autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml + --------- + Co-authored-by: Kosuke Takeuchi +* feat(planning_evaluator): delete_launch_planning_evaluator_arg (`#240 `_) + * delete_launch_planning_evaluator_arg + * delete_launch_planning_evaluator_arg + --------- +* feat(avoidance): add config for new framework (`#233 `_) + * feat(behavior_path_planner): add config for avoidance on new framework + * fix(behavior_path_planner): fix priority + * fix(behavior_path_planner): add description of priority param + --------- +* feat(pull_over): support new framework (`#237 `_) + feat(behavior_path_planner): add config for pull over on new framework +* feat(lane_change): add config for new framework (`#239 `_) + * feat(lane_change): add config for new framework + * rearrange module alphabetically + --------- +* fix(avoidance): increase road shoulder margin 0.0 -> 0.3 (`#242 `_) +* feat: lengthen safety_check_backward_distance in avoidance module (`#241 `_) +* feat(side_shift): add config for new framework (`#234 `_) + feat(behavior_path_planner): add config for side shift on new framework +* feat(pull_out): add config for new framework (`#236 `_) + feat(behavior_path_planner): add config for pull out on new framework +* feat(planning_evaluator): launch planning_evaluator when scenario simulation is running (`#219 `_) + * feat(planning_evaluator): launch planning_evaluator when scenario simulation is running + * refactoring + --------- +* feat(behavior_path_planner): pull over freespace parking (`#221 `_) + * feat(behavior_path_planner): pull over freespace parking + * fix typo + --------- +* fix(behavior_path_planner): change pull over maximum_deceleration (`#229 `_) +* fix(autoware_launch): add walkway visualization (`#231 `_) +* feat(autoware_launch): update obstacle avoidance planner parameter (`#220 `_) + * update obstacle_avoidance_planner's param + * update + --------- +* feat(avoidance): add new param for avoidance target object filtering logic (`#226 `_) + feat(avoidance): add new param for avoidance +* feat(behavior_path_planner): add param for new planner manager (`#218 `_) +* feat(obstacle_stop_planner): add margin behind goal (`#228 `_) +* fix(autoware_launch): use tier4_sensing_component.launch.xml (`#227 `_) +* feat(mission_planner): add config param file for mission_planner package (`#225 `_) + * add mission_planner param file + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(osbtacle_stop_planner): add new trajectory checker parameter (`#224 `_) + add new trajectory checker parameter +* fix(obstacle_stop_planner): add lacking param (`#222 `_) + add param + Co-authored-by: yamazakiTasuku +* feat(lane_departure_checker): add optional neighbor lanelets parameters (`#217 `_) + feat(lane_departure_checker): add optional neighbor lanelets parameters (`#217 `_) +* feat(vehicle_cmd_gate): enable filter with actual steer in manual mode (`#189 `_) +* chore(run_out): update parameter for mandatory detection area (`#205 `_) +* feat(autoware_launch): update rviz and rtc config for planning (`#213 `_) +* fix(autoware_launch): add missing system file (`#211 `_) +* fix(autoware_launch): unify with tier4 launch (`#210 `_) + * fix + * fix + * fix + * fix + * fix + * fix + --------- +* feat(system_component_launch): add config param for dummy diag publisher (`#206 `_) + * add config param for dummy diag publisher + * fixed dummy_diag_publisher param yaml (add empty diag) + * launch dummy diag publisher by launch_dummy_diag_publisher param + --------- +* refactor(autoware_launch): clean up component launch (`#207 `_) + * refactor(autoware_launch): clean up component launch + * fix + * Update autoware_launch/launch/components/tier4_map_component.launch.xml + Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> + --------- + Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> +* fix: revert "chore: sync param files (`#161 `_)" (`#209 `_) + This reverts commit 6fe7144c4d8e7909b58c5abbccd59c8c200e0618. + Co-authored-by: awf-autoware-bot[bot] <94889083+awf-autoware-bot[bot]@users.noreply.github.com> +* fix(autoware_launch): fix the planning param (`#208 `_) +* fix(autoware_launch): add z_axis_filtering params for obstacle_stop_planner node (`#150 `_) +* fix(obstacle_avoidance_planner.param.yaml): add a margin for vehicle to stop before the end of drivable area boundary (`#192 `_) + * fix: add margin for vehicle stop before the end of drivable area boundary + Adding ros parameter for vehicle stop margin for obstacle avoidance planner + * style(pre-commit): autofix + --------- + Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(behavior_path_planner): expand the drivable area based on the vehicle footprint (`#204 `_) +* feat(autoware_launch): add param for configurable lateral_distance (`#140 `_) + add param for configurable lateral_distance & debug flag + Co-authored-by: beyza +* chore: add lanelet2 map config (`#169 `_) + * add_lanelet2_map_config to autoware_launch config + * set projector type as default + --------- +* fix(behavior_velocity_planner): continue collision checking after pass judge (`#203 `_) + fix(behavior_velocity_planner): revert part of `#2719 `_ +* chore: sync param files (`#161 `_) + Co-authored-by: takayuki5168 +* feat(autoware_launch): add option to disable path update during avoidance (`#198 `_) +* chore(autoware_launch): minor parameter change for planning and control (`#195 `_) +* chore(autoware_launch): minor fix with trajectory_follower param (`#167 `_) +* fix(autoware_launch): change behavior_velocity parameters (`#179 `_) +* fix(multi_object_tracker): update data association matrix (`#196 `_) + * fix(multi_object_tracker): update data association matrix + * Update autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml + also update for other CAR->(other objects) + Co-authored-by: Yukihiro Saito + --------- + Co-authored-by: Yukihiro Saito +* feat(planning_config): update params to enable 60kmph speed (`#194 `_) +* feat(autoware_launch): add NDT parameters for dynamic_map_loading (`#151 `_) + * feat(autoware_launch): add NDT parameters for dynamic_map_loading + * set default param to false + * set default use_dynamic_map_loading to true + * fix parameter description + --------- +* fix(lane_change): update default parameter (`#183 `_) +* fix(autoware_launch): minor change with tier4_control_component (`#186 `_) +* fix(autoware_launch): minor change with tier4_planning_component (`#185 `_) + * fix(autoware_launch): minor change with tier4_planning_component + * update + --------- +* fix(occlusion_spot): occlusion spot parameter disable as default (`#191 `_) +* feat(mpc_lateral_controller): add steering bias removal (`#190 `_) + * feat(mpc_lateral_controller): add steering bias removal + * change name +* feat(intersection): add param for stuck stopline overshoot margin (`#188 `_) +* fix(autoware_launch): enable launch_deprecated_api (`#187 `_) + * fix(autoware_launch): enable launch_deprecated_api + * Update autoware_launch/launch/components/tier4_autoware_api_component.launch.xml + Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> + Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> +* feat(control_launch): add min_braking_distance to lane_departure_checker (`#184 `_) +* feat(intersection): improve ego velocity prediction in collision detection (`#181 `_) +* feat(autoware_launch): visualize modified_goal as PoseWithUuidStamped (`#182 `_) +* feat(autoware_launch): add param for considering footprint edges when check the drivable area (`#175 `_) + * add is_considering_footprint_edges param + * add description + Co-authored-by: beyza +* fix(autoware_launch): add missing simulator param (`#164 `_) +* fix(obstacle_stop_planner): rename param for obstacle stop planner (`#174 `_) + fix(obstacle_stop_planner): hunting -> chattering +* feat(autoware_lauch): modify launch for planning_validator (`#180 `_) + * modify launch for planning_validator + * fix +* feat(autoware_launch): add tier4 autoware api component (`#173 `_) +* fix(autoware_launch): change planning parameters (`#178 `_) +* fix(lane_change): fix default abort param (`#177 `_) + * fix(lane_change): fix default abort param + * revert safety time margin +* fix(lane_change): behavior planning common and lane change param (`#158 `_) + * fix(planning): behavior planning common and lane change param + * revert forward_path_length +* refactor(autoware_launch/bpp-avoidance): remove redundant parameters (`#170 `_) +* feat(autoware_launch): add fitting_uniform_circle parameter for mpt (`#159 `_) + * feat(autoware_launch): add new config params for fitting uniform circle + * reformat +* feat(behavior_path_planner): ignore pull out start near lane end (`#171 `_) +* fix(autoware_launch): fix wrong parameter name (`#172 `_) + * fix(autoware_launch): fix wrong parameter name + * fix +* refactor(autoware_launch): organize arguments for planning (`#165 `_) + * refactor(tier4_planning_launch): organize arguments + * update +* feat(behavior_path_planner): add option for combining arc pull out paths (`#168 `_) + * feat(behavior_path_planner): add option for combining arc pull out paths + * divide_pull_out_path +* feat(behavior_path_planner): ignore pull over goal near lane start (`#166 `_) + feat(behavior_path_planner) ignore pull over goal near lane start +* feat(autoware_launch): add point cloud container to localization launch (`#108 `_) +* fix(rviz): fix topic name for obstacle_stop_planner debug marker (`#162 `_) +* feat(behavior_path_planner): param to skip some linestring types when expanding the drivable area (`#160 `_) + [behavior_path_planner] add types to skip in drivable_area_expansion +* feat(autoware_launch): update pure_pursuit parameters (`#154 `_) +* feat(obstacle_stop_planner): add parameter for voxel_grid (`#156 `_) + * feat(obstacle_stop_planner): add parameter for voxel grid + * fix: parameter +* feat(avoidance): add new param for yield maneuver in avoidance module (`#146 `_) + * feat(avoidance): add new param for yield maneuver in avoidance module + * fix(avoidance): fix param name for readability + * fix(planning_launch): add missing param +* feat: add speed bump debug markers to autoware.rviz (`#63 `_) +* feat(autoware_launch): add speed bump parameters (`#138 `_) +* fix(autoware-launch): add NDT parameters for de-grounded lidar scan matching (`#155 `_) + * fix(autoware-launch):add NDT parameters for de-grounded lidar scan matching + * style(pre-commit): autofix + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(behavior_velocity_planner): fix blind spot over-detection (`#153 `_) +* fix(planning_launch): ignore unavoidable objects around the goal (`#152 `_) + * fix(planning_launch): ignore unavoidable objects around the goal + * Update autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml + Co-authored-by: Kosuke Takeuchi +* feat(autoware_launch): enable use_individual_control_param (`#148 `_) + * fix(autoware_launch): add missing param of vehicle_cmd_gate in yaml + * feat(autoware_launch): enable use_individual_control_param +* fix(autoware_launch): add missing param of vehicle_cmd_gate in yaml (`#149 `_) +* refactor(autoware_launch): organize control yaml (`#147 `_) +* feat: update param path (`#144 `_) + * feat: update param path + * fix + * organize param files +* fix: avoidance parameter file (`#145 `_) + * fix: avoidance parameter file + * Update autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +* feat(perception): change detection region (`#141 `_) +* fix(autoware_launch): remove unnecessary `config` declaration (`#137 `_) + * fix(autoware_launch): remove unnecessary `config` declaration + * follow alphabetical order +* feat(autoware_launch): move config from autoware.universe for simulator (`#132 `_) + * feat(autoware_launch): move config to autoware_launch for perception + * first commit + * fix(autoware_launch): fix config path of system_error_monitor + * fix typo again + * resolve conflict +* fix(autoware_launch): fix config path of system_error_monitor (`#136 `_) + * fix(autoware_launch): fix config path of system_error_monitor + * fix typo again +* feat(autoware_launch): move config from autoware.universe for control (`#134 `_) + * feat(autoware_launch): move config from autoware.universe for control + * fix + * update operation_mode_transition_manager.param.yaml + Co-authored-by: kminoda +* feat(autoware_launch): move config from autoware.universe for map (`#128 `_) + feat(autoware_launch): move config to autoware_launch for map +* feat(autoware_launch): move config from autoware.universe for localization (`#129 `_) + * feat(autoware_launch): move config to autoware_launch for localization + * fix order +* feat(autoware_launch): move config from autoware.universe for perception (`#131 `_) + feat(autoware_launch): move config to autoware_launch for perception +* feat(autoware_launch): move config from autoware.universe for planning (`#133 `_) + * feat(autoware_launch): move config from autoware.universe for planning + * remove unnecessary config + * add rtc + * apply universe param change +* feat(autoware_launch): move config from autoware.universe for system (`#130 `_) + * feat(autoware_launch): move config to autoware_launch for system + * fix +* feat(autoware_launch): add bound visualization (`#135 `_) +* feat(autoware_launch): visualize multiple candidate paths (`#125 `_) + * feat(autoware_launch): visualize multiple candidate paths + * feature(autoware.rviz): fix name space +* fix: change check_external_emergency_heartbeat false (`#119 `_) + * fix: use_external_emergenc_stop false + * Update autoware.launch.xml +* fix(autoware_launch): remove web_controller (`#121 `_) +* fix: rename use_external_emergency_stop to check_external_emergency_heartbeat (`#120 `_) +* feat: remove web controller (`#117 `_) +* fix(autoware_launch): add parameter to launch launch_system_monitor (`#113 `_) +* fix(rviz): update obstacle_avoidance_planner virtual_wall topic name (`#115 `_) +* feat: set use_external_emergency_stop to false by default when launching psim (`#109 `_) +* refactor(autoware_launch): change pure_pursuit debug marker topic name (`#110 `_) + Co-authored-by: Berkay Karaman +* feat(autoware_launch): add obstacle_collision_checker to launch (`#106 `_) + * feat(autoware_launch): add obstacle_collision_checker to launch + * ci(pre-commit): autofix + * add option to other launch files + * ci(pre-commit): autofix + Co-authored-by: Berkay Karaman + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(autoware_launch): add autoware_state_panel to autoware.rviz (`#104 `_) +* fix(rviz): enlarge pointcloud size for NDT results (`#103 `_) + * fix(rviz): enlarge pointcloud size for NDT results + * change default settings of Initial pointcloud +* feat(autoware_launch): add e2e_simulator.launch.xml (`#98 `_) + * feat(autoware_launch): add e2e_simulator.launch.xml + * chore: rename + * chore: remove unnecessary option +* fix(autoware_launch): launch dummy_localization regardless of scenario_simulation flag (`#95 `_) +* feat: move adapi rviz adaptor (`#88 `_) + feat: move adapi rviz adaptor +* chore(autoware_launch): designate vehicle_id to tier4_control_launch (`#74 `_) + Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> +* fix: add adapi dependency (`#86 `_) +* feat(autoware_launch): apply the change of pose initializer (`#72 `_) + * feat(autoware_launch): apply the change of pose initializer + * fix: add group for include scope +* feat(autoware_launch): add rviz helper for ad api (`#70 `_) + * feat(autoware_launch): add rviz helper for ad api + * feat: change launch file +* feat(rviz): update rviz planning module's debug marker (`#85 `_) + * feat(rviz): add behavior path debug markers (`#441 `_) + * feat(rviz): add 2D dummy bus button as default (`#453 `_) + * feat(rviz): add behavior path debug markers (`#462 `_) + * feat(rviz): remove old pull over marker + Co-authored-by: kosuke55 +* feat: disable visualization of object pose covariance (`#79 `_) +* feat(autoware_launch): add vehicle footprint to autoware.rviz (`#81 `_) + feat: add vehicle footprint to autoware.rviz +* fix: use sim time option (`#69 `_) + * fix: use sim time option + * fix: minimum usesim time option + * ci(pre-commit): autofix + * fix: add simulation flag to distinguish + * ci(pre-commit): autofix + * Revert "ci(pre-commit): autofix" + This reverts commit 291770d114baae38c7645b51c2569a66fa6353d3. + * Revert "Merge commit '7b1424eaeb2b06a6fb2921ff242a3c4e5fef6169' into fix/use_sim_time_option" + This reverts commit 02fede2df4099d5019b60fddb585e53357e62535, reversing + changes made to 9aeaa88f39c152333cac658a908f9ab8d7dcd037. + * Revert "fix: add simulation flag to distinguish" + This reverts commit 9aeaa88f39c152333cac658a908f9ab8d7dcd037. + * fix: remove duplicated arg + * fix: use sim time option + * ci(pre-commit): autofix + * fix: ungroup autoware launch + * Revert "fix: ungroup autoware launch" + This reverts commit cb3e3aa536ae2aa740cd846c97fe6cf373ba8744. + * fix: to scoped false + * chore: better comment + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* refactor(autoware_launch): use autoware.launch.xml in planning/logging_simulator.launch.xml (`#59 `_) + * refactor(autoware_launch): use autoware.launch.xml in planning_simulator.launch.xml + * fix planning_launcher launch and use autoware.launch.xml in logging_simulator.launch.xml + * fix arguments + * fix argument order + * remove init_localization_pose + * move if tag + * reorder arguments + * add description for arguments +* chore(rviz): update rviz config for pull_over (`#58 `_) +* feat: add line_width property to object display (`#56 `_) +* chore: update to universe config (`#52 `_) + * chore: to universe rviz config + * feat: replace rostime to date time panel + * fix : to best effott + * feat: add manuever topic + * chore: disable marker by default + * feat: add diag marker +* fix(mission_planner): disable lane_start_bound in Rviz (`#51 `_) +* feat: add arguments for pointcloud container to planning (`#37 `_) + * feat: add arguments for pointcloud container to planning + * add marker for run out module +* feat: disable some namespace for lanelet2 (`#50 `_) +* feat(rviz_plugin): adaptive scaling for display size (`#44 `_) +* refactor: update rviz config for virtual wall marker separation (`#42 `_) +* feat: add autoware_api.launch.xml to launch files in autoware_launch package (`#26 `_) + * feat: add autoware_api.launch.xml to launch files in autoware_launch package + * fix(autoware_launch): fix flags for autoware.launch and logging_simulator.launch +* feat(obstacle_avoidance_planner): add obstacle_avoidance_planner wall marker in autoware.rviz (`#28 `_) +* feat: cosmetic change autoware.rviz for perception (`#24 `_) +* feat(autoware_launch): update autoware.rviz not to visualize occlusion spot markers (`#25 `_) + Co-authored-by: taikitanaka3 +* feat(autoware_launch): update autoware.rviz not to visualize obstacle_avoidance_planner markers (`#23 `_) +* fix: incorrect arguments and including launch (`#19 `_) + * fix: incorrect arguments and including launch + * add launch_vehicle_interface + * bug fix +* ci(pre-commit): update pre-commit-hooks-ros (`#18 `_) + * ci(pre-commit): update pre-commit-hooks-ros + * ci(pre-commit): autofix + * Update .pre-commit-config.yaml + * Update .pre-commit-config.yaml + * Update .pre-commit-config.yaml + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix: fix launch args (`#6 `_) +* fix: add group to each section (`#5 `_) + * chore: apply pre-commit + * fix: add group +* feat: add autoware_launch (`#1 `_) + * feat: change launch package name (`#186 `_) + * rename launch folder + * autoware_launch -> tier4_autoware_launch + * integration_launch -> tier4_integration_launch + * map_launch -> tier4_map_launch + * fix + * planning_launch -> tier4_planning_launch + * simulator_launch -> tier4_simulator_launch + * control_launch -> tier4_control_launch + * localization_launch -> tier4_localization_launch + * perception_launch -> tier4_perception_launch + * sensing_launch -> tier4_sensing_launch + * system_launch -> tier4_system_launch + * ci(pre-commit): autofix + * vehicle_launch -> tier4_vehicle_launch + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: tanaka3 + Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> + * feat(atutoware.rviz): disable selectable for pointcloud visualization (`#402 `_) + * fix: change the default mode of perception.launch (`#409 `_) + * fix: change the default mode of perception.launch + * chore: remove unnecessary comments + * chore: remove default values + * rename package name + * ci(pre-commit): autofix + * add build_depends.repos + Co-authored-by: Tomoya Kimura + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: tanaka3 + Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> + Co-authored-by: Yamato Ando +* Contributors: Ahmed Ebrahim, Alexey Panferov, Amadeusz Szymko, Anh Nguyen, Autumn60, Azumi Suzuki, Berkay Karaman, Dmitrii Koldaev, Fumiya Watanabe, Giovanni Muhammad Raditya, Go Sakayori, Hasan Özfidan, Hiroki OTA, Ismet Atabay, Kaan Çolak, Kazunori-Nakajima, Kenji Miyake, Kento Yabuuchi, Kenzo Lobos Tsunekawa, Khalil Selyan, KokiAoki, Kosuke Takeuchi, Kyoichi Sugahara, M. Fatih Cırıt, Makoto Kurihara, Mamoru Sobue, Masaki Baba, Masato Saeki, Maxime CLEMENT, Mehmet Dogru, Mitsuhiro Sakamoto, Motz, Muhammed Yavuz Köseoğlu, Naophis, Phoebe Wu, Ryohsuke Mitsudome, RyuYamamoto, Ryuta Kambe, SakodaShintaro, SaltUhey, Satoshi OTA, Satoshi Tanaka, Shintaro Tomie, Shumpei Wakabayashi, Shunsuke Miura, Taekjin LEE, TaikiYamada4, Takagi, Isamu, Takamasa Horibe, Takayuki Murooka, Takeshi Miura, Tao Zhong, TetsuKawa, Tomohito ANDO, Tomoya Kimura, Vincent Richard, Xuyuan Han, Yamato Ando, Yoshi Ri, Yuki TAKAGI, Yukihiro Saito, Yusuke Muramatsu, Yutaka Shimizu, Yuxuan Liu, Zhe Shen, Zulfaqar Azmi, asana17, awf-autoware-bot[bot], badai nguyen, beginningfan, beyzanurkaya, cyn-liu, danielsanchezaran, ito-san, keisuke, kminoda, melike tanrikulu, mkquda, pawellech1, ryohei sasaki, taikitanaka3, yamazakiTasuku, Łukasz Chojnacki diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index f8000b8082..678c08d7b6 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -1,7 +1,7 @@ autoware_launch - 0.1.0 + 0.38.0 The autoware_launch package Yukihiro Saito From 68426e5658ba985f29e1dbf81978a39be3b0ee10 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 15 Nov 2024 11:46:09 +0900 Subject: [PATCH 03/25] feat(crosswalk): disable slowdowns when the crosswalk is occluded (#1232) Signed-off-by: Maxime CLEMENT --- .../behavior_velocity_planner/crosswalk.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 5a0757401b..05a2658c28 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 @@ -79,7 +79,7 @@ # param for occlusions occlusion: - enable: true # if true, ego will slowdown around crosswalks that are occluded + enable: false # if true, ego will slowdown around crosswalks that are occluded occluded_object_velocity: 2.0 # [m/s] assumed velocity of objects that may come out of the occluded space slow_down_velocity: 1.0 # [m/s] time_buffer: 0.5 # [s] consecutive time with/without an occlusion to add/remove the slowdown From 42f8c16b0c7378c0e28d5e0a78650be40856acb4 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 15 Nov 2024 13:32:51 +0900 Subject: [PATCH 04/25] feat(goal_planner): loosen safety check to prevent unnecessary stop (#1231) Signed-off-by: kosuke55 --- .../goal_planner/goal_planner.param.yaml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) 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 a20fae6e6a..723e34e61a 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 @@ -139,13 +139,13 @@ 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_horizon_for_front_object: 5.0 + time_horizon_for_rear_object: 5.0 time_resolution: 0.5 delay_until_departure: 1.0 # For target object filtering target_filtering: - safety_check_time_horizon: 10.0 + safety_check_time_horizon: 5.0 safety_check_time_resolution: 1.0 # detection range object_check_forward_distance: 100.0 @@ -179,7 +179,7 @@ # safety check configuration enable_safety_check: true method: "integral_predicted_polygon" - keep_unsafe_time: 3.0 + keep_unsafe_time: 0.5 # collision check parameters publish_debug_marker: false rss_params: @@ -192,7 +192,7 @@ forward_margin: 1.0 backward_margin: 1.0 lat_margin: 1.0 - time_horizon: 10.0 + time_horizon: 5.0 # hysteresis factor to expand/shrink polygon with the value hysteresis_factor_expand_rate: 1.0 collision_check_yaw_diff_threshold: 3.1416 From 1f6ee4e37ee3c960f8997c8796e504aa7a955dda Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 15 Nov 2024 15:44:47 +0900 Subject: [PATCH 05/25] chore(crosswalk)!: delete wide crosswalk corresponding function (#1233) Signed-off-by: Yuki Takagi --- .../behavior_velocity_planner/crosswalk.param.yaml | 2 -- 1 file changed, 2 deletions(-) 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 05a2658c28..fe443ca476 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 @@ -13,8 +13,6 @@ # For the Lanelet2 map with no explicit stop lines stop_distance_from_crosswalk: 3.5 # [m] make stop line away from crosswalk - # For the case where the crosswalk width is very wide - far_object_threshold: 10.0 # [m] If objects cross X meters behind the stop line, the stop position is determined according to the object position (stop_distance_from_object meters before the object). # For the case where the stop position is determined according to the object position. stop_distance_from_object_preferred: 3.0 # [m] stop_distance_from_object_limit: 3.0 # [m] From a217440bcce69ff807a378ea78b4fef28c6f9a68 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 18 Nov 2024 11:12:45 +0900 Subject: [PATCH 06/25] feat(rviz): show velocity/steering factors (#1235) Signed-off-by: satoshi-ota --- autoware_launch/rviz/planning_bev.rviz | 2 ++ autoware_launch/rviz/planning_tpv.rviz | 2 ++ 2 files changed, 4 insertions(+) diff --git a/autoware_launch/rviz/planning_bev.rviz b/autoware_launch/rviz/planning_bev.rviz index 449bb4567a..4b7ce39e51 100644 --- a/autoware_launch/rviz/planning_bev.rviz +++ b/autoware_launch/rviz/planning_bev.rviz @@ -68,6 +68,8 @@ Panels: Name: LoggingLevelConfigureRvizPlugin - Class: rviz_plugins::RTCManagerPanel Name: RTCManagerPanel + - Class: rviz_plugins::VelocitySteeringFactorsPanel + Name: VelocitySteeringFactorsPanel Visualization Manager: Class: "" Displays: diff --git a/autoware_launch/rviz/planning_tpv.rviz b/autoware_launch/rviz/planning_tpv.rviz index 53f755cd62..6b11e3e570 100644 --- a/autoware_launch/rviz/planning_tpv.rviz +++ b/autoware_launch/rviz/planning_tpv.rviz @@ -67,6 +67,8 @@ Panels: Name: LoggingLevelConfigureRvizPlugin - Class: rviz_plugins::RTCManagerPanel Name: RTCManagerPanel + - Class: rviz_plugins::VelocitySteeringFactorsPanel + Name: VelocitySteeringFactorsPanel Visualization Manager: Class: "" Displays: From 5806a02bd6eb90a1691896fdc38d5af3d8323381 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 18 Nov 2024 14:34:41 +0900 Subject: [PATCH 07/25] feat(freespace_planner): lower safety distance margin from 0.5 to 0.4m (#1234) Signed-off-by: Maxime CLEMENT --- .../parking/freespace_planner/freespace_planner.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml index d82a942035..1d7048ee39 100644 --- a/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/parking/freespace_planner/freespace_planner.param.yaml @@ -9,7 +9,7 @@ th_stopped_velocity_mps: 0.01 th_course_out_distance_m: 1.0 th_obstacle_time_sec: 1.0 - vehicle_shape_margin_m: 0.5 + vehicle_shape_margin_m: 0.4 replan_when_obstacle_found: true replan_when_course_out: true From 2269c49ebd43e9dc0970d2e30b69dff14677f940 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Tue, 19 Nov 2024 11:12:05 +0900 Subject: [PATCH 08/25] chore(system_diagnostic_monitor): sort paths (#1230) Signed-off-by: Yuki Takagi --- .../autoware-main.yaml | 42 +++++++++---------- 1 file changed, 21 insertions(+), 21 deletions(-) diff --git a/autoware_launch/config/system/system_diagnostic_monitor/autoware-main.yaml b/autoware_launch/config/system/system_diagnostic_monitor/autoware-main.yaml index 30b6ce9bad..fbbfe384f2 100644 --- a/autoware_launch/config/system/system_diagnostic_monitor/autoware-main.yaml +++ b/autoware_launch/config/system/system_diagnostic_monitor/autoware-main.yaml @@ -1,27 +1,13 @@ files: - - { path: $(dirname)/map.yaml } + - { path: $(dirname)/control.yaml } - { path: $(dirname)/localization.yaml } - - { path: $(dirname)/planning.yaml } + - { path: $(dirname)/map.yaml } - { path: $(dirname)/perception.yaml } - - { path: $(dirname)/control.yaml } - - { path: $(dirname)/vehicle.yaml } + - { path: $(dirname)/planning.yaml } - { path: $(dirname)/system.yaml } + - { path: $(dirname)/vehicle.yaml } units: - - path: /autoware/modes/stop - type: ok - - - path: /autoware/modes/autonomous - type: and - list: - - { type: link, link: /autoware/map } - - { type: link, link: /autoware/localization } - - { type: link, link: /autoware/planning } - - { type: link, link: /autoware/perception } - - { type: link, link: /autoware/control } - - { type: link, link: /autoware/vehicle } - - { type: link, link: /autoware/system } - - path: /autoware/modes/local type: and list: @@ -36,13 +22,21 @@ units: - { type: link, link: /autoware/system } - { type: link, link: /autoware/control/remote } - - path: /autoware/modes/emergency_stop + - path: /autoware/modes/stop + type: ok + + - path: /autoware/modes/autonomous type: and list: + - { type: link, link: /autoware/map } + - { type: link, link: /autoware/localization } + - { type: link, link: /autoware/planning } + - { type: link, link: /autoware/perception } + - { type: link, link: /autoware/control } - { type: link, link: /autoware/vehicle } - { type: link, link: /autoware/system } - - path: /autoware/modes/comfortable_stop + - path: /autoware/modes/pull_over type: and list: - { type: link, link: /autoware/map } @@ -53,7 +47,7 @@ units: - { type: link, link: /autoware/vehicle } - { type: link, link: /autoware/system } - - path: /autoware/modes/pull_over + - path: /autoware/modes/comfortable_stop type: and list: - { type: link, link: /autoware/map } @@ -64,6 +58,12 @@ units: - { type: link, link: /autoware/vehicle } - { type: link, link: /autoware/system } + - path: /autoware/modes/emergency_stop + type: and + list: + - { type: link, link: /autoware/vehicle } + - { type: link, link: /autoware/system } + - path: /autoware/debug/tools type: and list: From 28767b448f5d29f83311cfdbe836d97bcfefaea9 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 19 Nov 2024 11:35:12 +0900 Subject: [PATCH 09/25] feat: enable MRM summary Signed-off-by: Takayuki Murooka --- autoware_launch/rviz/autoware.rviz | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index c53d5d62e6..589c9cbfd5 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -269,13 +269,13 @@ Visualization Manager: Enabled: true Name: Vehicle - Class: rviz_plugins/MrmSummaryOverlayDisplay - Enabled: false + Enabled: true Font Size: 10 - Left: 512 + Left: 10 Max Letter Num: 100 Name: MRM Summary Text Color: 25; 255; 240 - Top: 64 + Top: 10 Topic: Depth: 5 Durability Policy: Volatile From c42bd46d6ef64ba6321a5e90bcfd356b1bcf4867 Mon Sep 17 00:00:00 2001 From: "Kem (TiankuiXian)" <1041084556@qq.com> Date: Tue, 19 Nov 2024 11:44:18 +0900 Subject: [PATCH 10/25] feat(control): use preset.yaml to control which modules to launch for control modules (#1237) * add control_module_preset Signed-off-by: xtk8532704 <1041084556@qq.com> * fix typo Signed-off-by: xtk8532704 <1041084556@qq.com> --------- Signed-off-by: xtk8532704 <1041084556@qq.com> --- .../config/control/preset/default_preset.yaml | 39 +++++++++++++++++++ .../preset/dlr_control_validator_preset.yaml | 39 +++++++++++++++++++ autoware_launch/launch/autoware.launch.xml | 5 ++- .../tier4_control_component.launch.xml | 9 ++--- .../launch/e2e_simulator.launch.xml | 2 + .../launch/logging_simulator.launch.xml | 2 + .../launch/planning_simulator.launch.xml | 2 + 7 files changed, 91 insertions(+), 7 deletions(-) create mode 100644 autoware_launch/config/control/preset/default_preset.yaml create mode 100644 autoware_launch/config/control/preset/dlr_control_validator_preset.yaml diff --git a/autoware_launch/config/control/preset/default_preset.yaml b/autoware_launch/config/control/preset/default_preset.yaml new file mode 100644 index 0000000000..74ba17b0a1 --- /dev/null +++ b/autoware_launch/config/control/preset/default_preset.yaml @@ -0,0 +1,39 @@ +launch: + # controller + - arg: + name: trajectory_follower_mode + default: trajectory_follower_node + # option: trajectory_follower_node + # smart_mpc_trajectory_follower + # none + + # external_cmd selector/converter + - arg: + name: launch_external_cmd_selector + default: "true" + - arg: + name: launch_external_cmd_converter + default: "true" + + # optional control checkers + - arg: + name: launch_lane_departure_checker + default: "true" + - arg: + name: launch_control_validator + default: "true" + - arg: + name: launch_autonomous_emergency_braking + default: "true" + - arg: + name: launch_collision_detector + default: "true" + - arg: + name: launch_obstacle_collision_checker + default: "false" + - arg: + name: launch_predicted_path_checker + default: "false" + - arg: + name: launch_control_evaluator + default: "true" diff --git a/autoware_launch/config/control/preset/dlr_control_validator_preset.yaml b/autoware_launch/config/control/preset/dlr_control_validator_preset.yaml new file mode 100644 index 0000000000..1ad7ce9ac9 --- /dev/null +++ b/autoware_launch/config/control/preset/dlr_control_validator_preset.yaml @@ -0,0 +1,39 @@ +launch: + # controller + - arg: + name: trajectory_follower_mode + default: none + # option: trajectory_follower_node + # smart_mpc_trajectory_follower + # none + + # external_cmd selector/converter + - arg: + name: launch_external_cmd_selector + default: "false" + - arg: + name: launch_external_cmd_converter + default: "false" + + # optional control checkers + - arg: + name: launch_lane_departure_checker + default: "false" + - arg: + name: launch_control_validator + default: "true" + - arg: + name: launch_autonomous_emergency_braking + default: "false" + - arg: + name: launch_collision_detector + default: "false" + - arg: + name: launch_obstacle_collision_checker + default: "false" + - arg: + name: launch_predicted_path_checker + default: "false" + - arg: + name: launch_control_evaluator + default: "false" diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 95f15f59fb..29378cc0c8 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -9,6 +9,7 @@ + @@ -113,7 +114,9 @@ - + + + diff --git a/autoware_launch/launch/components/tier4_control_component.launch.xml b/autoware_launch/launch/components/tier4_control_component.launch.xml index d23a3c42c5..99cfe7484f 100644 --- a/autoware_launch/launch/components/tier4_control_component.launch.xml +++ b/autoware_launch/launch/components/tier4_control_component.launch.xml @@ -1,13 +1,13 @@ + + + - - - @@ -43,10 +43,7 @@ - - - diff --git a/autoware_launch/launch/e2e_simulator.launch.xml b/autoware_launch/launch/e2e_simulator.launch.xml index b1a5d6ee8b..3237754c48 100644 --- a/autoware_launch/launch/e2e_simulator.launch.xml +++ b/autoware_launch/launch/e2e_simulator.launch.xml @@ -10,6 +10,7 @@ + @@ -51,6 +52,7 @@ + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index 8780578a6e..df5f591fc4 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -9,6 +9,7 @@ + @@ -43,6 +44,7 @@ + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index bc601cb30f..b7e21999f1 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -8,6 +8,7 @@ + @@ -58,6 +59,7 @@ + From c3649a6f57666f1e175bc2309937d9ffa696afe1 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 19 Nov 2024 13:22:36 +0900 Subject: [PATCH 11/25] feat: add an option of odometry uncertainty consideration in multi_object_tracker_node (#1196) feat: add an option of odometry uncertainty consideration in multi_object_tracker_node.param.yaml Signed-off-by: Taekjin LEE --- .../multi_object_tracker/multi_object_tracker_node.param.yaml | 1 + 1 file changed, 1 insertion(+) 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 index 006c179ae1..5a272a67e0 100644 --- 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 @@ -13,6 +13,7 @@ publish_rate: 10.0 world_frame_id: map enable_delay_compensation: true + consider_odometry_uncertainty: false # debug parameters publish_processing_time: true From e32c5c7858d16491b101db10efa2c122e2265885 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 19 Nov 2024 19:21:58 +0900 Subject: [PATCH 12/25] fix: default value for control_module_preset (#1242) Signed-off-by: Takayuki Murooka --- autoware_launch/launch/planning_simulator.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index b7e21999f1..be175553b7 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -8,7 +8,7 @@ - + From bb90f514a5c05f024e91ad0b4145af51705be7c9 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Wed, 20 Nov 2024 09:40:13 +0900 Subject: [PATCH 13/25] fix: default value for control_module_preset (#1243) Signed-off-by: Shintaro Sakoda --- autoware_launch/launch/logging_simulator.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index df5f591fc4..f1a9ad5fab 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -9,7 +9,7 @@ - + From ea30ec025d1123ffcb09eb4a48214c69ff2b6a3e Mon Sep 17 00:00:00 2001 From: Kazunori-Nakajima <169115284+Kazunori-Nakajima@users.noreply.github.com> Date: Wed, 20 Nov 2024 23:56:10 +0900 Subject: [PATCH 14/25] feat(processing_time_checker): update processing time list (#1236) Signed-off-by: Kasunori-Nakajima --- .../processing_time_checker.param.yaml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/autoware_launch/config/system/processing_time_checker/processing_time_checker.param.yaml b/autoware_launch/config/system/processing_time_checker/processing_time_checker.param.yaml index 033b20d234..526e413ea1 100644 --- a/autoware_launch/config/system/processing_time_checker/processing_time_checker.param.yaml +++ b/autoware_launch/config/system/processing_time_checker/processing_time_checker.param.yaml @@ -2,6 +2,7 @@ ros__parameters: update_rate: 10.0 processing_time_topic_name_list: + - /control/control_evaluator/debug/processing_time_ms - /control/control_validator/debug/processing_time_ms - /control/trajectory_follower/controller_node_exe/lateral/debug/processing_time_ms - /control/trajectory_follower/controller_node_exe/longitudinal/debug/processing_time_ms @@ -9,6 +10,9 @@ - /control/vehicle_cmd_gate/debug/processing_time_ms - /perception/object_recognition/prediction/map_based_prediction/debug/processing_time_ms - /perception/object_recognition/tracking/multi_object_tracker/debug/processing_time_ms + - /planning/mission_planning/mission_planner/debug/processing_time_ms + - /planning/mission_planning/route_selector/debug/processing_time_ms + - /planning/planning_evaluator/debug/processing_time_ms - /planning/planning_validator/debug/processing_time_ms - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/avoidance_by_lane_change/processing_time_ms - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/dynamic_obstacle_avoidance/processing_time_ms @@ -37,6 +41,7 @@ - /planning/scenario_planning/lane_driving/motion_planning/path_optimizer/debug/processing_time_ms - /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/processing_time_ms - /planning/scenario_planning/parking/costmap_generator/debug/processing_time_ms + - /planning/scenario_planning/parking/freespace_planner/debug/processing_time_ms - /planning/scenario_planning/scenario_selector/debug/processing_time_ms - /planning/scenario_planning/velocity_smoother/debug/processing_time_ms - /simulation/shape_estimation/debug/processing_time_ms From 6f09415455e7744982d37c01b5fc8a6a3d481beb Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 25 Nov 2024 14:43:51 +0900 Subject: [PATCH 15/25] feat(autonomous_emergency_braking) add params for limiting imu path with lat deviation (#1244) add params Signed-off-by: Daniel Sanchez --- .../autonomous_emergency_braking.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml b/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml index 710001ec58..99ca4d4ef5 100644 --- a/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml +++ b/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml @@ -3,10 +3,12 @@ # Ego path calculation use_predicted_trajectory: true use_imu_path: true + limit_imu_path_lat_dev: false use_pointcloud_data: true use_predicted_object_data: false use_object_velocity_calculation: true check_autoware_state: true + imu_path_lat_dev_threshold: 1.75 min_generated_imu_path_length: 0.5 max_generated_imu_path_length: 10.0 imu_prediction_time_horizon: 1.5 From 350083c12590235afa13d82fd6347c96fe691daa Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 26 Nov 2024 09:17:26 +0900 Subject: [PATCH 16/25] feat(scan_ground_filter): update grid size for ground segmentation (#1223) feat: update grid size for ground segmentation The grid size for ground segmentation has been updated from 0.1 to 0.5. This change improves the performance with the new grid data structure. Signed-off-by: Taekjin LEE --- .../ground_segmentation/ground_segmentation.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml b/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml index 0237671ccf..cc7c52ed47 100644 --- a/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml +++ b/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml @@ -24,7 +24,7 @@ use_virtual_ground_point: True split_height_distance: 0.2 non_ground_height_threshold: 0.20 - grid_size_m: 0.1 + grid_size_m: 0.5 grid_mode_switch_radius: 20.0 gnd_grid_buffer_size: 4 detection_range_z_max: 2.5 From ce7fe450b8927c601216303d87258c04d75df74e Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Tue, 26 Nov 2024 14:10:29 +0900 Subject: [PATCH 17/25] refactor(lane_change): refactor lane change parameters (#1247) refactor lane change params Signed-off-by: mohammad alqudah --- .../lane_change/lane_change.param.yaml | 51 +++++++++---------- 1 file changed, 23 insertions(+), 28 deletions(-) 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 380fe6281e..3651222c0e 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 @@ -1,42 +1,35 @@ /**: ros__parameters: lane_change: - backward_lane_length: 200.0 #[m] - prepare_duration: 4.0 # [s] - + backward_lane_length: 200.0 backward_length_buffer_for_end_of_lane: 3.0 # [m] backward_length_buffer_for_blocking_object: 3.0 # [m] backward_length_from_intersection: 5.0 # [m] - lane_changing_lateral_jerk: 0.5 # [m/s3] - - minimum_lane_changing_velocity: 2.78 # [m/s] - prediction_time_resolution: 0.5 # [s] - longitudinal_acceleration_sampling_num: 5 - lateral_acceleration_sampling_num: 3 - # side walk parked vehicle object_check_min_road_shoulder_width: 0.5 # [m] object_shiftable_ratio_threshold: 0.6 # turn signal min_length_for_turn_signal_activation: 10.0 # [m] - length_ratio_for_turn_signal_deactivation: 0.8 # ratio (desired end position) - # longitudinal acceleration - min_longitudinal_acc: -1.0 - max_longitudinal_acc: 1.0 - - skip_process: - longitudinal_distance_diff_threshold: - prepare: 1.0 - lane_changing: 1.0 + # trajectory generation + trajectory: + prepare_duration: 4.0 + lateral_jerk: 0.5 + min_longitudinal_acc: -1.0 + max_longitudinal_acc: 1.0 + th_prepare_length_diff: 1.0 + th_lane_changing_length_diff: 1.0 + min_lane_changing_velocity: 2.78 + lon_acc_sampling_num: 5 + lat_acc_sampling_num: 3 # safety check safety_check: allow_loose_check_for_cancel: true enable_target_lane_bound_check: true - collision_check_yaw_diff_threshold: 3.1416 + stopped_object_velocity_threshold: 1.0 # [m/s] execution: expected_front_deceleration: -1.0 expected_rear_deceleration: -1.0 @@ -93,14 +86,16 @@ pedestrian: true # collision check - enable_collision_check_for_prepare_phase: - general_lanes: false - intersection: true - turns: true - stopped_object_velocity_threshold: 1.0 # [m/s] - check_objects_on_current_lanes: false - check_objects_on_other_lanes: false - use_all_predicted_path: false + collision_check: + enable_for_prepare_phase: + general_lanes: false + intersection: true + turns: true + prediction_time_resolution: 0.5 + yaw_diff_threshold: 3.1416 + check_current_lanes: false + check_other_lanes: false + use_all_predicted_paths: false # lane change regulations regulation: From d91c508a2dce751b158460995434b601d7e53c21 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim <36835765+ahmeddesokyebrahim@users.noreply.github.com> Date: Tue, 26 Nov 2024 19:02:40 +0200 Subject: [PATCH 18/25] fix(static_obstacle_avoidance): improve avoidance for parked NPCs (#1129) Signed-off-by: Ahmed Ebrahim Signed-off-by: beyza --- .../static_obstacle_avoidance.param.yaml | 36 +++++++++---------- 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml index 31e35dcad5..3480bb66e5 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml @@ -23,9 +23,9 @@ th_moving_time: 2.0 # [s] longitudinal_margin: 0.0 # [m] lateral_margin: - soft_margin: 0.7 # [m] + soft_margin: 0.5 # [m] hard_margin: 0.2 # [m] - hard_margin_for_parked_vehicle: 0.7 # [m] + hard_margin_for_parked_vehicle: 0.2 # [m] max_expand_ratio: 0.0 # [-] FOR DEVELOPER envelope_buffer_margin: 0.1 # [m] FOR DEVELOPER th_error_eclipse_long_radius : 0.6 # [m] @@ -34,9 +34,9 @@ th_moving_time: 2.0 longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.7 + soft_margin: 0.5 hard_margin: 0.2 - hard_margin_for_parked_vehicle: 0.7 + hard_margin_for_parked_vehicle: 0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 th_error_eclipse_long_radius : 0.6 @@ -45,9 +45,9 @@ th_moving_time: 2.0 longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.7 + soft_margin: 0.5 hard_margin: 0.2 - hard_margin_for_parked_vehicle: 0.7 + hard_margin_for_parked_vehicle: 0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 th_error_eclipse_long_radius : 0.6 @@ -56,9 +56,9 @@ th_moving_time: 2.0 longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.7 + soft_margin: 0.5 hard_margin: 0.2 - hard_margin_for_parked_vehicle: 0.7 + hard_margin_for_parked_vehicle: 0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 th_error_eclipse_long_radius : 0.6 @@ -67,7 +67,7 @@ th_moving_time: 1.0 longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.7 + soft_margin: 0.5 hard_margin: -0.2 hard_margin_for_parked_vehicle: -0.2 max_expand_ratio: 0.0 @@ -76,33 +76,33 @@ bicycle: th_moving_speed: 0.28 th_moving_time: 1.0 - longitudinal_margin: 1.0 + longitudinal_margin: 0.6 lateral_margin: soft_margin: 0.7 hard_margin: 0.5 - hard_margin_for_parked_vehicle: 0.5 + hard_margin_for_parked_vehicle: 0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 th_error_eclipse_long_radius : 0.6 motorcycle: th_moving_speed: 1.0 th_moving_time: 1.0 - longitudinal_margin: 1.0 + longitudinal_margin: 0.6 lateral_margin: - soft_margin: 0.7 + soft_margin: 0.5 hard_margin: 0.3 - hard_margin_for_parked_vehicle: 0.3 + hard_margin_for_parked_vehicle: 0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 th_error_eclipse_long_radius : 0.6 pedestrian: th_moving_speed: 0.28 th_moving_time: 1.0 - longitudinal_margin: 1.0 + longitudinal_margin: 0.6 lateral_margin: soft_margin: 0.7 hard_margin: 0.5 - hard_margin_for_parked_vehicle: 0.5 + hard_margin_for_parked_vehicle: 0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 th_error_eclipse_long_radius : 0.6 @@ -232,7 +232,7 @@ # avoidance distance parameters longitudinal: min_prepare_time: 1.0 # [s] - max_prepare_time: 3.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] FOR DEVELOPER @@ -294,7 +294,7 @@ velocity: [1.39, 4.17, 11.1] # [m/s] max_accel_values: [0.5, 0.5, 0.5] # [m/ss] min_jerk_values: [0.2, 0.2, 0.2] # [m/sss] - max_jerk_values: [1.0, 1.0, 1.0] # [m/sss] + max_jerk_values: [3.0, 3.0, 3.0] # [m/sss] # longitudinal constraints longitudinal: From e14b2c849950930475fc644b78e62630f2510cd7 Mon Sep 17 00:00:00 2001 From: beyzanurkaya <32412808+beyzanurkaya@users.noreply.github.com> Date: Tue, 26 Nov 2024 20:02:58 +0300 Subject: [PATCH 19/25] fix(dynamic_obstacle_avoidance): improve avoidance for moving NPCs (#1170) Signed-off-by: beyza --- .../dynamic_obstacle_avoidance.param.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/dynamic_obstacle_avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/dynamic_obstacle_avoidance.param.yaml index aa1fdb3048..9bba8c52dc 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/dynamic_obstacle_avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/dynamic_obstacle_avoidance.param.yaml @@ -56,10 +56,10 @@ object_path_base: min_longitudinal_polygon_margin: 3.0 # [m] - lat_offset_from_obstacle: 1.0 # [m] - margin_distance_around_pedestrian: 2.0 # [m] + lat_offset_from_obstacle: 0.3 # [m] + margin_distance_around_pedestrian: 0.8 # [m] predicted_path: - end_time_to_consider: 2.0 # [s] + end_time_to_consider: 1.0 # [s] threshold_confidence: 0.0 # [] not probability max_lat_offset_to_avoid: 0.5 # [m] max_time_for_object_lat_shift: 0.0 # [s] From 44afd91fbf66f9c22539c699f19b008e2f6a56d1 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Wed, 27 Nov 2024 14:49:56 +0900 Subject: [PATCH 20/25] refactor(autoware_behavior_velocity_planner_common,autoware_behavior_velocity_planner): separate param files (#1254) Signed-off-by: Y.Hisaki --- .../behavior_velocity_planner.param.yaml | 5 ----- .../behavior_velocity_planner_common.param.yaml | 7 +++++++ .../launch/components/tier4_planning_component.launch.xml | 3 ++- 3 files changed, 9 insertions(+), 6 deletions(-) create mode 100644 autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner_common.param.yaml 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 b31506918a..49749cd129 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 @@ -4,8 +4,3 @@ backward_path_length: 5.0 behavior_output_path_interval: 1.0 stop_line_extend_length: 5.0 - max_accel: -2.8 - max_jerk: -5.0 - system_delay: 0.5 - delay_response_time: 0.5 - is_publish_debug_path: false # publish all debug path with lane id in each module diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner_common.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner_common.param.yaml new file mode 100644 index 0000000000..aff2aec9cf --- /dev/null +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner_common.param.yaml @@ -0,0 +1,7 @@ +/**: + ros__parameters: + max_accel: -2.8 + max_jerk: -5.0 + system_delay: 0.5 + delay_response_time: 0.5 + is_publish_debug_path: false # publish all debug path with lane id in each module diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml index 1f929543d4..a01a5fca17 100644 --- a/autoware_launch/launch/components/tier4_planning_component.launch.xml +++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml @@ -44,7 +44,8 @@ - + + From 72c84f116e5e1546e42e851b24ccfe67668552b0 Mon Sep 17 00:00:00 2001 From: "tomoya.kimura" Date: Wed, 27 Nov 2024 17:43:37 +0900 Subject: [PATCH 21/25] chore: rename codeowners file Signed-off-by: tomoya.kimura --- .github/{CODEOWNERS => _CODEOWNERS} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename .github/{CODEOWNERS => _CODEOWNERS} (100%) diff --git a/.github/CODEOWNERS b/.github/_CODEOWNERS similarity index 100% rename from .github/CODEOWNERS rename to .github/_CODEOWNERS From cf5cdb7225571c56256c4a3d8090e39229a0c694 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Thu, 28 Nov 2024 05:48:29 +0900 Subject: [PATCH 22/25] Revert "fix(dynamic_obstacle_avoidance): improve avoidance for moving NPCs (#1170)" This reverts commit e14b2c849950930475fc644b78e62630f2510cd7. --- .../dynamic_obstacle_avoidance.param.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/dynamic_obstacle_avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/dynamic_obstacle_avoidance.param.yaml index 9bba8c52dc..aa1fdb3048 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/dynamic_obstacle_avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/dynamic_obstacle_avoidance.param.yaml @@ -56,10 +56,10 @@ object_path_base: min_longitudinal_polygon_margin: 3.0 # [m] - lat_offset_from_obstacle: 0.3 # [m] - margin_distance_around_pedestrian: 0.8 # [m] + lat_offset_from_obstacle: 1.0 # [m] + margin_distance_around_pedestrian: 2.0 # [m] predicted_path: - end_time_to_consider: 1.0 # [s] + end_time_to_consider: 2.0 # [s] threshold_confidence: 0.0 # [] not probability max_lat_offset_to_avoid: 0.5 # [m] max_time_for_object_lat_shift: 0.0 # [s] From 9a4809d8593b581adcf5342bdd242a95d03d2085 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Thu, 28 Nov 2024 05:48:42 +0900 Subject: [PATCH 23/25] Revert "fix(static_obstacle_avoidance): improve avoidance for parked NPCs (#1129)" This reverts commit d91c508a2dce751b158460995434b601d7e53c21. --- .../static_obstacle_avoidance.param.yaml | 36 +++++++++---------- 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml index 3480bb66e5..31e35dcad5 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml @@ -23,9 +23,9 @@ th_moving_time: 2.0 # [s] longitudinal_margin: 0.0 # [m] lateral_margin: - soft_margin: 0.5 # [m] + soft_margin: 0.7 # [m] hard_margin: 0.2 # [m] - hard_margin_for_parked_vehicle: 0.2 # [m] + hard_margin_for_parked_vehicle: 0.7 # [m] max_expand_ratio: 0.0 # [-] FOR DEVELOPER envelope_buffer_margin: 0.1 # [m] FOR DEVELOPER th_error_eclipse_long_radius : 0.6 # [m] @@ -34,9 +34,9 @@ th_moving_time: 2.0 longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.5 + soft_margin: 0.7 hard_margin: 0.2 - hard_margin_for_parked_vehicle: 0.2 + hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 th_error_eclipse_long_radius : 0.6 @@ -45,9 +45,9 @@ th_moving_time: 2.0 longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.5 + soft_margin: 0.7 hard_margin: 0.2 - hard_margin_for_parked_vehicle: 0.2 + hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 th_error_eclipse_long_radius : 0.6 @@ -56,9 +56,9 @@ th_moving_time: 2.0 longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.5 + soft_margin: 0.7 hard_margin: 0.2 - hard_margin_for_parked_vehicle: 0.2 + hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 th_error_eclipse_long_radius : 0.6 @@ -67,7 +67,7 @@ th_moving_time: 1.0 longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.5 + soft_margin: 0.7 hard_margin: -0.2 hard_margin_for_parked_vehicle: -0.2 max_expand_ratio: 0.0 @@ -76,33 +76,33 @@ bicycle: th_moving_speed: 0.28 th_moving_time: 1.0 - longitudinal_margin: 0.6 + longitudinal_margin: 1.0 lateral_margin: soft_margin: 0.7 hard_margin: 0.5 - hard_margin_for_parked_vehicle: 0.2 + hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 th_error_eclipse_long_radius : 0.6 motorcycle: th_moving_speed: 1.0 th_moving_time: 1.0 - longitudinal_margin: 0.6 + longitudinal_margin: 1.0 lateral_margin: - soft_margin: 0.5 + soft_margin: 0.7 hard_margin: 0.3 - hard_margin_for_parked_vehicle: 0.2 + hard_margin_for_parked_vehicle: 0.3 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 th_error_eclipse_long_radius : 0.6 pedestrian: th_moving_speed: 0.28 th_moving_time: 1.0 - longitudinal_margin: 0.6 + longitudinal_margin: 1.0 lateral_margin: soft_margin: 0.7 hard_margin: 0.5 - hard_margin_for_parked_vehicle: 0.2 + hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 th_error_eclipse_long_radius : 0.6 @@ -232,7 +232,7 @@ # avoidance distance parameters longitudinal: min_prepare_time: 1.0 # [s] - max_prepare_time: 2.0 # [s] + max_prepare_time: 3.0 # [s] min_prepare_distance: 1.0 # [m] min_slow_down_speed: 1.38 # [m/s] buf_slow_down_speed: 0.56 # [m/s] FOR DEVELOPER @@ -294,7 +294,7 @@ velocity: [1.39, 4.17, 11.1] # [m/s] max_accel_values: [0.5, 0.5, 0.5] # [m/ss] min_jerk_values: [0.2, 0.2, 0.2] # [m/sss] - max_jerk_values: [3.0, 3.0, 3.0] # [m/sss] + max_jerk_values: [1.0, 1.0, 1.0] # [m/sss] # longitudinal constraints longitudinal: From 99a75f83f8d290a510f3d62100b88aaa1f15a55c Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Thu, 28 Nov 2024 11:30:09 +0900 Subject: [PATCH 24/25] feat(lane_change): add delay lane change parameters (#1256) add delay lane change parameters Signed-off-by: mohammad alqudah --- .../lane_change/lane_change.param.yaml | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) 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 3651222c0e..fe8915c784 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 @@ -6,10 +6,6 @@ backward_length_buffer_for_blocking_object: 3.0 # [m] backward_length_from_intersection: 5.0 # [m] - # side walk parked vehicle - object_check_min_road_shoulder_width: 0.5 # [m] - object_shiftable_ratio_threshold: 0.6 - # turn signal min_length_for_turn_signal_activation: 10.0 # [m] @@ -25,6 +21,13 @@ lon_acc_sampling_num: 5 lat_acc_sampling_num: 3 + # delay lane change + delay_lane_change: + enable: true + check_only_parked_vehicle: false + min_road_shoulder_width: 0.5 # [m] + th_parked_vehicle_shift_ratio: 0.6 + # safety check safety_check: allow_loose_check_for_cancel: true From 10d823de2972276a7a8a8e2da396da5277b7498f Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Thu, 28 Nov 2024 15:33:18 +0900 Subject: [PATCH 25/25] feat(autonomous_emergency_braking): add parameter to limit IMU path length and rename longitudinal offset (#1251) Signed-off-by: Kyoichi Sugahara --- .../autonomous_emergency_braking.param.yaml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml b/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml index 99ca4d4ef5..b23c3bbdd4 100644 --- a/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml +++ b/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml @@ -4,6 +4,7 @@ use_predicted_trajectory: true use_imu_path: true limit_imu_path_lat_dev: false + limit_imu_path_length: true use_pointcloud_data: true use_predicted_object_data: false use_object_velocity_calculation: true @@ -39,7 +40,7 @@ maximum_cluster_size: 10000 # RSS distance collision check - longitudinal_offset: 1.0 + longitudinal_offset_margin: 1.0 t_response: 1.0 a_ego_min: -3.0 a_obj_min: -1.0