-
Notifications
You must be signed in to change notification settings - Fork 8
/
Copy pathvesc.yaml
40 lines (34 loc) · 1.09 KB
/
vesc.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
# erpm (electrical rpm) = speed_to_erpm_gain * speed (meters / second) + speed_to_erpm_offset
#-4614
speed_to_erpm_gain: -3500
speed_to_erpm_offset: 0.0
tachometer_ticks_to_meters_gain: 0.00225
# servo smoother - limits rotation speed and smooths anything above limit
max_servo_speed: 3.2 # radians/second
servo_smoother_rate: 75.0 # messages/sec
# throttle smoother - limits acceleration and smooths anything above limit
max_acceleration: 2.5 # meters/second^2
throttle_smoother_rate: 75.0 # messages/sec
# servo value (0 to 1) = steering_angle_to_servo_gain * steering angle (radians) + steering_angle_to_servo_offset
steering_angle_to_servo_gain: 0.95
steering_angle_to_servo_offset: 0.55
# publish odom to base link tf
vesc_to_odom/publish_tf: false
# car wheelbase is about 25cm
chassis_length: 0.3
wheelbase: .225
vesc_driver:
port: /dev/vesc
duty_cycle_min: 0.0
duty_cycle_max: 0.0
current_min: 0.0
current_max: 20.0
brake_min: -20000.0
brake_max: 200000.0
speed_min: -3250
speed_max: 3250
position_min: 0.0
position_max: 0.0
servo_min: 0.15
servo_max: 0.85
invert_servo: true