Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

chore: sync beta branch beta/v0.15.0 with tier4/main #250

Merged
merged 24 commits into from
Oct 27, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
24 commits
Select commit Hold shift + click to select a range
198f929
feat(avoidance): check if the avoidance path is in drivable area (#584)
satoshi-ota Oct 12, 2023
be56728
chore(intersection): parameterize stuck vehicle detection turn_direct…
soblin Oct 12, 2023
eeccf72
feat(ndt_scan_matcher): added a new parameter "n_startup_trials" (#602)
SakodaShintaro Oct 13, 2023
2614818
feat(autoware_launch): add yield_stuck.distance_thr in intersection (…
takayuki5168 Oct 13, 2023
5b9dfdb
feat(duplicated_node_checker): add duplicated_node_checker (#631)
Owen-Liuyuxuan Oct 14, 2023
807e5c6
feat(intersection): ignore decelerating vehicle on amber traffic ligh…
soblin Oct 15, 2023
d95d929
feat(lane_change): add rss paramas for stuck (#633)
kosuke55 Oct 15, 2023
307dc94
add tracking object merger for long range radar sensor (#627)
YoshiRi Oct 16, 2023
b811253
feat(behavior_path_planner): curvature based drivable area expansion …
maxime-clem Oct 16, 2023
434f95a
feat(lane_change): change stuck velocity to 0.5 (#636)
kosuke55 Oct 16, 2023
06cd743
fix(tier4_simulator_component): add lacked param path (#640)
satoshi-ota Oct 17, 2023
76dcd54
fix(drivable_area_expansion): disable by default (#639)
maxime-clem Oct 17, 2023
7d3f1d2
fix(intersection): lower state_transit_margi_time to 0 (#638)
soblin Oct 17, 2023
5d8a2f0
feat(avoidance): add paramenters for dynamic detection area (#634)
satoshi-ota Oct 17, 2023
681f5f7
feat(planner_manager): limit iteration number by parameter (#645)
satoshi-ota Oct 19, 2023
9e5293c
feat(map_based_prediction): enable to control lateral path convergenc…
YoshiRi Oct 20, 2023
082e862
feat(intersection): timeout static occlusion with traffic light (#646)
soblin Oct 20, 2023
90c7a6a
feat(duplicated_node_checker): disable duplicated_node_checker (#649)
kyoichi-sugahara Oct 20, 2023
13b2855
feat(intersection): use own max acc/jerk param (#650)
soblin Oct 23, 2023
5a04d1c
feat(duplicated_node_checker): add duplicated node names to msg (#651)
kyoichi-sugahara Oct 23, 2023
2ed86f2
feat(behavior_velocity_run_out): ignore momentary detection caused by…
TomohitoAndo Oct 24, 2023
c88d055
perf(elastic_band_smoother): increase lateral replan threshold (#652)
maxime-clem Oct 24, 2023
61aeb52
feat(rviz): add sensing/perception debug topics (#653)
miursh Oct 24, 2023
30d29fa
Merge pull request #249 from tier4/sync-awf-upstream
tier4-autoware-public-bot[bot] Oct 25, 2023
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,11 @@
# The number of particles to estimate initial pose
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 Down
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
@@ -0,0 +1,27 @@
# general parameters for radar_object_tracker node
/**:
ros__parameters:
# basic settings
world_frame_id: "map"
tracker_lifetime: 1.0 # [sec]
# if empty, use default config declared in this package
tracking_config_directory: ""

# delay compensate parameters
publish_rate: 10.0
enable_delay_compensation: false

# 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: 70.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]
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
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: 0.1 # assume 0.1m/s velocity noise
vy: 0.1
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]
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]
# 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,168 @@
/**:
ros__parameters:
lidar-lidar:
can_assign_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
0, 1, 1, 1, 1, 0, 0, 0, #CAR
0, 1, 1, 1, 1, 0, 0, 0, #TRUCK
0, 1, 1, 1, 1, 0, 0, 0, #BUS
0, 1, 1, 1, 1, 0, 0, 0, #TRAILER
0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE
0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE
0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN

max_dist_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[4.0, 4.0, 5.0, 5.0, 5.0, 2.0, 2.0, 2.0, #UNKNOWN
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR
5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK
5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS
5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRAILER
2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #MOTORBIKE
2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #BICYCLE
2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN

max_rad_matrix: # If value is greater than pi, it will be ignored.
#UNKNOWN, CAR, TRUCK, BUS, TRAILER MOTORBIKE, BICYCLE, PEDESTRIAN
[3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #CAR
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRUCK
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #BUS
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRAILER
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN

max_velocity_diff_matrix: # Ignored when value is larger than 100.0
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #UNKNOWN
100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #CAR
100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRUCK
100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #BUS
100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRAILER
100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #MOTORBIKE
100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #BICYCLE
100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0] #PEDESTRIAN

min_iou_matrix: # If value is negative, it will be ignored.
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN
0.1, 0.3, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] #PEDESTRIAN

lidar-radar:
can_assign_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
0, 1, 1, 1, 1, 0, 0, 0, #CAR
0, 1, 1, 1, 1, 0, 0, 0, #TRUCK
0, 1, 1, 1, 1, 0, 0, 0, #BUS
0, 1, 1, 1, 1, 0, 0, 0, #TRAILER
0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE
0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE
0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN

max_dist_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[4.0, 4.0, 5.0, 5.0, 5.0, 3.5, 3.5, 3.5, #UNKNOWN
4.0, 5.5, 6.0, 6.0, 6.0, 1.0, 1.0, 1.0, #CAR
5.0, 6.0, 6.5, 6.5, 6.5, 1.0, 1.0, 1.0, #TRUCK
5.0, 6.0, 6.5, 6.5, 6.5, 1.0, 1.0, 1.0, #BUS
5.0, 6.0, 6.5, 6.5, 6.5, 1.0, 1.0, 1.0, #TRAILER
3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #MOTORBIKE
3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #BICYCLE
3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.5] #PEDESTRIAN

max_rad_matrix: # If value is greater than pi, it will be ignored.
#UNKNOWN, CAR, TRUCK, BUS, TRAILER MOTORBIKE, BICYCLE, PEDESTRIAN
[3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #CAR
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRUCK
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #BUS
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRAILER
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN

max_velocity_diff_matrix: # Ignored when value is larger than 100.0
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #UNKNOWN
100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #CAR
100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRUCK
100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #BUS
100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRAILER
100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #MOTORBIKE
100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #BICYCLE
100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0] #PEDESTRIAN

min_iou_matrix: # set all value to 0.0 to disable this constraint
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #UNKNOWN
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #CAR
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #TRUCK
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #BUS
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #TRAILER
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #MOTORBIKE
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #BICYCLE
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] #PEDESTRIAN

radar-radar:
can_assign_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
0, 1, 1, 1, 1, 0, 0, 0, #CAR
0, 1, 1, 1, 1, 0, 0, 0, #TRUCK
0, 1, 1, 1, 1, 0, 0, 0, #BUS
0, 1, 1, 1, 1, 0, 0, 0, #TRAILER
0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE
0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE
0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN

max_dist_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[4.0, 4.0, 5.0, 5.0, 5.0, 3.5, 3.5, 3.5, #UNKNOWN
4.0, 7.0, 7.5, 7.5, 7.5, 1.0, 1.0, 1.0, #CAR
5.0, 7.5, 7.5, 7.5, 7.5, 1.0, 1.0, 1.0, #TRUCK
5.0, 7.5, 7.5, 7.5, 7.5, 1.0, 1.0, 1.0, #BUS
5.0, 7.5, 7.5, 7.5, 7.5, 1.0, 1.0, 1.0, #TRAILER
3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #MOTORBIKE
3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, #BICYCLE
3.5, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.5] #PEDESTRIAN
max_rad_matrix: # If value is greater than pi, it will be ignored.
#UNKNOWN, CAR, TRUCK, BUS, TRAILER MOTORBIKE, BICYCLE, PEDESTRIAN
[3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #CAR
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRUCK
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #BUS
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRAILER
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN

max_velocity_diff_matrix: # Ignored when value is larger than 100.0
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #UNKNOWN
100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #CAR
100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRUCK
100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #BUS
100.0, 8.0, 8.0, 8.0, 8.0, 100.0, 100.0, 100.0, #TRAILER
100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #MOTORBIKE
100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0, #BICYCLE
100.0, 100.0,100.0,100.0,100.0, 100.0, 100.0, 100.0] #PEDESTRIAN

min_iou_matrix: # set all value to 0.0 to disable this constraint
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #UNKNOWN
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #CAR
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #TRUCK
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #BUS
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #TRAILER
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #MOTORBIKE
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, #BICYCLE
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] #PEDESTRIAN
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
# Node parameters
/**:
ros__parameters:
base_link_frame_id: "base_link"
time_sync_threshold: 0.999
sub_object_timeout_sec: 0.8
publish_interpolated_sub_objects: true #for debug

# choose the input sensor type for each object type
# "lidar", "radar", "camera" are available
main_sensor_type: "lidar"
sub_sensor_type: "radar"

# tracker settings
tracker_state_parameter:
remove_probability_threshold: 0.3
publish_probability_threshold: 0.5
default_lidar_existence_probability: 0.7
default_radar_existence_probability: 0.6
default_camera_existence_probability: 0.5
decay_rate: 0.1
max_dt: 1.0

# logging
enable_logging: false
log_file_path: "/tmp/decorative_tracker_merger.log"
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
# Merger policy for decorative tracker merger node
# decorative tracker merger works by merging the sub-object trackers into a main object tracker result
# There are 3 merger policy:
# 1. "skip": skip the sub-object tracker result
# 2. "overwrite": overwrite the main object tracker result with sub-object tracker result
# 3. "fusion": merge the main object tracker result with sub-object tracker result by using covariance based fusion
/**:
ros__parameters:
kinematics_to_be_merged: "velocity" # currently only support "velocity"

# choose the merger policy for each object type
# : "skip", "overwrite", "fusion"
kinematics_merge_policy: "overwrite"
classification_merge_policy: "skip"
existence_prob_merge_policy: "skip"
shape_merge_policy: "skip"
Original file line number Diff line number Diff line change
Expand Up @@ -118,8 +118,6 @@
object_ignore_section_crosswalk_in_front_distance: 30.0 # [m]
object_ignore_section_crosswalk_behind_distance: 30.0 # [m]
# detection range
object_check_forward_distance: 150.0 # [m]
object_check_backward_distance: 10.0 # [m]
object_check_goal_distance: 20.0 # [m]
# filtering parking objects
threshold_distance_object_is_on_center: 1.0 # [m]
Expand All @@ -128,6 +126,13 @@
# lost object compensation
object_last_seen_threshold: 2.0

# detection area generation parameters
detection_area:
static: false # [-]
min_forward_distance: 50.0 # [m]
max_forward_distance: 150.0 # [m]
backward_distance: 10.0 # [m]

# For safety check
safety_check:
# safety check configuration
Expand Down Expand Up @@ -169,6 +174,7 @@
hard_road_shoulder_margin: 0.3 # [m]
max_right_shift_length: 5.0
max_left_shift_length: 5.0
max_deviation_from_lane: 0.5 # [m]
# avoidance distance parameters
longitudinal:
prepare_time: 2.0 # [s]
Expand Down Expand Up @@ -219,12 +225,6 @@
max_jerk: 1.0 # [m/sss]
max_acceleration: 1.0 # [m/ss]

target_velocity_matrix:
col_size: 2
matrix:
[2.78, 13.9, # velocity [m/s]
0.50, 1.00] # margin [m]

shift_line_pipeline:
trim:
quantize_filter_threshold: 0.1
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
/**:
ros__parameters:
verbose: false
max_iteration_num: 100

groot_zmq_publisher_port: 1666
groot_zmq_server_port: 1667
Expand Down
Loading
Loading