forked from ucla-mobility/OpenCDA
-
Notifications
You must be signed in to change notification settings - Fork 0
/
cooperception_datadump_town05_carla.yaml
150 lines (143 loc) · 6.04 KB
/
cooperception_datadump_town05_carla.yaml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
description: |-
Copyright 2021 <UCLA Mobility Lab>
Author: Runsheng Xu <[email protected]>
Content: This is the scenario testing configuration file for single vehicle perception/localization/behavior/control
testing in high speed in the customized 2lanefree simple version.
# define carla simulation setting
world:
sync_mode: true
client_port: 2000
fixed_delta_seconds: &delta 0.05
seed: 165
# First define the basic parameters of the vehicles
vehicle_base: &vehicle_base
sensing: &base_sensing
perception: &base_perception
activate: false # when not activated, objects positions will be retrieved from server directly
camera_visualize: 1 # how many camera images need to be visualized. 0 means no visualization for camera
camera_num: 4 # how many cameras are mounted on the vehicle. Maximum 3(frontal, left and right cameras)
lidar_visualize: true # whether to visualize lidar points using open3d
lidar: # lidar sensor configuration, check CARLA sensor reference for more details
channels: 64
range: 120
points_per_second: 1300000
rotation_frequency: 20 # the simulation is 20 fps
upper_fov: 2
lower_fov: -25
dropoff_general_rate: 0.1
dropoff_intensity_limit: 0.7
dropoff_zero_intensity: 0.15
noise_stddev: 0.02
localization: &base_localize
activate: true # when not activated, ego position will be retrieved from server directly
dt: *delta # used for kalman filter
gnss: # gnss sensor configuration
noise_alt_stddev: 0.005
noise_lat_stddev: 1e-6
noise_lon_stddev: 1e-6
heading_direction_stddev: 0.1 # degree
speed_stddev: 0.2
debug_helper: &loc_debug_helper
show_animation: false # whether to show real-time trajectory plotting
x_scale: 1.0 # used to multiply with the x coordinate to make the error on x axis clearer
y_scale: 100.0 # used to multiply with the y coordinate to make the error on y axis clearer
behavior: &base_behavior
max_speed: 70 # maximum speed, km/h
tailgate_speed: 34 # when a vehicles needs to be close to another vehicle asap
speed_lim_dist: 3 # max_speed - speed_lim_dist = target speed
speed_decrease: 15 # used in car following mode to decrease speed for distance keeping
safety_time: 4 # ttc safety thresholding for decreasing speed
emergency_param: 0.4 # used to identify whether a emergency stop needed
ignore_traffic_light: true # whether to ignore traffic light
overtake_allowed: true # whether overtake allowed, typically false for platoon leader
collision_time_ahead: 1.5 # used for collision checking
overtake_counter_recover: 35 # the vehicle can not do another overtake during next certain steps
sample_resolution: 4.5 # the unit distance between two adjacent waypoints in meter
local_planner: &base_local_planner # trajectory planning related
buffer_size: 12 # waypoint buffer size
trajectory_update_freq: 15 # used to control trajectory points updating frequency
waypoint_update_freq: 9 # used to control waypoint updating frequency
trajectory_dt: 0.20 # for every dt seconds, we sample a trajectory point from the trajectory path as next goal state
min_dist: 3 # used to pop out the waypoints too close to current location
debug: false # whether to draw future/history waypoints
debug_trajectory: false # whether to draw the trajectory points and path
controller: &base_controller
type: pid_controller # this has to be exactly the same name as the controller py file
args:
lat:
k_p: 0.75
k_d: 0.02
k_i: 0.4
lon:
k_p: 0.37
k_d: 0.024
k_i: 0.032
dynamic: false # whether use dynamic pid setting
dt: *delta # this should be equal to your simulation time-step
max_brake: 1.0
max_throttle: 1.0
max_steering: 0.3
v2x: &base_v2x # communication related
enabled: true
communication_range: 35
loc_noise: 0.0
yaw_noise: 0.0
speed_noise: 0.0
lag: 0
# define the background traffic control by carla
carla_traffic_manager:
sync_mode: true # has to be same as the world setting
global_distance: 5 # the minimum distance in meters that vehicles have to keep with the rest
# Sets the difference the vehicle's intended speed and its current speed limit.
# Carla default speed is 30 km/h, so -100 represents 60 km/h,
# and 20 represents 24 km/h
global_speed_perc: -200
set_osm_mode: true # Enables or disables the OSM mode.
auto_lane_change: true
random: true # whether to random select vehicles' color and model
ignore_lights_percentage: 100 # whether set the traffic ignore traffic lights
vehicle_list: ~ # a number or a list
# Used only when vehicle_list is a number.
# x_min, x_max, y_min, y_max, x_step, y_step, vehicle_num
range:
- [-50, -10, 187, 194, 15, 3.5, 8]
# define scenario. In this scenario, a 4-vehicle platoon already exists.
scenario:
single_cav_list: # this is for merging vehicle or single cav without v2x
- <<: *vehicle_base
spawn_position: [-17.87, 194.67, 1.3, 0, -179, 0]
destination: [-130, 194.67, 0.3]
v2x:
<<: *base_v2x
communication_range: 45
behavior:
<<: *base_behavior
local_planner:
<<: *base_local_planner
debug_trajectory: false
debug: false
- <<: *vehicle_base
spawn_position: [-37.87, 187.75, 3.3, 0, -179, 0]
destination: [-130, 187.75, 0.3]
v2x:
<<: *base_v2x
communication_range: 45
behavior:
<<: *base_behavior
local_planner:
<<: *base_local_planner
debug_trajectory: false
debug: false
- <<: *vehicle_base
spawn_position: [-98, 200.93, 9.0, 0, 0, 0]
destination: [22.15, 180.93, 3.0]
v2x:
<<: *base_v2x
communication_range: 45
behavior:
<<: *base_behavior
max_speed: 30
local_planner:
<<: *base_local_planner
debug_trajectory: false
debug: false