Skip to content

Commit 4c6d043

Browse files
authored
feat(autoware_velocity_smoother): port the package from Autoware Universe (#299)
Signed-off-by: Ryohsuke Mitsudome <ryohsuke.mitsudome@tier4.jp>
1 parent 8180baf commit 4c6d043

32 files changed

+7771
-0
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,68 @@
1+
cmake_minimum_required(VERSION 3.14)
2+
project(autoware_velocity_smoother)
3+
4+
find_package(autoware_cmake REQUIRED)
5+
autoware_package()
6+
7+
find_package(Boost REQUIRED)
8+
find_package(eigen3_cmake_module REQUIRED)
9+
find_package(Eigen3 REQUIRED)
10+
11+
include_directories(
12+
SYSTEM
13+
${EIGEN3_INCLUDE_DIR}
14+
)
15+
16+
set(MOTION_VELOCITY_SMOOTHER_SRC
17+
src/node.cpp
18+
)
19+
20+
set(SMOOTHER_SRC
21+
src/smoother/smoother_base.cpp
22+
src/smoother/l2_pseudo_jerk_smoother.cpp
23+
src/smoother/linf_pseudo_jerk_smoother.cpp
24+
src/smoother/jerk_filtered_smoother.cpp
25+
src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp
26+
src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp
27+
src/trajectory_utils.cpp
28+
src/resample.cpp
29+
)
30+
31+
ament_auto_add_library(smoother SHARED
32+
${SMOOTHER_SRC}
33+
)
34+
35+
ament_auto_add_library(${PROJECT_NAME}_node SHARED
36+
${MOTION_VELOCITY_SMOOTHER_SRC}
37+
)
38+
39+
target_link_libraries(${PROJECT_NAME}_node
40+
smoother
41+
)
42+
43+
rclcpp_components_register_node(${PROJECT_NAME}_node
44+
PLUGIN "autoware::velocity_smoother::VelocitySmootherNode"
45+
EXECUTABLE velocity_smoother_node
46+
)
47+
48+
if(BUILD_TESTING)
49+
ament_add_ros_isolated_gmock(test_smoother_functions
50+
test/test_smoother_functions.cpp
51+
)
52+
target_link_libraries(test_smoother_functions
53+
smoother
54+
)
55+
ament_add_ros_isolated_gtest(test_${PROJECT_NAME}
56+
test/test_velocity_smoother_node_interface.cpp
57+
)
58+
target_link_libraries(test_${PROJECT_NAME}
59+
${PROJECT_NAME}_node
60+
)
61+
endif()
62+
63+
64+
ament_auto_package(
65+
INSTALL_TO_SHARE
66+
launch
67+
config
68+
)

planning/autoware_velocity_smoother/README.md

+275
Large diffs are not rendered by default.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
/**:
2+
ros__parameters:
3+
resample:
4+
ds_resample: 0.1
5+
num_resample: 1
6+
delta_yaw_threshold: 0.785
7+
8+
latacc:
9+
enable_constant_velocity_while_turning: false
10+
constant_velocity_dist_threshold: 2.0
11+
12+
forward:
13+
max_acc: 1.0
14+
min_acc: -1.0
15+
max_jerk: 0.3
16+
min_jerk: -0.3
17+
kp: 0.3
18+
19+
backward:
20+
start_jerk: -0.1
21+
min_jerk_mild_stop: -0.3
22+
min_jerk: -1.5
23+
min_acc_mild_stop: -1.0
24+
min_acc: -2.5
25+
span_jerk: -0.01
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
/**:
2+
ros__parameters:
3+
jerk_weight: 10.0 # weight for "smoothness" cost for jerk
4+
over_v_weight: 100000.0 # weight for "over speed limit" cost
5+
over_a_weight: 5000.0 # weight for "over accel limit" cost
6+
over_j_weight: 2000.0 # weight for "over jerk limit" cost
7+
jerk_filter_ds: 0.1 # resampling ds for jerk filter
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
/**:
2+
ros__parameters:
3+
pseudo_jerk_weight: 100.0 # weight for "smoothness" cost
4+
over_v_weight: 100000.0 # weight for "over speed limit" cost
5+
over_a_weight: 1000.0 # weight for "over accel limit" cost
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
/**:
2+
ros__parameters:
3+
pseudo_jerk_weight: 200.0 # weight for "smoothness" cost
4+
over_v_weight: 100000.0 # weight for "over speed limit" cost
5+
over_a_weight: 5000.0 # weight for "over accel limit" cost
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
/**:
2+
ros__parameters:
3+
# constraints param for normal driving
4+
max_vel: 11.1 # max velocity limit [m/s]
5+
6+
normal:
7+
min_acc: -0.5 # min deceleration [m/ss]
8+
max_acc: 1.0 # max acceleration [m/ss]
9+
min_jerk: -0.5 # min jerk [m/sss]
10+
max_jerk: 1.0 # max jerk [m/sss]
11+
12+
# constraints to be observed
13+
limit:
14+
min_acc: -2.5 # min deceleration limit [m/ss]
15+
max_acc: 1.0 # max acceleration limit [m/ss]
16+
min_jerk: -1.5 # min jerk limit [m/sss]
17+
max_jerk: 1.5 # max jerk limit [m/sss]
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,63 @@
1+
/**:
2+
ros__parameters:
3+
# motion state constraints
4+
max_velocity: 20.0 # max velocity limit [m/s]
5+
stop_decel: 0.0 # deceleration at a stop point[m/ss]
6+
7+
# external velocity limit parameter
8+
margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m]
9+
10+
# ---- curve parameters ----
11+
# - common parameters -
12+
curvature_calculation_distance: 5.0 # distance of points while curvature is calculating for the steer rate and lateral acceleration limit [m]
13+
# - lateral acceleration limit parameters -
14+
enable_lateral_acc_limit: true # To toggle the lateral acc filter on and off. You can switch it dynamically at runtime.
15+
max_lateral_accel: 0.8 # max lateral acceleration limit [m/ss]
16+
min_curve_velocity: 2.74 # min velocity at lateral acceleration limit and steering angle rate limit [m/s]
17+
decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit
18+
decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit
19+
min_decel_for_lateral_acc_lim_filter: -2.5 # deceleration limit applied in the lateral acceleration filter to avoid sudden braking [m/ss]
20+
# - steering angle rate limit parameters -
21+
enable_steering_rate_limit: true # To toggle the steer rate filter on and off. You can switch it dynamically at runtime.
22+
max_steering_angle_rate: 40.0 # maximum steering angle rate [degree/s]
23+
resample_ds: 0.1 # distance between trajectory points [m]
24+
curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m]
25+
26+
# engage & replan parameters
27+
replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s]
28+
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)
29+
engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement)
30+
engage_exit_ratio: 0.5 # exit engage sequence to normal velocity planning when the velocity exceeds engage_exit_ratio x engage_velocity.
31+
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]
32+
33+
# stop velocity
34+
stopping_velocity: 2.778 # change target velocity to this value before v=0 point [m/s]
35+
stopping_distance: 0.0 # distance for the stopping_velocity [m]. 0 means the stopping velocity is not applied.
36+
37+
# path extraction parameters
38+
extract_ahead_dist: 200.0 # forward trajectory distance used for planning [m]
39+
extract_behind_dist: 5.0 # backward trajectory distance used for planning [m]
40+
delta_yaw_threshold: 1.0472 # Allowed delta yaw between ego pose and trajectory pose [radian]
41+
42+
# resampling parameters for optimization
43+
max_trajectory_length: 200.0 # max trajectory length for resampling [m]
44+
min_trajectory_length: 150.0 # min trajectory length for resampling [m]
45+
resample_time: 2.0 # resample total time for dense sampling [s]
46+
dense_resample_dt: 0.2 # resample time interval for dense sampling [s]
47+
dense_min_interval_distance: 0.1 # minimum points-interval length for dense sampling [m]
48+
sparse_resample_dt: 0.5 # resample time interval for sparse sampling [s]
49+
sparse_min_interval_distance: 4.0 # minimum points-interval length for sparse sampling [m]
50+
51+
# resampling parameters for post process
52+
post_max_trajectory_length: 300.0 # max trajectory length for resampling [m]
53+
post_min_trajectory_length: 30.0 # min trajectory length for resampling [m]
54+
post_resample_time: 10.0 # resample total time for dense sampling [s]
55+
post_dense_resample_dt: 0.1 # resample time interval for dense sampling [s]
56+
post_dense_min_interval_distance: 0.1 # minimum points-interval length for dense sampling [m]
57+
post_sparse_resample_dt: 0.1 # resample time interval for sparse sampling [s]
58+
post_sparse_min_interval_distance: 1.0 # minimum points-interval length for sparse sampling [m]
59+
60+
# system
61+
over_stop_velocity_warn_thr: 1.389 # used to check if the optimization exceeds the input velocity on the stop point
62+
63+
plan_from_ego_speed_on_manual_mode: true # planning is done from ego velocity/acceleration on MANUAL mode. This should be true for smooth transition from MANUAL to AUTONOMOUS, but could be false for debugging.

0 commit comments

Comments
 (0)