-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathparams.yaml
207 lines (171 loc) · 5.03 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
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
# The distance between the front and
# rear axle of the racecar
wheelbase: 0.287 # meters
# width of racecar
width: 0.342 # meters
# steering delay
buffer_length: 5
# Limits on the speed and steering angle
max_speed: 2 # meters/second
max_steering_angle: 0.4189 # radians
max_accel: 2.5 #7.51 # meters/second^2
max_decel: 2.5 #8.26 # meters/second^2
max_steering_vel: 3.2 # radians/second
friction_coeff: 0.523 # - (complete estimate)
height_cg: 0.074 # m (roughly measured to be 3.25 in)
l_cg2rear: 0.17145 # m (decently measured to be 6.75 in)
l_cg2front: 0.15875 # m (decently measured to be 6.25 in)
C_S_front: 4.718 #.79 # 1/rad ? (estimated weight/4)
C_S_rear: 5.4562 #.79 # 1/rad ? (estimated weight/4)
mass: 3.47 # kg (measured on car 'lidart')
moment_inertia: .04712 # kg m^2 (estimated as a rectangle with width and height of car and evenly distributed mass, then shifted to account for center of mass location)
# The rate at which the pose and the lidar publish
update_pose_rate: 0.02
# Lidar simulation parameters
scan_beams: 720
scan_field_of_view: 6.2831853 #4.71 # radians
scan_range: 12.0
# The distance from the center of the
# rear axis (base_link) to the lidar
scan_distance_to_base_link: 0.01286 # meters
# The standard deviation of the noise applied
# to the lidar simulation
scan_std_dev: 0.01 # meters
# The probability threshold for points
# in the occupancy grid to be considered "free".
# Used for the lidar simulator.
map_free_threshold: 0.8
# Time to collision cutoff value
ttc_threshold: 0.01
# Indices for mux controller
mux_size: 6
joy_mux_idx: 0
key_mux_idx: 1
random_walker_mux_idx: 2
brake_mux_idx: 3
nav_mux_idx: 4
# **Add index for new planning method here**
# **(increase mux_size accordingly)**
new_method_mux_idx: -1
collision_assistance_mux_idx: 5
# Enables joystick if true
joy: true
# Joystick indices
joy_speed_axis: 1
joy_angle_axis: 3
joy_max_speed: 1 #2. # meters/second
# Joystick indices for toggling mux
joy_button_idx: 4 # LB button
key_button_idx: 6 # not sure
brake_button_idx: 0 # A button
random_walk_button_idx: 1 # ? button
nav_button_idx: 5 # RB button
collision_assistance_button_idx: 2 # X button
# **Add button for new planning method here**
new_button_idx: -1
# Keyboard characters for toggling mux
joy_key_char: "j"
keyboard_key_char: "k"
brake_key_char: "b"
random_walk_key_char: "r"
nav_key_char: "n"
# **Add button for new planning method here**
new_key_char: "z"
# Keyboard driving params
keyboard_speed: 1.8 # meters/second
keyboard_steer_ang: .3 # radians
# obstacle parameters
obstacle_size: 2
# The names of topics to listen and publish to
joy_topic: "/joy"
drive_topic: "/drive"
map_topic: "/map"
distance_transform_topic: "/dt"
scan_topic: "/scan"
pose_topic: "/pose"
ground_truth_pose_topic: "/gt_pose"
odom_topic: "/odom"
imu_topic: "/imu/data"
pose_rviz_topic: "/initialpose"
keyboard_topic: "/key"
brake_bool_topic: "/brake_bool"
mux_topic: "/mux"
camera_info: "/camera/depth/camera_info"
img_raw: "/camera/depth/image_rect_raw"
camera_metadata: "/camera/depth/meta_data"
# Topic names of various drive channels
rand_drive_topic: "/rand_drive"
brake_drive_topic: "/brake"
nav_drive_topic: "/nav"
# **Add name for new planning method here**
new_drive_topic: "/new_drive"
collision_assistance_drive_topic: "/collision_assistance"
# name of file to write collision log to
collision_file: "collision_file"
# The names of the transformation frames published to
map_frame: "map"
base_frame: "base_link"
base_frame_imu: "base_link_imu"
scan_frame: "laser"
odom_frame: "odom"
broadcast_transform: true
publish_ground_truth_pose: true
# Ackermann to VESC parameters
speed_to_erpm_gain: 3182.18
speed_to_erpm_offset: 0.0
steering_angle_to_servo_gain: -0.9
steering_angle_to_servo_offset: 0.5000
driver_smoother_rate: 75.0 # messages/sec
# Collision Assistance Algorithm Parameters
distance_to_obstacle_th: 1.0
force_gain: 8.0
velocity_correction_gain: 0.6
steering_correction_gain: 0.6
emergency_brake_active: true
# Wall Following Algorithm Parameters
CenterOffset: 0
DistanceLeft: 0.8
DistanceRight: 0.8
TrackWall: 0
angle_bl: rad(270*pi/180)
angle_al: rad(200*pi/180)
angle_br: rad(90*pi/180)
angle_ar: rad(160*pi/180)
n_pts_l: 100
n_pts_r: 100
tau: 0.1
k_d: 4
k_p: 3.5
vehicle_velocity: 1.7
turn_velocity: 0.8
velocity_zero: 0.3
# Gap Following Algorithm Parameters
safe_distance: 2
right_beam_angle: rad(2*pi*4.0/16)
left_beam_angle: rad(2*pi*12.0/16)
turn_angle1: rad(pi/6)
turn_angle2: rad(pi/3)
stop_time1: 1.0
stop_time2: 1.0
# Speed control paramteres
heading_beam_angle: rad(pi/16)
stop_distance: 0.6 #m
stop_distance_decay: 1.0 #m
# Separating Barrier Line Optimization Mode: 0 (indepndent) 1 (parallel)
optim_mode: 1
# Camera Parameters
use_camera: 1 # use the camera depth data (1) else 0 -> do not
min_depth: 100 # mm
max_depth: 5000 # mm
cam_baselink_offset: 270 #mm
# the following are defined in number of pixels
image_width: 848
image_height: 480
roi_u_lower: 250
roi_u_upper: 548
roi_v_lower: 150
roi_v_upper: 470
y_cam_max: 100 #mm
y_cam_min: -150 #mm
x_cam_max: 600 #mm
x_cam_min: -600 #mm