SwerveModule.
More...
#include <SwerveModule.h>
|
|
| SwerveModule (BaseController *_azimuthMotor, BaseController *_driveMotor, frc::Translation2d _wheelLocation, units::meter_t wheelDiameter, frc::sim::DCMotorSim driveSim, frc::sim::DCMotorSim azimuthSim) |
| |
|
frc::Rotation2d | getAzimuthPosition () |
| |
|
units::meter_t | getDrivePosition () |
| |
|
units::meters_per_second_t | getDriveSpeed () |
| |
|
units::meters_per_second_t | getMaxDriveSpeed () |
| |
|
frc::SwerveModulePosition | getModulePosition () |
| |
| frc::SwerveModuleState | getState () |
| |
| void | setDesiredState (frc::SwerveModuleState desiredState, bool isDriveOpenLoop) |
| |
| void | setDesiredState (frc::SwerveModuleState desiredState) |
| |
| void | resetDriveEncoder () |
| |
|
void | resetAzimuthEncoder () |
| |
| bool | loadAndSetAzimuthZeroReference (std::vector< units::turn_t > offsets) |
| |
|
void | setAzimuthPosition (frc::Rotation2d angle) |
| |
|
void | setAzimuthPower (units::volt_t voltage) |
| |
|
void | setDrivePower (units::volt_t voltage) |
| |
|
frc::Translation2d | convertSwerveStateToVelocityVector (frc::SwerveModuleState state) |
| |
| void | LoggablePeriodic () override |
| | Periodic callback for logging updates.
|
| |
|
void | SimulationPeriodic () |
| |
| void | LogChild (std::string_view name, Loggable *child) |
| | Register a child Loggable under a named subtree.
|
| |
| void | LogChild (std::string_view name, wpi::Sendable *child) |
| | Register a child Sendable under a named subtree.
|
| |
| void | setLoggingPeriod (units::millisecond_t period) |
| | Set the minimum period between LoggablePeriodic() invocations.
|
| |
|
template<> |
| decltype(Loggable::subscribers) ::iterator | addSubscriber (std::string_view field, const std::vector< bool > &defaultValue) |
| |
|
template<> |
| void | WriteLogImpl (nt::Publisher *pub, const std::vector< bool > &data) |
| |
|
template<> |
| std::vector< bool > | ReadLogImpl (nt::Subscriber *sub) |
| |
SwerveModule.
Usage:
T ReadLog(std::string_view field, const T &defaultValue={})
Read a value from NetworkTables for the given field.
Definition Loggable.h:343
SwerveModule.
Definition SwerveModule.h:29
◆ getState()
| frc::SwerveModuleState valor::SwerveModule::getState |
( |
| ) |
|
Get the current state of the swerve module
- Returns
- current state of the swerve module
◆ loadAndSetAzimuthZeroReference()
| bool valor::SwerveModule::loadAndSetAzimuthZeroReference |
( |
std::vector< units::turn_t > | offsets | ) |
|
Save the current azimuth absolute encoder reference position in NetworkTables preferences. Call this method following physical alignment of the module wheel in its zeroed position. Used during module instantiation to initialize the relative encoder. Loads the current azimuth absolute encoder reference position and sets selected sensor encoder
- Returns
- if the mag encoder was successfully
◆ LoggablePeriodic()
| void valor::SwerveModule::LoggablePeriodic |
( |
| ) |
|
|
overridevirtual |
Periodic callback for logging updates.
If a derived class needs to perform periodic updates to published values, override this method. It is intended to be called by the logging framework; this base class provides an empty implementation.
Reimplemented from valor::Loggable.
◆ resetDriveEncoder()
| void valor::SwerveModule::resetDriveEncoder |
( |
| ) |
|
Resets the drive encoders to currently read a position of 0
◆ setDesiredState() [1/2]
| void valor::SwerveModule::setDesiredState |
( |
frc::SwerveModuleState | desiredState | ) |
|
|
inline |
Command the swerve module motors to the desired state using closed-loop drive speed control
- Parameters
-
| desiredState | the desired swerve module speed and angle |
◆ setDesiredState() [2/2]
| void valor::SwerveModule::setDesiredState |
( |
frc::SwerveModuleState | desiredState, |
|
|
bool | isDriveOpenLoop ) |
Command the swerve module motors to the desired state
- Parameters
-
| desiredState | the desired swerve module speed and angle |
| isDriveOpen | true if drive should set speed using closed-loop velocity control |
The documentation for this class was generated from the following file: