2023-Robot
Robot code for 2023 FRC season by Argos, FRC team #1756
|
Classes | |
class | NetworkTablesHomingStorage |
Saves and loads swerve module homes to networkTables. More... | |
struct | SwerveModulePositions |
Representation of the absolute encoder position of each module at home position. More... | |
struct | TranslationSpeeds |
Translation speeds as percent max output. More... | |
Functions | |
frc::SwerveModuleState | Optimize (frc::SwerveModuleState desiredState, units::degree_t currentModuleAngle, units::degrees_per_second_t currentModuleAngularRate, units::feet_per_second_t currentModuleDriveVel, units::feet_per_second_t maxVelocity) |
Optimize swerve module to minimize rotations and drive direction changes. | |
template<class T , int size, class V > | |
constexpr TranslationSpeeds | CircularInterpolate (const TranslationSpeeds rawSpeeds, const argos_lib::InterpolationMap< T, size, V > interpMap) |
Use argos_lib::InterpolationMap to apply mapping according to joystick vector magnitude. | |
|
constexpr |
Use argos_lib::InterpolationMap to apply mapping according to joystick vector magnitude.
T | Type of interpolated input |
size | Number of elements in interpolation map |
V | Type of interpolated output |
rawSpeeds | Joystick inputs as percentages |
interpMap | Interpolation map to apply to magnitudes |
frc::SwerveModuleState argos_lib::swerve::Optimize | ( | frc::SwerveModuleState | desiredState, |
units::degree_t | currentModuleAngle, | ||
units::degrees_per_second_t | currentModuleAngularRate, | ||
units::feet_per_second_t | currentModuleDriveVel, | ||
units::feet_per_second_t | maxVelocity | ||
) |
Optimize swerve module to minimize rotations and drive direction changes.
desiredState | Requested state. Output must result in same motion |
currentModuleAngle | Module rotation angle in relative or absolute position |
currentModuleAngularRate | Current module rotation speed. To prevent rapid changes in rotation direction. |
currentModuleDriveVel | Current module drive velocity. To prevent rapid changes in drive motor velocity. |
maxVelocity | Max velocity for determining max transition change thresholds |