forked from f1tenth/f1tenth_simulator
-
Notifications
You must be signed in to change notification settings - Fork 1
/
params.yaml
193 lines (165 loc) · 7.99 KB
/
params.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
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
# ----------------------------------------------------------------------------------------------------------------------
# vehicle parameters ---------------------------------------------------------------------------------------------------
# ----------------------------------------------------------------------------------------------------------------------
# The distance between the front and rear axle of the racecar
wheelbase: 0.3302 # meters
# width of racecar
width: 0.2032 # meters
# according to rules https://iros2021.f1tenth.org/rules.html#25-head-to-head-race, 2.5.2.c
cube_width: 0.20
# Limits on the speed and steering angle
max_speed: 27. # meters/second
max_steering_angle: 0.192 # radians
max_steering_vel: 1.9 # radians/second
max_accel: 7.51 # meters/second^2
max_decel: 8.26 # meters/second^2
friction_coeff: 5.923
height_cg: 0.074 # m
l_cg2rear: 0.139 # m
l_cg2front: 0.1912 # m
C_S_front: 4.718
C_S_rear: 5.4562
mass: 3.958 # kg
# estimated as a rectangle with width and height of car and evenly distributed mass, then shifted to account for center of mass location
moment_inertia: .15712 # kg m^2
empirical_drivetrain_parameters_1: 6.097
empirical_drivetrain_parameters_2: 0.237
empirical_drivetrain_parameters_3: 0.392
# engine_revolutions_per_minute_reference
empirical_Pacejka_parameters_B_f: 0.201
empirical_Pacejka_parameters_C_f: 2.114
empirical_Pacejka_parameters_D_f: 28.892
empirical_Pacejka_parameters_B_r: 0.201
empirical_Pacejka_parameters_C_r: 2.114
empirical_Pacejka_parameters_D_r: 28.892
# ----------------------------------------------------------------------------------------------------------------------
# update rate ----------------------------------------------------------------------------------------------------------
# ----------------------------------------------------------------------------------------------------------------------
# The rate of publishing the pose, the LiDAR, and collision checking
update_pose_rate: 0.005
# ----------------------------------------------------------------------------------------------------------------------
# LiDAR sensor parameters ----------------------------------------------------------------------------------------------
# ----------------------------------------------------------------------------------------------------------------------
# https://www.hokuyo-aut.jp/dl/UST-10LX_Specification.pdf
# number of total beams
scan_beams: 1081
# how many radians the LiDAR will scan? should between (0, 2pi]
scan_field_of_view: 4.71238898038469 # 270degree, degree to radians: degree*PI/180
# maximum detection range
scan_max_range: 10 # meters
# The distance from the center of the rear axis (base_link) to the lidar sensor
# Sidenote: For the F1tenth, the LiDAR is at head of a car
scan_distance_to_base_link: 0.275 # meters
# The standard deviation of the noise applied to the lidar simulation
scan_std_dev: 0.015 # meters
# ----------------------------------------------------------------------------------------------------------------------
# occupancy grid threshold ---------------------------------------------------------------------------------------------
# ----------------------------------------------------------------------------------------------------------------------
# The probability threshold for points in the occupancy grid to be considered "free".
# Used in scan_simulator_2d.cpp set_map().
map_free_threshold: 0.5
# ----------------------------------------------------------------------------------------------------------------------
# Time To Collision threshold ------------------------------------------------------------------------------------------
# ----------------------------------------------------------------------------------------------------------------------
# Time to collision cutoff value
# Used in simulator.cpp
ttc_threshold: 0.01
# ----------------------------------------------------------------------------------------------------------------------
# Mux index ------------------------------------------------------------------------------------------------------------
# ----------------------------------------------------------------------------------------------------------------------
# total number of indices
mux_size: 99
joy_mux_idx: 0
key_mux_idx: 1
random_walker_mux_idx: 2
brake_mux_idx: 3
nav_mux_idx: 4
MPC_mux_idx: 5
LSTM_mux_idx: 6
# **Add index for new planning method here**
# **(increasing accordingly)**
# new_method_mux_idx: 7
# ----------------------------------------------------------------------------------------------------------------------
# Joy index ------------------------------------------------------------------------------------------------------------
# ----------------------------------------------------------------------------------------------------------------------
# Enables joystick if true
joy: true
# joy axis and button index depends on different controller, must check before using different controller
# axis index (must unique)
joy_speed_axis_blue: 5 # LT
joy_angle_axis_blue: 0 # left joystick (horizon direction)
joy_speed_axis_red: 2 # RT
joy_angle_axis_red: 3 # right joystick (horizon direction)
MPC_axis_idx: 7 # up button
LSTM_axis_idx: 6 # left button
# button index (must unique)
joy_button_idx: 0 # A button
key_button_idx: 2 # X button
brake_button_idx: 3 # Y button
random_walk_button_idx: 1 # B button
nav_button_idx: 5 # RB button
data_button_idx: 4 # LB button
# **Add button for new planning method here**
# new_button_idx: -1
# ----------------------------------------------------------------------------------------------------------------------
# Keyboard chars -------------------------------------------------------------------------------------------------------
# ----------------------------------------------------------------------------------------------------------------------
# must unique
joy_key_char: "y"
keyboard_key_char: "t"
brake_key_char: "b"
random_walk_key_char: "r"
nav_key_char: "n"
MPC_key_char: "g"
LSTM_key_char: "u"
# **Add button for new planning method here**
# new_key_char: "v"
# Keyboard driving params
keyboard_speed: 9 # meters/second
keyboard_steer_ang: 0.3 # radians
# ----------------------------------------------------------------------------------------------------------------------
# Topics ---------------------------------------------------------------------------------------------------------------
# ----------------------------------------------------------------------------------------------------------------------
# topic MUST start with "/"
joy_topic: "/joy"
keyboard_topic: "/key"
drive_topic_blue: "/drive_blue"
drive_topic_red: "/drive_red"
map_topic: "/map"
distance_transform_topic: "/dt"
scan_topic_red: "/red/scan"
scan_topic_blue: "/blue/scan"
pose_topic_blue: "/blue/pose"
pose_topic_red: "/red/pose"
ground_truth_pose_topic: "/gt_pose"
odom_topic: "/odom"
imu_topic: "/imu"
pose_rviz_topic: "/initialpose"
brake_bool_topic: "/brake_bool"
mux_topic: "/mux"
data_topic: "/data"
carState_topic_red: "/carState_topic_red"
reference_line: "/minimum_time"
mpc_goal_path: "/goal_and_path"
switch_topic_red: "/MPC_ML"
# Topic names of various drive channels in mux.cpp
rand_drive_topic: "/rand_drive"
brake_drive_topic: "/brake"
nav_drive_topic: "/nav"
MPC_drive_topic: "/mpc"
overtaking_drive_topic: "/overtake"
# **Add name for new planning method here**
# new_drive_topic: "/new_drive"
# ----------------------------------------------------------------------------------------------------------------------
# transformation frames ------------------------------------------------------------------------------------------------
# ----------------------------------------------------------------------------------------------------------------------
# The names of the transformation frames published to
# frame must NOT start with "/"
map_frame: "map"
base_frame_blue: "blue/base_link"
scan_frame_blue: "blue/laser"
base_frame_red: "red/base_link"
scan_frame_red: "red/laser"
map_name: "de-espana"
broadcast_transform: true
publish_ground_truth_pose: true