Skip to content

Commit

Permalink
Merge branch 'main' into feat/out_of_lane-more_stable-universe
Browse files Browse the repository at this point in the history
  • Loading branch information
maxime-clem authored Nov 15, 2023
2 parents 6b237ef + 81b9f11 commit 28d4166
Show file tree
Hide file tree
Showing 46 changed files with 1,679 additions and 170 deletions.
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
/**:
ros__parameters:
publish_debug_pointcloud: false
use_predicted_trajectory: true
use_imu_path: true
voxel_grid_x: 0.05
Expand All @@ -11,7 +12,9 @@
t_response: 1.0
a_ego_min: -3.0
a_obj_min: -1.0
prediction_time_horizon: 1.5
prediction_time_interval: 0.1
imu_prediction_time_horizon: 1.5
imu_prediction_time_interval: 0.1
mpc_prediction_time_horizon: 1.5
mpc_prediction_time_interval: 0.1
collision_keeping_sec: 0.0
aeb_hz: 10.0
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@
check_external_emergency_heartbeat: false
use_start_request: false
enable_cmd_limit_filter: true
filter_activated_count_threshold: 5
filter_activated_velocity_threshold: 1.0
external_emergency_stop_heartbeat_timeout: 0.0
stop_hold_acceleration: -1.5
emergency_acceleration: -2.4
Expand Down
4 changes: 2 additions & 2 deletions autoware_launch/config/localization/ekf_localizer.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,9 @@

# for diagnostics
pose_no_update_count_threshold_warn: 50
pose_no_update_count_threshold_error: 250
pose_no_update_count_threshold_error: 100
twist_no_update_count_threshold_warn: 50
twist_no_update_count_threshold_error: 250
twist_no_update_count_threshold_error: 100

# for velocity measurement limitation (Set 0.0 if you want to ignore)
threshold_observable_velocity_mps: 0.0 # [m/s]
15 changes: 14 additions & 1 deletion autoware_launch/config/localization/ndt_scan_matcher.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,12 @@
converged_param_nearest_voxel_transformation_likelihood: 2.3

# The number of particles to estimate initial pose
initial_estimate_particles_num: 100
initial_estimate_particles_num: 200

# The number of initial random trials in the TPE (Tree-Structured Parzen Estimator).
# This value should be equal to or less than 'initial_estimate_particles_num' and more than 0.
# If it is equal to 'initial_estimate_particles_num', the search will be the same as a full random search.
n_startup_trials: 20

# Tolerance of timestamp difference between current time and sensor pointcloud. [sec]
lidar_topic_timeout_sec: 1.0
Expand All @@ -67,6 +72,14 @@
0.0, 0.0, 0.0, 0.0, 0.0, 0.000625,
]

# 2D Real-time covariance estimation with multiple searches (output_pose_covariance is the minimum value)
use_covariance_estimation: false

# Offset arrangement in covariance estimation [m]
# initial_pose_offset_model_x & initial_pose_offset_model_y must have the same number of elements.
initial_pose_offset_model_x: [0.0, 0.0, 0.5, -0.5, 1.0, -1.0]
initial_pose_offset_model_y: [0.5, -0.5, 0.0, 0.0, 0.0, 0.0]

# Regularization switch
regularization_enabled: false

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
/**:
ros__parameters:
min_points_num:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[10, 10, 10, 10, 10,10, 10, 10]

max_points_num:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[10, 10, 10, 10, 10,10, 10, 10]

min_points_and_distance_ratio:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[800.0, 880.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0]
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
/**:
ros__parameters:
tracker_ignore_label:
UNKNOWN : true
CAR : false
TRUCK : false
BUS : false
TRAILER : false
MOTORCYCLE : false
BICYCLE : false
PEDESTRIAN : false
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
ros__parameters:
enable_delay_compensation: true
prediction_time_horizon: 10.0 #[s]
lateral_control_time_horizon: 5.0 #[s]
prediction_sampling_delta_time: 0.5 #[s]
min_velocity_for_map_based_prediction: 1.39 #[m/s]
min_crosswalk_user_velocity: 1.39 #[m/s]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,10 @@
max_dist_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[4.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN
4.0, 4.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRAILER
4.0, 8.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #CAR
4.0, 6.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #TRUCK
4.0, 6.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #BUS
4.0, 6.0, 8.0, 8.0, 8.0, 1.0, 1.0, 1.0, #TRAILER
3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #MOTORBIKE
3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #BICYCLE
2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
/**:
ros__parameters:
car_tracker: "linear_motion_tracker"
truck_tracker: "linear_motion_tracker"
bus_tracker: "linear_motion_tracker"
trailer_tracker: "linear_motion_tracker"
pedestrian_tracker: "linear_motion_tracker"
bicycle_tracker: "linear_motion_tracker"
motorcycle_tracker: "linear_motion_tracker"
car_tracker: "constant_turn_rate_motion_tracker"
truck_tracker: "constant_turn_rate_motion_tracker"
bus_tracker: "constant_turn_rate_motion_tracker"
trailer_tracker: "constant_turn_rate_motion_tracker"
pedestrian_tracker: "constant_turn_rate_motion_tracker"
bicycle_tracker: "constant_turn_rate_motion_tracker"
motorcycle_tracker: "constant_turn_rate_motion_tracker"
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
# general parameters for radar_object_tracker node
/**:
ros__parameters:
# basic settings
world_frame_id: "map"
tracker_lifetime: 1.0 # [sec]
measurement_count_threshold: 3 # object will be published if it is tracked more than this threshold

# delay compensate parameters
publish_rate: 10.0
enable_delay_compensation: true

# logging
enable_logging: false
logging_file_path: "/tmp/association_log.json"

# filtering
## 1. distance based filtering: remove closer objects than this threshold
use_distance_based_noise_filtering: true
minimum_range_threshold: 60.0 # [m]

## 2. lanelet map based filtering
use_map_based_noise_filtering: true
max_distance_from_lane: 5.0 # [m]
max_angle_diff_from_lane: 0.785398 # [rad] (45 deg)
max_lateral_velocity: 7.0 # [m/s]
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
default:
# This file defines the parameters for the linear motion tracker.
# All this parameter coordinate is assumed to be in the vehicle coordinate system.
# So, the x axis is pointing to the front of the vehicle, y axis is pointing to the left of the vehicle.
ekf_params:
# random walk noise is used to model the acceleration noise
process_noise_std: # [m/s^2]
x: 0.5
y: 0.5
yaw: 0.1
vx: 1.0 # assume 1m/s velocity noise
wz: 0.4
measurement_noise_std:
x: 4.0 # [m]
y: 4.0 # [m]
# y: 0.02 # rad/m if use_polar_coordinate_in_measurement_noise is true
yaw: 0.2 # [rad]
vx: 10 # [m/s]
initial_covariance_std:
x: 3.0 # [m]
y: 6.0 # [m]
yaw: 10.0 # [rad]
vx: 100.0 # [m/s]
wz: 10.0 # [rad/s]
# input flag
trust_yaw_input: false # set true if yaw input of sensor is reliable
trust_twist_input: false # set true if twist input of sensor is reliable
use_polar_coordinate_in_measurement_noise: false # set true if you want to define the measurement noise in polar coordinate
assume_zero_yaw_rate: false # set true if you want to assume zero yaw rate
# output limitation
limit:
max_speed: 80.0 # [m/s]
# low pass filter is used to smooth the yaw and shape estimation
low_pass_filter:
time_constant: 1.0 # [s]
sampling_time: 0.1 # [s]
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
default:
# This file defines the parameters for the linear motion tracker.
# All this parameter coordinate is assumed to be in the vehicle coordinate system.
# So, the x axis is pointing to the front of the vehicle, y axis is pointing to the left of the vehicle.
ekf_params:
# random walk noise is used to model the acceleration noise
process_noise_std: # [m/s^2]
ax: 0.98 # assume 0.1G acceleration noise
ay: 0.98
vx: 1.0 # assume 1m/s velocity noise
vy: 1.0
x: 1.0 # assume 1m position noise
y: 1.0
measurement_noise_std:
x: 0.6 # [m]
# y: 4.0 # [m]
y: 0.01 # rad/m if use_polar_coordinate_in_measurement_noise is true
vx: 10 # [m/s]
vy: 100 # [m/s]
initial_covariance_std:
x: 3.0 # [m]
y: 6.0 # [m]
vx: 1000.0 # [m/s]
vy: 1000.0 # [m/s]
ax: 1000.0 # [m/s^2]
ay: 1000.0 # [m/s^2]
estimate_acc: false # set true if you want to estimate the acceleration
# input flag
trust_yaw_input: false # set true if yaw input of sensor is reliable
trust_twist_input: false # set true if twist input of sensor is reliable
use_polar_coordinate_in_measurement_noise: true # set true if you want to define the measurement noise in polar coordinate
# output limitation
limit:
max_speed: 80.0 # [m/s]
# low pass filter is used to smooth the yaw and shape estimation
low_pass_filter:
time_constant: 1.0 # [s]
sampling_time: 0.1 # [s]
Loading

0 comments on commit 28d4166

Please sign in to comment.