Autonomous Racing  1
f1tenth Project Group of Technical University Dortmund, Germany
car_config.h
Go to the documentation of this file.
1 #pragma once
2 
3 namespace car_config
4 {
8  constexpr double PI = 3.14159265358979323846;
9 
10  constexpr double DEG_TO_RAD = PI / 180;
11 
15  constexpr double WHEELBASE = 0.325;
16 
17  constexpr double WHEEL_DIAMETER = 0.098;
18 
19  constexpr double WHEEL_WIDTH = 0.042;
20 
21  constexpr double FRONT_WHEEL_DISTANCE = 0.23;
22 
23  constexpr double REAR_WHEEL_DISTANCE = 0.233;
24 
25  constexpr double WHEEL_PERIMETER = WHEEL_DIAMETER * PI;
26 
27  constexpr double TURNING_RADIUS = 0.605;
28 
33  constexpr double MAX_RPM_MECHANICAL = 60000;
34 
38  constexpr double MOTOR_POLES = 3;
39 
44  constexpr double MAX_RPM_ELECTRICAL = MAX_RPM_MECHANICAL / MOTOR_POLES;
45 
50  constexpr double ERPM_TO_SPEED = WHEEL_PERIMETER * MOTOR_POLES / 60;
51 
56  constexpr double SPEED_TO_ERPM = 1 / ERPM_TO_SPEED;
57 
62  constexpr double RPM_TO_SPEED = WHEEL_PERIMETER / 60;
63 
67  constexpr double STEERING_TO_SERVO_OFFSET = 0.5;
68 
73  constexpr double STEERING_TO_SERVO_GAIN = -3 / PI;
74 
75  constexpr double MAX_STEERING_ANGLE = 30 * DEG_TO_RAD;
76 
77  constexpr double MIN_STEERING_ANGLE = -30 * DEG_TO_RAD;
78 
83  constexpr double TRANSMISSION = 20;
84 
85  constexpr double MAX_SERVO_POSITION = 1;
86 
91  constexpr double ERPM_TO_RAD_PER_SEC = MOTOR_POLES * 2 * PI / 60;
92 };
constexpr double TRANSMISSION
Gear transmission inside the differential of the car. This is an estimate, the exact value is not kno...
Definition: car_config.h:83
constexpr double ERPM_TO_RAD_PER_SEC
Conversion factor from electrical revolutions per minute to radian to seconds radian/s * minute = ra...
Definition: car_config.h:91
constexpr double PI
Since it&#39;s not possible to use <cmath> in a constexpression, it&#39;s defined here again.
Definition: car_config.h:8
constexpr double FRONT_WHEEL_DISTANCE
Definition: car_config.h:21
constexpr double REAR_WHEEL_DISTANCE
Definition: car_config.h:23
constexpr double WHEEL_WIDTH
Definition: car_config.h:19
constexpr double WHEEL_DIAMETER
Definition: car_config.h:17
constexpr double TURNING_RADIUS
Definition: car_config.h:27
constexpr double WHEEL_PERIMETER
Definition: car_config.h:25
constexpr double SPEED_TO_ERPM
Conversion factor from meters per second to electrical revolutions per minute s/ (m * minute) = 1/m...
Definition: car_config.h:56
constexpr double MAX_STEERING_ANGLE
Definition: car_config.h:75
constexpr double DEG_TO_RAD
Definition: car_config.h:10
constexpr double WHEELBASE
The distance between the front and rear axes.
Definition: car_config.h:15
constexpr double STEERING_TO_SERVO_GAIN
Conversion factor from steering angle to servo input 1/radian.
Definition: car_config.h:73
constexpr double MAX_SERVO_POSITION
Definition: car_config.h:85
constexpr double MAX_RPM_MECHANICAL
Maximum revolutions per minute of the motor. Divide by TRANSMISSION to get the maximum wheel rpm 1/m...
Definition: car_config.h:33
constexpr double RPM_TO_SPEED
Conversion factor from mechanical revolutions per minute to meters per second m/s * minute = m...
Definition: car_config.h:62
constexpr double STEERING_TO_SERVO_OFFSET
Position of the servo for normal wheel position.
Definition: car_config.h:67
constexpr double MAX_RPM_ELECTRICAL
Maximum electrical revolutions per minute for use in the VESC 1/min.
Definition: car_config.h:44
constexpr double MOTOR_POLES
Number of electrical motor poles.
Definition: car_config.h:38
constexpr double MIN_STEERING_ANGLE
Definition: car_config.h:77
constexpr double ERPM_TO_SPEED
Conversion factor from electrical revolutions per minute to meters per second m/s * minute = m...
Definition: car_config.h:50