![]() |
Autonomous Racing
1
f1tenth Project Group of Technical University Dortmund, Germany
|
Go to the source code of this file.
Namespaces | |
car_config | |
Variables | |
constexpr double | car_config::PI = 3.14159265358979323846 |
Since it's not possible to use <cmath> in a constexpression, it's defined here again. More... | |
constexpr double | car_config::DEG_TO_RAD = PI / 180 |
constexpr double | car_config::WHEELBASE = 0.325 |
The distance between the front and rear axes. More... | |
constexpr double | car_config::WHEEL_DIAMETER = 0.098 |
constexpr double | car_config::WHEEL_WIDTH = 0.042 |
constexpr double | car_config::FRONT_WHEEL_DISTANCE = 0.23 |
constexpr double | car_config::REAR_WHEEL_DISTANCE = 0.233 |
constexpr double | car_config::WHEEL_PERIMETER = WHEEL_DIAMETER * PI |
constexpr double | car_config::TURNING_RADIUS = 0.605 |
constexpr double | car_config::MAX_RPM_MECHANICAL = 60000 |
Maximum revolutions per minute of the motor. Divide by TRANSMISSION to get the maximum wheel rpm 1/min. More... | |
constexpr double | car_config::MOTOR_POLES = 3 |
Number of electrical motor poles. More... | |
constexpr double | car_config::MAX_RPM_ELECTRICAL = MAX_RPM_MECHANICAL / MOTOR_POLES |
Maximum electrical revolutions per minute for use in the VESC 1/min. More... | |
constexpr double | car_config::ERPM_TO_SPEED = WHEEL_PERIMETER * MOTOR_POLES / 60 |
Conversion factor from electrical revolutions per minute to meters per second m/s * minute = m. More... | |
constexpr double | car_config::SPEED_TO_ERPM = 1 / ERPM_TO_SPEED |
Conversion factor from meters per second to electrical revolutions per minute s/ (m * minute) = 1/m. More... | |
constexpr double | car_config::RPM_TO_SPEED = WHEEL_PERIMETER / 60 |
Conversion factor from mechanical revolutions per minute to meters per second m/s * minute = m. More... | |
constexpr double | car_config::STEERING_TO_SERVO_OFFSET = 0.5 |
Position of the servo for normal wheel position. More... | |
constexpr double | car_config::STEERING_TO_SERVO_GAIN = -3 / PI |
Conversion factor from steering angle to servo input 1/radian. More... | |
constexpr double | car_config::MAX_STEERING_ANGLE = 30 * DEG_TO_RAD |
constexpr double | car_config::MIN_STEERING_ANGLE = -30 * DEG_TO_RAD |
constexpr double | car_config::TRANSMISSION = 20 |
Gear transmission inside the differential of the car. This is an estimate, the exact value is not known. More... | |
constexpr double | car_config::MAX_SERVO_POSITION = 1 |
constexpr double | car_config::ERPM_TO_RAD_PER_SEC = MOTOR_POLES * 2 * PI / 60 |
Conversion factor from electrical revolutions per minute to radian to seconds radian/s * minute = radians. More... | |