Skip to content

Commit

Permalink
update and add parameter about radar_object_tracker for far away dete…
Browse files Browse the repository at this point in the history
…ction

Signed-off-by: yoshiri <[email protected]>
  • Loading branch information
YoshiRi committed Oct 27, 2023
1 parent 5469244 commit 25e38f6
Show file tree
Hide file tree
Showing 6 changed files with 70 additions and 25 deletions.
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
Expand Up @@ -4,12 +4,11 @@
# basic settings
world_frame_id: "map"
tracker_lifetime: 1.0 # [sec]
# if empty, use default config declared in this package
tracking_config_directory: ""
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: false
enable_delay_compensation: true

# logging
enable_logging: false
Expand All @@ -18,10 +17,10 @@
# filtering
## 1. distance based filtering: remove closer objects than this threshold
use_distance_based_noise_filtering: true
minimum_range_threshold: 70.0 # [m]
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: 5.0 # [m/s]
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
Expand Up @@ -7,22 +7,28 @@ default:
process_noise_std: # [m/s^2]
ax: 0.98 # assume 0.1G acceleration noise
ay: 0.98
vx: 0.1 # assume 0.1m/s velocity noise
vy: 0.1
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: 0.9 # [m]
vx: 0.4 # [m/s]
vy: 1 # [m/s]
# 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: 1.0 # [m/s]
vy: 5.0 # [m/s]
ax: 0.5 # [m/s^2]
ay: 1.0 # [m/s^2]
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]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,10 @@
name="object_recognition_tracking_radar_object_tracker_node_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/tracking/radar_object_tracker/radar_object_tracker.param.yaml"
/>
<arg
name="object_recognition_tracking_radar_object_tracker_tracking_config_directory_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/tracking/radar_object_tracker/tracking/"
/>
<arg
name="object_recognition_tracking_object_merger_data_association_matrix_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/tracking/tracking_object_merger/data_association_matrix.param.yaml"
Expand Down

0 comments on commit 25e38f6

Please sign in to comment.