forked from tier4/autoware.universe
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
feat(obstacle_cruise_planner): add new package (tier4#570)
* feat(obstacle_velocity_planner): add obstacle_velocity_planner Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * udpate yaml Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * update dependency Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix maybe-unused false positive error Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * Tier IV -> TIER IV Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix some reviews Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix some reviews Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * minor change Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * minor changes Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * use obstacle_stop by default Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix compile error Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * obstacle_velocity -> adaptive_cruise Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix for autoware meta repository Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix compile error on CI Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * add min_ego_accel_for_rss Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix CI error Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * rename to obstacle_cruise_planner Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix tier4_planning_launch Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix humble CI Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
- Loading branch information
1 parent
3eeb501
commit f32f496
Showing
35 changed files
with
6,380 additions
and
3 deletions.
There are no files selected for viewing
123 changes: 123 additions & 0 deletions
123
...g/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,123 @@ | ||
/**: | ||
ros__parameters: | ||
common: | ||
planning_algorithm: "pid_base" # currently supported algorithm is "pid_base" | ||
|
||
is_showing_debug_info: true | ||
|
||
# longitudinal info | ||
idling_time: 4.0 # idling time to detect front vehicle starting deceleration [s] | ||
min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss] | ||
min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] | ||
safe_distance_margin : 6.0 # This is also used as a stop margin [m] | ||
min_strong_accel: -3.0 # obstacle stop requiring deceleration less than this value will be ignored [m/ss] | ||
|
||
lpf_gain_for_accel: 0.2 # gain of low pass filter for ego acceleration [-] | ||
|
||
nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index | ||
nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index | ||
min_behavior_stop_margin: 3.0 # [m] | ||
|
||
cruise_obstacle_type: | ||
unknown: true | ||
car: true | ||
truck: true | ||
bus: true | ||
trailer: true | ||
motorcycle: true | ||
bicycle: false | ||
pedestrian: false | ||
|
||
stop_obstacle_type: | ||
unknown: true | ||
car: true | ||
truck: true | ||
bus: true | ||
trailer: true | ||
motorcycle: true | ||
bicycle: true | ||
pedestrian: true | ||
|
||
obstacle_filtering: | ||
rough_detection_area_expand_width : 5.0 # rough lateral margin for rough detection area expansion [m] | ||
detection_area_expand_width : 0.0 # lateral margin for precise detection area expansion | ||
decimate_trajectory_step_length : 2.0 # longitudinal step length to calculate trajectory polygon for collision checking | ||
|
||
# if crossing vehicle is decided as target obstacles or not | ||
crossing_obstacle_velocity_threshold : 3.0 # velocity threshold for crossing obstacle for cruise or stop [m/s] | ||
crossing_obstacle_traj_angle_threshold : 1.22 # [rad] = 70 [deg], yaw threshold of crossing obstacle against the nearest trajectory point for cruise or stop | ||
collision_time_margin : 8.0 # time threshold of collision between obstacle adn ego for cruise or stop [s] | ||
|
||
ego_obstacle_overlap_time_threshold : 1.0 # time threshold to decide cut-in obstacle for cruise or stop [s] | ||
max_prediction_time_for_collision_check : 20.0 # prediction time to check collision between obstacle and ego | ||
|
||
ignored_outside_obstacle_type: | ||
unknown: false | ||
car: false | ||
truck: false | ||
bus: false | ||
trailer: false | ||
motorcycle: false | ||
bicycle: true | ||
pedestrian: true | ||
|
||
pid_based_planner: | ||
# use_predicted_obstacle_pose: false | ||
|
||
# PID gains to keep safe distance with the front vehicle | ||
kp: 0.6 | ||
ki: 0.0 | ||
kd: 0.5 | ||
|
||
min_accel_during_cruise: -2.0 # minimum acceleration during cruise to slow down [m/ss] | ||
|
||
output_ratio_during_accel: 2.5 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-] | ||
vel_to_acc_weight: 8.0 # target acceleration is calculated by (target_velocity - current_velocity) * vel_to_acc_weight [-] | ||
|
||
min_cruise_target_vel: 0.0 # minimum target velocity during slow down [m/s] | ||
|
||
obstacle_velocity_threshold_from_cruise_to_stop : 3.0 # stop planning is executed to the obstacle whose velocity is less than this value [m/s] | ||
|
||
optimization_based_planner: | ||
limit_min_accel: -3.0 | ||
resampling_s_interval: 2.0 | ||
dense_resampling_time_interval: 0.1 | ||
sparse_resampling_time_interval: 1.0 | ||
dense_time_horizon: 5.0 | ||
max_time_horizon: 25.0 | ||
max_trajectory_length: 200.0 | ||
velocity_margin: 0.1 #[m/s] | ||
|
||
# Parameters for safe distance | ||
safe_distance_margin: 5.0 | ||
t_dangerous: 0.5 | ||
|
||
# Parameters for collision detection | ||
collision_time_threshold: 10.0 | ||
object_zero_velocity_threshold: 3.0 #[m/s] | ||
object_low_velocity_threshold: 3.0 #[m/s] | ||
external_velocity_limit: 20.0 #[m/s] | ||
delta_yaw_threshold_of_object_and_ego: 90.0 # [deg] | ||
delta_yaw_threshold_of_nearest_index: 60.0 # [deg] | ||
collision_duration_threshold_of_object_and_ego: 1.0 # [s] | ||
|
||
# Switch for each functions | ||
enable_adaptive_cruise: true | ||
use_object_acceleration: false | ||
use_hd_map: true | ||
|
||
# For initial Motion | ||
replan_vel_deviation: 5.0 # velocity deviation to replan initial velocity [m/s] | ||
engage_velocity: 0.25 # engage velocity threshold [m/s] (if the trajectory velocity is higher than this value, use this velocity for engage vehicle speed) | ||
engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement) | ||
engage_exit_ratio: 0.5 # exit engage sequence to normal velocity planning when the velocity exceeds engage_exit_ratio x engage_velocity. | ||
stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m] | ||
|
||
# Weights for optimization | ||
max_s_weight: 100.0 | ||
max_v_weight: 1.0 | ||
over_s_safety_weight: 1000000.0 | ||
over_s_ideal_weight: 50.0 | ||
over_v_weight: 500000.0 | ||
over_a_weight: 5000.0 | ||
over_j_weight: 10000.0 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,39 @@ | ||
cmake_minimum_required(VERSION 3.14) | ||
project(obstacle_cruise_planner) | ||
|
||
find_package(autoware_cmake REQUIRED) | ||
autoware_package() | ||
|
||
find_package(Eigen3 REQUIRED) | ||
|
||
ament_auto_add_library(obstacle_cruise_planner_core SHARED | ||
src/node.cpp | ||
src/utils.cpp | ||
src/polygon_utils.cpp | ||
src/optimization_based_planner/resample.cpp | ||
src/optimization_based_planner/box2d.cpp | ||
src/optimization_based_planner/velocity_optimizer.cpp | ||
src/optimization_based_planner/optimization_based_planner.cpp | ||
src/pid_based_planner/pid_based_planner.cpp | ||
) | ||
|
||
rclcpp_components_register_node(obstacle_cruise_planner_core | ||
PLUGIN "motion_planning::ObstacleCruisePlannerNode" | ||
EXECUTABLE obstacle_cruise_planner | ||
) | ||
|
||
if(BUILD_TESTING) | ||
find_package(ament_lint_auto REQUIRED) | ||
ament_lint_auto_find_test_dependencies() | ||
endif() | ||
|
||
ament_auto_package( | ||
INSTALL_TO_SHARE | ||
launch | ||
config | ||
) | ||
|
||
install(PROGRAMS | ||
scripts/trajectory_visualizer.py | ||
DESTINATION lib/${PROJECT_NAME} | ||
) |
Oops, something went wrong.