Index
All Classes and Interfaces|All Packages|Constant Field Values
A
- absoluteEncoder - Variable in class swervelib.motors.SparkFlexSwerve
-
Absolute encoder attached to the SparkMax (if exists)
- absoluteEncoder - Variable in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Absolute encoder attached to the SparkMax (if exists)
- absoluteEncoder - Variable in class swervelib.motors.SparkMaxSwerve
-
Absolute encoder attached to the SparkMax (if exists)
- absoluteEncoder - Variable in class swervelib.parser.SwerveModuleConfiguration
-
The Absolute Encoder for the swerve module.
- absoluteEncoderInverted - Variable in class swervelib.parser.json.ModuleJson
-
Absolute encoder inversion state.
- absoluteEncoderInverted - Variable in class swervelib.parser.SwerveModuleConfiguration
-
Whether the absolute encoder is inverted.
- absoluteEncoderOffset - Variable in class swervelib.parser.json.ModuleJson
-
Absolute encoder offset from 0 in degrees.
- absolutePositionCache - Variable in class swervelib.SwerveModule
-
Absolute encoder position cache.
- addSlewRateLimiters(SlewRateLimiter, SlewRateLimiter, SlewRateLimiter) - Method in class swervelib.SwerveController
-
Add slew rate limiters to all controls.
- addValue(double) - Method in class swervelib.math.IMULinearMovingAverageFilter
-
Add a value to the DoubleCircularBuffer
- addVisionMeasurement(Pose2d, double) - Method in class swervelib.SwerveDrive
-
Add a vision measurement to the
SwerveDrivePoseEstimator
and update theSwerveIMU
gyro reading with the given timestamp of the vision measurement. - addVisionMeasurement(Pose2d, double, Matrix<N3, N1>) - Method in class swervelib.SwerveDrive
-
Add a vision measurement to the
SwerveDrivePoseEstimator
and update theSwerveIMU
gyro reading with the given timestamp of the vision measurement. - ADIS16448Swerve - Class in swervelib.imu
-
IMU Swerve class for the
ADIS16448_IMU
device. - ADIS16448Swerve() - Constructor for class swervelib.imu.ADIS16448Swerve
-
Construct the ADIS16448 imu and reset default configurations.
- ADIS16470Swerve - Class in swervelib.imu
-
IMU Swerve class for the
ADIS16470_IMU
device. - ADIS16470Swerve() - Constructor for class swervelib.imu.ADIS16470Swerve
-
Construct the ADIS16470 imu and reset default configurations.
- ADXRS450Swerve - Class in swervelib.imu
-
IMU Swerve class for the
ADXRS450_Gyro
device. - ADXRS450Swerve() - Constructor for class swervelib.imu.ADXRS450Swerve
-
Construct the ADXRS450 imu and reset default configurations.
- Alert - Class in swervelib.telemetry
-
Class for managing persistent alerts to be sent over NetworkTables.
- Alert(String, String, Alert.AlertType) - Constructor for class swervelib.telemetry.Alert
-
Creates a new Alert.
- Alert(String, Alert.AlertType) - Constructor for class swervelib.telemetry.Alert
-
Creates a new Alert in the default group - "Alerts".
- Alert.AlertType - Enum Class in swervelib.telemetry
-
Represents an alert's level of urgency.
- AnalogAbsoluteEncoderSwerve - Class in swervelib.encoders
-
Swerve Absolute Encoder for Thrifty Encoders and other analog encoders.
- AnalogAbsoluteEncoderSwerve(int) - Constructor for class swervelib.encoders.AnalogAbsoluteEncoderSwerve
-
Construct the Encoder given the analog input channel.
- AnalogAbsoluteEncoderSwerve(AnalogInput) - Constructor for class swervelib.encoders.AnalogAbsoluteEncoderSwerve
-
Construct the Thrifty Encoder as a Swerve Absolute Encoder.
- AnalogGyroSwerve - Class in swervelib.imu
-
Creates a IMU for
AnalogGyro
devices, only uses yaw. - AnalogGyroSwerve(int) - Constructor for class swervelib.imu.AnalogGyroSwerve
-
Analog port in which the gyroscope is connected.
- angle - Variable in class swervelib.parser.json.ModuleJson
-
Angle motor device configuration.
- angle - Variable in class swervelib.parser.json.modules.BoolMotorJson
-
Angle motor inversion state.
- angle - Variable in class swervelib.parser.json.modules.ConversionFactorsJson
-
Angle motor conversion factors composition.
- angle - Variable in class swervelib.parser.json.MotorConfigDouble
-
Angle motor.
- angle - Variable in class swervelib.parser.json.MotorConfigInt
-
Angle motor.
- angle - Variable in class swervelib.parser.json.PIDFPropertiesJson
-
The PIDF with Integral Zone used for the angle motor.
- AngleConversionFactorsJson - Class in swervelib.parser.json.modules
-
Angle motor conversion factors composite JSON parse class.
- AngleConversionFactorsJson() - Constructor for class swervelib.parser.json.modules.AngleConversionFactorsJson
- angleJoystickRadiusDeadband - Variable in class swervelib.parser.json.ControllerPropertiesJson
-
The minimum radius of the angle control joystick to allow for heading adjustment of the robot.
- angleJoyStickRadiusDeadband - Variable in class swervelib.parser.SwerveControllerConfiguration
-
hypotenuse deadband for the robot angle control joystick.
- angleLimiter - Variable in class swervelib.SwerveController
-
SlewRateLimiter
for angular movement in radians/second. - angleModules(SwerveDrive, Rotation2d) - Static method in class swervelib.SwerveDriveTest
-
Set the angle of the modules to a given
Rotation2d
- angleMotor - Variable in class swervelib.parser.SwerveModuleConfiguration
-
The drive motor and angle motor of this swerve module.
- angleMotorCurrentLimit - Variable in class swervelib.parser.SwerveModulePhysicalCharacteristics
-
Current limits for the Swerve Module.
- angleMotorInverted - Variable in class swervelib.parser.SwerveModuleConfiguration
-
State of inversion of the angle motor.
- angleMotorRampRate - Variable in class swervelib.parser.SwerveModulePhysicalCharacteristics
-
The time it takes for the motor to go from 0 to full throttle in seconds.
- angleOffset - Variable in class swervelib.parser.SwerveModuleConfiguration
-
Angle offset in degrees for the Swerve Module.
- anglePIDF - Variable in class swervelib.parser.SwerveModuleConfiguration
-
PIDF configuration options for the angle motor closed-loop PID controller.
- angularVelocityCoefficient - Variable in class swervelib.SwerveDrive
-
Angular Velocity Correction Coefficent (expected values between -0.15 and 0.15).
- angularVelocityCorrection - Variable in class swervelib.SwerveDrive
-
Correct for skew that scales with angular velocity in
SwerveDrive.drive(Translation2d, double, boolean, boolean)
- angularVelocitySkewCorrection(ChassisSpeeds) - Method in class swervelib.SwerveDrive
-
Correct for skew that worsens as angular velocity increases
- antiJitter(SwerveModuleState, SwerveModuleState, double) - Static method in class swervelib.math.SwerveMath
-
Perform anti-jitter within modules if the speed requested is too low.
- applyDeadband(double, boolean, double) - Static method in class swervelib.math.SwerveMath
-
Algebraically apply a deadband using a piece wise function.
- autonomousAngularVelocityCorrection - Variable in class swervelib.SwerveDrive
-
Correct for skew that scales with angular velocity in
SwerveDrive.setChassisSpeeds(ChassisSpeeds chassisSpeeds)
during auto. - autonomousChassisVelocityCorrection - Variable in class swervelib.SwerveDrive
-
Correct chassis velocity in
SwerveDrive.setChassisSpeeds(ChassisSpeeds chassisSpeeds)
(auto) using 254's correction during auto.
B
- BoolMotorJson - Class in swervelib.parser.json.modules
-
Inverted motor JSON parsed class.
- BoolMotorJson() - Constructor for class swervelib.parser.json.modules.BoolMotorJson
- burnFlash() - Method in class swervelib.motors.SparkFlexSwerve
-
Save the configurations from flash to EEPROM.
- burnFlash() - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Save the configurations from flash to EEPROM.
- burnFlash() - Method in class swervelib.motors.SparkMaxSwerve
-
Save the configurations from flash to EEPROM.
- burnFlash() - Method in class swervelib.motors.SwerveMotor
-
Save the configurations from flash to EEPROM.
- burnFlash() - Method in class swervelib.motors.TalonFXSwerve
-
Save the configurations from flash to EEPROM.
- burnFlash() - Method in class swervelib.motors.TalonSRXSwerve
-
Save the configurations from flash to EEPROM.
C
- Cache<T> - Class in swervelib.parser
-
Cache for frequently requested data.
- Cache(Supplier<T>, long) - Constructor for class swervelib.parser.Cache
-
Cache for arbitrary values.
- calculate() - Method in class swervelib.math.IMULinearMovingAverageFilter
-
Calculate the average of the samples in the buffer
- calculate() - Method in class swervelib.parser.json.modules.AngleConversionFactorsJson
-
Calculate the drive conversion factor.
- calculate() - Method in class swervelib.parser.json.modules.DriveConversionFactorsJson
-
Calculate the drive conversion factor.
- calculateDegreesPerSteeringRotation(double) - Static method in class swervelib.math.SwerveMath
-
Calculate the degrees per steering rotation for the integrated encoder.
- calculateDegreesPerSteeringRotation(double, double) - Static method in class swervelib.math.SwerveMath
-
Calculate the degrees per steering rotation for the integrated encoder.
- calculateMaxAcceleration(double) - Static method in class swervelib.math.SwerveMath
-
Calculate the practical maximum acceleration of the robot using the wheel coefficient of friction.
- calculateMaxAcceleration(double, double, double, double, double) - Static method in class swervelib.math.SwerveMath
-
Calculate the maximum theoretical acceleration without friction.
- calculateMaxAngularVelocity(double, double, double) - Static method in class swervelib.math.SwerveMath
-
Calculate the maximum angular velocity.
- calculateMetersPerRotation(double, double) - Static method in class swervelib.math.SwerveMath
-
Calculate the meters per rotation for the integrated encoder.
- calculateMetersPerRotation(double, double, double) - Static method in class swervelib.math.SwerveMath
-
Calculate the meters per rotation for the integrated encoder.
- CanandgyroSwerve - Class in swervelib.imu
-
SwerveIMU interface for the Boron
Canandgyro
by Redux Robotics - CanandgyroSwerve(int) - Constructor for class swervelib.imu.CanandgyroSwerve
-
Generate the SwerveIMU for
Canandgyro
. - CanAndMagSwerve - Class in swervelib.encoders
-
HELIUM
Canandmag
from ReduxRobotics absolute encoder, attached through the CAN bus. - CanAndMagSwerve(int) - Constructor for class swervelib.encoders.CanAndMagSwerve
-
Create the
Canandmag
- canbus - Variable in class swervelib.parser.json.DeviceJson
-
The CAN bus name which the device resides on if using CAN.
- CANCoderSwerve - Class in swervelib.encoders
-
Swerve Absolute Encoder for CTRE CANCoders.
- CANCoderSwerve(int) - Constructor for class swervelib.encoders.CANCoderSwerve
-
Initialize the CANCoder on the standard CANBus.
- CANCoderSwerve(int, String) - Constructor for class swervelib.encoders.CANCoderSwerve
-
Initialize the CANCoder on the CANivore.
- canIdWarning - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
An
Alert
for if the CAN ID is greater than 40. - centerModules(SwerveDrive) - Static method in class swervelib.SwerveDriveTest
-
Set the modules to center to 0.
- chassisVelocityCorrection - Variable in class swervelib.SwerveDrive
-
Correct chassis velocity in
SwerveDrive.drive(Translation2d, double, boolean, boolean)
using 254's correction. - clearStickyFaults() - Method in class swervelib.encoders.AnalogAbsoluteEncoderSwerve
-
Clear sticky faults on the encoder.
- clearStickyFaults() - Method in class swervelib.encoders.CanAndMagSwerve
-
Clear sticky faults on the encoder.
- clearStickyFaults() - Method in class swervelib.encoders.CANCoderSwerve
-
Clear sticky faults on the encoder.
- clearStickyFaults() - Method in class swervelib.encoders.PWMDutyCycleEncoderSwerve
-
Clear sticky faults on the encoder.
- clearStickyFaults() - Method in class swervelib.encoders.SparkMaxAnalogEncoderSwerve
-
Clear sticky faults on the encoder.
- clearStickyFaults() - Method in class swervelib.encoders.SparkMaxEncoderSwerve
-
Clear sticky faults on the encoder.
- clearStickyFaults() - Method in class swervelib.encoders.SwerveAbsoluteEncoder
-
Clear sticky faults on the encoder.
- clearStickyFaults() - Method in class swervelib.imu.ADIS16448Swerve
-
Clear sticky faults on IMU.
- clearStickyFaults() - Method in class swervelib.imu.ADIS16470Swerve
-
Clear sticky faults on IMU.
- clearStickyFaults() - Method in class swervelib.imu.ADXRS450Swerve
-
Clear sticky faults on IMU.
- clearStickyFaults() - Method in class swervelib.imu.AnalogGyroSwerve
-
Clear sticky faults on IMU.
- clearStickyFaults() - Method in class swervelib.imu.CanandgyroSwerve
-
Clear sticky faults on
Canandgyro
. - clearStickyFaults() - Method in class swervelib.imu.NavXSwerve
-
Clear sticky faults on IMU.
- clearStickyFaults() - Method in class swervelib.imu.Pigeon2Swerve
-
Clear sticky faults on
Pigeon2
. - clearStickyFaults() - Method in class swervelib.imu.PigeonSwerve
-
Clear sticky faults on IMU.
- clearStickyFaults() - Method in class swervelib.imu.SwerveIMU
-
Clear sticky faults on IMU.
- clearStickyFaults() - Method in class swervelib.motors.SparkFlexSwerve
-
Clear the sticky faults on the motor controller.
- clearStickyFaults() - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Clear the sticky faults on the motor controller.
- clearStickyFaults() - Method in class swervelib.motors.SparkMaxSwerve
-
Clear the sticky faults on the motor controller.
- clearStickyFaults() - Method in class swervelib.motors.SwerveMotor
-
Clear the sticky faults on the motor controller.
- clearStickyFaults() - Method in class swervelib.motors.TalonFXSwerve
-
Clear the sticky faults on the motor controller.
- clearStickyFaults() - Method in class swervelib.motors.TalonSRXSwerve
-
Clear the sticky faults on the motor controller.
- config - Variable in class swervelib.SwerveController
-
SwerveControllerConfiguration
object storing data to generate thePIDController
for controlling the robot heading, and deadband for heading joystick. - configuration - Variable in class swervelib.SwerveModule
-
Swerve module configuration options.
- configure(boolean) - Method in class swervelib.encoders.AnalogAbsoluteEncoderSwerve
-
Configure the absolute encoder to read from [0, 360) per second.
- configure(boolean) - Method in class swervelib.encoders.CanAndMagSwerve
-
Configure the CANandMag to read from [0, 360) per second.
- configure(boolean) - Method in class swervelib.encoders.CANCoderSwerve
-
Configure the absolute encoder to read from [0, 360) per second.
- configure(boolean) - Method in class swervelib.encoders.PWMDutyCycleEncoderSwerve
-
Configure the inversion state of the encoder.
- configure(boolean) - Method in class swervelib.encoders.SparkMaxAnalogEncoderSwerve
-
Configure the absolute encoder to read from [0, 360) per second.
- configure(boolean) - Method in class swervelib.encoders.SparkMaxEncoderSwerve
-
Configure the absolute encoder to read from [0, 360) per second.
- configure(boolean) - Method in class swervelib.encoders.SwerveAbsoluteEncoder
-
Configure the absolute encoder to read from [0, 360) per second.
- configureCANStatusFrames(int) - Method in class swervelib.motors.TalonFXSwerve
-
Set the CAN status frames.
- configureCANStatusFrames(int) - Method in class swervelib.motors.TalonSRXSwerve
-
Set the CAN status frames.
- configureCANStatusFrames(int, int, int, int, int) - Method in class swervelib.motors.SparkFlexSwerve
-
Set the CAN status frames.
- configureCANStatusFrames(int, int, int, int, int) - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Set the CAN status frames.
- configureCANStatusFrames(int, int, int, int, int, int, int) - Method in class swervelib.motors.SparkMaxSwerve
-
Set the CAN status frames.
- configureCANStatusFrames(int, int, int, int, int, int, int, int, int, int, int) - Method in class swervelib.motors.TalonFXSwerve
-
Set the CAN status frames.
- configureCANStatusFrames(int, int, int, int, int, int, int, int, int, int, int) - Method in class swervelib.motors.TalonSRXSwerve
-
Set the CAN status frames.
- configureIntegratedEncoder(double) - Method in class swervelib.motors.SparkFlexSwerve
-
Configure the integrated encoder for the swerve module.
- configureIntegratedEncoder(double) - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Configure the integrated encoder for the swerve module.
- configureIntegratedEncoder(double) - Method in class swervelib.motors.SparkMaxSwerve
-
Configure the integrated encoder for the swerve module.
- configureIntegratedEncoder(double) - Method in class swervelib.motors.SwerveMotor
-
Configure the integrated encoder for the swerve module.
- configureIntegratedEncoder(double) - Method in class swervelib.motors.TalonFXSwerve
-
Configure the integrated encoder for the swerve module.
- configureIntegratedEncoder(double) - Method in class swervelib.motors.TalonSRXSwerve
-
Configure the integrated encoder for the swerve module.
- configurePIDF(PIDFConfig) - Method in class swervelib.motors.SparkFlexSwerve
-
Configure the PIDF values for the closed loop controller.
- configurePIDF(PIDFConfig) - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Configure the PIDF values for the closed loop controller.
- configurePIDF(PIDFConfig) - Method in class swervelib.motors.SparkMaxSwerve
-
Configure the PIDF values for the closed loop controller.
- configurePIDF(PIDFConfig) - Method in class swervelib.motors.SwerveMotor
-
Configure the PIDF values for the closed loop controller.
- configurePIDF(PIDFConfig) - Method in class swervelib.motors.TalonFXSwerve
-
Configure the PIDF values for the closed loop controller.
- configurePIDF(PIDFConfig) - Method in class swervelib.motors.TalonSRXSwerve
-
Configure the PIDF values for the closed loop controller.
- configurePIDWrapping(double, double) - Method in class swervelib.motors.SparkFlexSwerve
-
Configure the PID wrapping for the position closed loop controller.
- configurePIDWrapping(double, double) - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Configure the PID wrapping for the position closed loop controller.
- configurePIDWrapping(double, double) - Method in class swervelib.motors.SparkMaxSwerve
-
Configure the PID wrapping for the position closed loop controller.
- configurePIDWrapping(double, double) - Method in class swervelib.motors.SwerveMotor
-
Configure the PID wrapping for the position closed loop controller.
- configurePIDWrapping(double, double) - Method in class swervelib.motors.TalonFXSwerve
-
Configure the PID wrapping for the position closed loop controller.
- configurePIDWrapping(double, double) - Method in class swervelib.motors.TalonSRXSwerve
-
Configure the PID wrapping for the position closed loop controller.
- controllerPropertiesJson - Static variable in class swervelib.parser.SwerveParser
-
Parsed controllerproperties.json
- ControllerPropertiesJson - Class in swervelib.parser.json
-
SwerveController
parsed class. - ControllerPropertiesJson() - Constructor for class swervelib.parser.json.ControllerPropertiesJson
- conversionFactor - Variable in class swervelib.parser.json.ModuleJson
-
Conversion factor for the module, if different from the one in swervedrive.json
- conversionFactor - Variable in class swervelib.parser.json.PhysicalPropertiesJson
-
Conversion factor applied to the motor controllers PID loops.
- conversionFactor - Variable in class swervelib.parser.SwerveModulePhysicalCharacteristics
-
The conversion factors for the drive and angle motors, created by
SwerveMath.calculateMetersPerRotation(double, double, double)
andSwerveMath.calculateDegreesPerSteeringRotation(double, double)
. - conversionFactors - Variable in class swervelib.parser.json.ModuleJson
-
Conversion Factors composition.
- conversionFactors - Variable in class swervelib.parser.json.PhysicalPropertiesJson
-
Conversion Factors composition.
- conversionFactors - Variable in class swervelib.parser.SwerveModuleConfiguration
-
Conversion factor for drive motor onboard PID's and angle PID's.
- ConversionFactorsJson - Class in swervelib.parser.json.modules
-
Conversion Factors parsed JSON class
- ConversionFactorsJson() - Constructor for class swervelib.parser.json.modules.ConversionFactorsJson
- convertToNativeSensorUnits(double, double) - Method in class swervelib.motors.TalonSRXSwerve
-
Convert the setpoint into native sensor units.
- createConfigCustomTimeout(double) - Static method in class swervelib.SwerveDriveTest
-
Creates a SysIdRoutine.Config with a custom final timeout
- createControllerConfiguration(SwerveDriveConfiguration, double) - Method in class swervelib.parser.json.ControllerPropertiesJson
-
Create the
SwerveControllerConfiguration
based on parsed and given data. - createDriveFeedforward(double, double, double) - Static method in class swervelib.math.SwerveMath
-
Create the drive feedforward for swerve modules.
- createEncoder(SwerveMotor) - Method in class swervelib.parser.json.DeviceJson
-
Create a
SwerveAbsoluteEncoder
from the current configuration. - createIMU() - Method in class swervelib.parser.json.DeviceJson
-
Create a
SwerveIMU
from the given configuration. - createIMUVelocity(SwerveIMU) - Static method in class swervelib.imu.IMUVelocity
-
Static factory for IMU Velocity.
- createModuleConfiguration(PIDFConfig, PIDFConfig, SwerveModulePhysicalCharacteristics, String) - Method in class swervelib.parser.json.ModuleJson
-
Create the swerve module configuration based off of parsed data.
- createModules(SwerveModuleConfiguration[], SimpleMotorFeedforward) - Method in class swervelib.parser.SwerveDriveConfiguration
-
Create modules based off of the SwerveModuleConfiguration.
- createMotor(boolean) - Method in class swervelib.parser.json.DeviceJson
-
Create a
SwerveMotor
from the given configuration. - createPhysicalProperties() - Method in class swervelib.parser.json.PhysicalPropertiesJson
-
Create the physical characteristics based off the parsed data.
- createPIDController() - Method in class swervelib.parser.PIDFConfig
-
Create a PIDController from the PID values.
- createSwerveDrive(double) - Method in class swervelib.parser.SwerveParser
-
Create
SwerveDrive
from JSON configuration directory. - createSwerveDrive(double, double, double) - Method in class swervelib.parser.SwerveParser
-
Create
SwerveDrive
from JSON configuration directory. - createSwerveDrive(SimpleMotorFeedforward, double) - Method in class swervelib.parser.SwerveParser
-
Create
SwerveDrive
from JSON configuration directory. - createSwerveDrive(SimpleMotorFeedforward, double, double, double) - Method in class swervelib.parser.SwerveParser
-
Create
SwerveDrive
from JSON configuration directory. - cubeTranslation(Translation2d) - Static method in class swervelib.math.SwerveMath
-
Cube the
Translation2d
magnitude given in Polar coordinates. - currentLimit - Variable in class swervelib.parser.json.PhysicalPropertiesJson
-
The current limit in AMPs to apply to the motors.
D
- d - Variable in class swervelib.parser.PIDFConfig
-
Derivative Gain for PID.
- desiredChassisSpeeds - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
Describes the desired forward, sideways and angular velocity of the robot.
- desiredStates - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
An array of rotation and velocity values describing the desired state of each swerve module
- DeviceJson - Class in swervelib.parser.json
-
Device JSON parsed class.
- DeviceJson() - Constructor for class swervelib.parser.json.DeviceJson
- diameter - Variable in class swervelib.parser.json.modules.DriveConversionFactorsJson
-
Diameter of the wheel in inches.
- drive - Variable in class swervelib.parser.json.ModuleJson
-
Drive motor device configuration.
- drive - Variable in class swervelib.parser.json.modules.BoolMotorJson
-
Drive motor inversion state.
- drive - Variable in class swervelib.parser.json.modules.ConversionFactorsJson
-
Drive motor conversion factors composition.
- drive - Variable in class swervelib.parser.json.MotorConfigDouble
-
Drive motor.
- drive - Variable in class swervelib.parser.json.MotorConfigInt
-
Drive motor.
- drive - Variable in class swervelib.parser.json.PIDFPropertiesJson
-
The PIDF with Integral Zone used for the drive motor.
- drive(Translation2d, double, boolean, boolean) - Method in class swervelib.SwerveDrive
-
The primary method for controlling the drivebase.
- drive(Translation2d, double, boolean, boolean, Translation2d) - Method in class swervelib.SwerveDrive
-
The primary method for controlling the drivebase.
- drive(ChassisSpeeds) - Method in class swervelib.SwerveDrive
-
Secondary method for controlling the drivebase.
- drive(ChassisSpeeds, boolean, Translation2d) - Method in class swervelib.SwerveDrive
-
The primary method for controlling the drivebase.
- drive(ChassisSpeeds, Translation2d) - Method in class swervelib.SwerveDrive
-
Secondary method for controlling the drivebase.
- DriveConversionFactorsJson - Class in swervelib.parser.json.modules
-
Drive motor composite JSON parse class.
- DriveConversionFactorsJson() - Constructor for class swervelib.parser.json.modules.DriveConversionFactorsJson
- driveFieldOriented(ChassisSpeeds) - Method in class swervelib.SwerveDrive
-
Secondary method of controlling the drive base given velocity and adjusting it for field oriented use.
- driveFieldOriented(ChassisSpeeds, Translation2d) - Method in class swervelib.SwerveDrive
-
Secondary method of controlling the drive base given velocity and adjusting it for field oriented use.
- driveFieldOrientedandRobotOriented(ChassisSpeeds, ChassisSpeeds) - Method in class swervelib.SwerveDrive
-
Tertiary method of controlling the drive base given velocity in both field oriented and robot oriented at the same time.
- driveMotor - Variable in class swervelib.parser.SwerveModuleConfiguration
-
The drive motor and angle motor of this swerve module.
- driveMotorCurrentLimit - Variable in class swervelib.parser.SwerveModulePhysicalCharacteristics
-
Current limits for the Swerve Module.
- driveMotorInverted - Variable in class swervelib.parser.SwerveModuleConfiguration
-
State of inversion of the drive motor.
- driveMotorRampRate - Variable in class swervelib.parser.SwerveModulePhysicalCharacteristics
-
The time it takes for the motor to go from 0 to full throttle in seconds.
- drivePositionCache - Variable in class swervelib.SwerveModule
-
Drive motor position cache.
- driveVelocityCache - Variable in class swervelib.SwerveModule
-
Drive motor velocity cache.
E
- encoder - Variable in class swervelib.encoders.AnalogAbsoluteEncoderSwerve
-
Encoder as Analog Input.
- encoder - Variable in class swervelib.encoders.CanAndMagSwerve
-
The
Canandmag
representing the CANandMag on the CAN bus. - encoder - Variable in class swervelib.encoders.CANCoderSwerve
-
CANCoder with WPILib sendable and support.
- encoder - Variable in class swervelib.encoders.SparkMaxAnalogEncoderSwerve
-
The
SparkAnalogSensor
representing the duty cycle encoder attached to the SparkMax analog port. - encoder - Variable in class swervelib.encoders.SparkMaxEncoderSwerve
-
The
AbsoluteEncoder
representing the duty cycle encoder attached to the SparkMax. - encoder - Variable in class swervelib.motors.SparkFlexSwerve
-
Integrated encoder.
- encoder - Variable in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Integrated encoder.
- encoder - Variable in class swervelib.motors.SparkMaxSwerve
-
Integrated encoder.
- encoder - Variable in class swervelib.parser.json.ModuleJson
-
Absolute encoder device configuration.
- ERROR - Enum constant in enum class swervelib.telemetry.Alert.AlertType
-
High priority alert - displayed first on the dashboard with a red "X" symbol.
- ERROR_TRACE - Enum constant in enum class swervelib.telemetry.Alert.AlertType
-
High priority alert - displayed first on the dashboard with a red "X" symbol.
F
- f - Variable in class swervelib.parser.PIDFConfig
-
Feedforward value for PID.
- factor - Variable in class swervelib.parser.json.modules.AngleConversionFactorsJson
-
Calculated or given conversion factor.
- factor - Variable in class swervelib.parser.json.modules.DriveConversionFactorsJson
-
Calculated conversion factor.
- factoryDefault() - Method in class swervelib.encoders.AnalogAbsoluteEncoderSwerve
-
Reset the encoder to factory defaults.
- factoryDefault() - Method in class swervelib.encoders.CanAndMagSwerve
-
Reset the encoder to factory defaults.
- factoryDefault() - Method in class swervelib.encoders.CANCoderSwerve
-
Reset the encoder to factory defaults.
- factoryDefault() - Method in class swervelib.encoders.PWMDutyCycleEncoderSwerve
-
Reset the encoder to factory defaults.
- factoryDefault() - Method in class swervelib.encoders.SparkMaxAnalogEncoderSwerve
-
Reset the encoder to factory defaults.
- factoryDefault() - Method in class swervelib.encoders.SparkMaxEncoderSwerve
-
Reset the encoder to factory defaults.
- factoryDefault() - Method in class swervelib.encoders.SwerveAbsoluteEncoder
-
Reset the encoder to factory defaults.
- factoryDefault() - Method in class swervelib.imu.ADIS16448Swerve
-
Reset IMU to factory default.
- factoryDefault() - Method in class swervelib.imu.ADIS16470Swerve
-
Reset IMU to factory default.
- factoryDefault() - Method in class swervelib.imu.ADXRS450Swerve
-
Reset IMU to factory default.
- factoryDefault() - Method in class swervelib.imu.AnalogGyroSwerve
-
Reset IMU to factory default.
- factoryDefault() - Method in class swervelib.imu.CanandgyroSwerve
-
Reset
Canandgyro
to factory default. - factoryDefault() - Method in class swervelib.imu.NavXSwerve
-
Reset offset to current gyro reading.
- factoryDefault() - Method in class swervelib.imu.Pigeon2Swerve
-
Reset
Pigeon2
to factory default. - factoryDefault() - Method in class swervelib.imu.PigeonSwerve
-
Reset IMU to factory default.
- factoryDefault() - Method in class swervelib.imu.SwerveIMU
-
Reset IMU to factory default.
- factoryDefaults() - Method in class swervelib.motors.SparkFlexSwerve
-
Configure the factory defaults.
- factoryDefaults() - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Configure the factory defaults.
- factoryDefaults() - Method in class swervelib.motors.SparkMaxSwerve
-
Configure the factory defaults.
- factoryDefaults() - Method in class swervelib.motors.SwerveMotor
-
Configure the factory defaults.
- factoryDefaults() - Method in class swervelib.motors.TalonFXSwerve
-
Configure the factory defaults.
- factoryDefaults() - Method in class swervelib.motors.TalonSRXSwerve
-
Configure the factory defaults.
- field - Variable in class swervelib.SwerveDrive
-
Field object.
- findCouplingRatio(SwerveDrive, double, boolean) - Static method in class swervelib.SwerveDriveTest
-
Find the coupling ratio for all modules.
- findDriveMotorKV(SwerveDrive, double, double, double) - Static method in class swervelib.SwerveDriveTest
-
Find the minimum amount of power required to move the swerve drive motors.
- forwardDirection - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
The direction the robot should be facing when the "Robot Rotation" is zero or blank.
- front - Variable in class swervelib.parser.json.modules.LocationJson
-
Location of the swerve module in inches from the center of the robot horizontally.
G
- gearRatio - Variable in class swervelib.parser.json.modules.AngleConversionFactorsJson
-
Gear ratio for the angle/steering/azimuth motor on the Swerve Module.
- gearRatio - Variable in class swervelib.parser.json.modules.DriveConversionFactorsJson
-
Gear ratio for the drive motor rotations to turn the wheel 1 complete rotation.
- generateSysIdCommand(SysIdRoutine, double, double, double) - Static method in class swervelib.SwerveDriveTest
-
Creates a command that can be mapped to a button or other trigger.
- getAbsoluteEncoder() - Method in class swervelib.encoders.AnalogAbsoluteEncoderSwerve
-
Get the instantiated absolute encoder Object.
- getAbsoluteEncoder() - Method in class swervelib.encoders.CanAndMagSwerve
-
Get the instantiated absolute encoder Object.
- getAbsoluteEncoder() - Method in class swervelib.encoders.CANCoderSwerve
-
Get the instantiated absolute encoder Object.
- getAbsoluteEncoder() - Method in class swervelib.encoders.PWMDutyCycleEncoderSwerve
-
Get the encoder object.
- getAbsoluteEncoder() - Method in class swervelib.encoders.SparkMaxAnalogEncoderSwerve
-
Get the instantiated absolute encoder Object.
- getAbsoluteEncoder() - Method in class swervelib.encoders.SparkMaxEncoderSwerve
-
Get the instantiated absolute encoder Object.
- getAbsoluteEncoder() - Method in class swervelib.encoders.SwerveAbsoluteEncoder
-
Get the instantiated absolute encoder Object.
- getAbsoluteEncoder() - Method in class swervelib.SwerveModule
-
Get the
SwerveAbsoluteEncoder
for theSwerveModule
. - getAbsoluteEncoderReadIssue() - Method in class swervelib.SwerveModule
-
Get if the last Absolute Encoder had a read issue, such as it does not exist.
- getAbsolutePosition() - Method in class swervelib.encoders.AnalogAbsoluteEncoderSwerve
-
Get the absolute position of the encoder.
- getAbsolutePosition() - Method in class swervelib.encoders.CanAndMagSwerve
-
Get the absolute position of the encoder.
- getAbsolutePosition() - Method in class swervelib.encoders.CANCoderSwerve
-
Get the absolute position of the encoder.
- getAbsolutePosition() - Method in class swervelib.encoders.PWMDutyCycleEncoderSwerve
-
Get the absolute position of the encoder.
- getAbsolutePosition() - Method in class swervelib.encoders.SparkMaxAnalogEncoderSwerve
-
Get the absolute position of the encoder.
- getAbsolutePosition() - Method in class swervelib.encoders.SparkMaxEncoderSwerve
-
Get the absolute position of the encoder.
- getAbsolutePosition() - Method in class swervelib.encoders.SwerveAbsoluteEncoder
-
Get the absolute position of the encoder.
- getAbsolutePosition() - Method in class swervelib.SwerveModule
-
Get the absolute position.
- getAccel() - Method in class swervelib.imu.ADIS16448Swerve
-
Fetch the acceleration [x, y, z] from the IMU in meters per second squared.
- getAccel() - Method in class swervelib.imu.ADIS16470Swerve
-
Fetch the acceleration [x, y, z] from the IMU in meters per second squared.
- getAccel() - Method in class swervelib.imu.ADXRS450Swerve
-
Fetch the acceleration [x, y, z] from the IMU in meters per second squared.
- getAccel() - Method in class swervelib.imu.AnalogGyroSwerve
-
Fetch the acceleration [x, y, z] from the IMU in meters per second squared.
- getAccel() - Method in class swervelib.imu.CanandgyroSwerve
-
Fetch the acceleration [x, y, z] from the IMU in meters per second squared.
- getAccel() - Method in class swervelib.imu.NavXSwerve
-
Fetch the acceleration [x, y, z] from the IMU in meters per second squared.
- getAccel() - Method in class swervelib.imu.Pigeon2Swerve
-
Fetch the acceleration [x, y, z] from the IMU in meters per second squared.
- getAccel() - Method in class swervelib.imu.PigeonSwerve
-
Fetch the acceleration [x, y, z] from the IMU in meters per second squared.
- getAccel() - Method in class swervelib.imu.SwerveIMU
-
Fetch the acceleration [x, y, z] from the IMU in meters per second squared.
- getAccel() - Method in class swervelib.simulation.SwerveIMUSimulation
-
Fetch the acceleration [x, y, z] from the IMU in m/s/s.
- getAccel() - Method in class swervelib.SwerveDrive
-
Gets current acceleration of the robot in m/s/s.
- getAngleMotor() - Method in class swervelib.SwerveModule
-
Get the angle
SwerveMotor
for theSwerveModule
. - getAnglePIDF() - Method in class swervelib.SwerveModule
-
Get the current angle/azimuth/steering motor PIDF values.
- getAppliedOutput() - Method in class swervelib.motors.SparkFlexSwerve
-
Get the applied dutycycle output.
- getAppliedOutput() - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Get the applied dutycycle output.
- getAppliedOutput() - Method in class swervelib.motors.SparkMaxSwerve
-
Get the applied dutycycle output.
- getAppliedOutput() - Method in class swervelib.motors.SwerveMotor
-
Get the applied dutycycle output.
- getAppliedOutput() - Method in class swervelib.motors.TalonFXSwerve
-
Get the applied dutycycle output.
- getAppliedOutput() - Method in class swervelib.motors.TalonSRXSwerve
-
Get the applied dutycycle output.
- getConfiguration() - Method in class swervelib.SwerveModule
-
Fetch the
SwerveModuleConfiguration
for theSwerveModule
with the parsed configurations. - getDriveBaseRadiusMeters() - Method in class swervelib.parser.SwerveDriveConfiguration
-
Calculate the Drive Base Radius
- getDriveMotor() - Method in class swervelib.SwerveModule
-
Get the drive
SwerveMotor
for theSwerveModule
. - getDrivePIDF() - Method in class swervelib.SwerveModule
-
Get the current drive motor PIDF values.
- getFieldVelocity() - Method in class swervelib.SwerveDrive
-
Gets the current field-relative velocity (x, y and omega) of the robot
- getGyro() - Method in class swervelib.SwerveDrive
-
Getter for the
SwerveIMU
. - getGyroRotation3d() - Method in class swervelib.simulation.SwerveIMUSimulation
-
Gets the estimated gyro
Rotation3d
of the robot. - getGyroRotation3d() - Method in class swervelib.SwerveDrive
-
Gets the current gyro
Rotation3d
of the robot, as reported by the imu. - getIMU() - Method in class swervelib.imu.ADIS16448Swerve
-
Get the instantiated IMU object.
- getIMU() - Method in class swervelib.imu.ADIS16470Swerve
-
Get the instantiated IMU object.
- getIMU() - Method in class swervelib.imu.ADXRS450Swerve
-
Get the instantiated IMU object.
- getIMU() - Method in class swervelib.imu.AnalogGyroSwerve
-
Get the instantiated IMU object.
- getIMU() - Method in class swervelib.imu.CanandgyroSwerve
-
Get the instantiated
Canandgyro
IMU object. - getIMU() - Method in class swervelib.imu.NavXSwerve
-
Get the instantiated NavX(
AHRS
) IMU object. - getIMU() - Method in class swervelib.imu.Pigeon2Swerve
-
Get the instantiated
Pigeon2
object. - getIMU() - Method in class swervelib.imu.PigeonSwerve
-
Get the instantiated
WPI_PigeonIMU
IMU object. - getIMU() - Method in class swervelib.imu.SwerveIMU
-
Get the instantiated IMU object.
- getJoystickAngle(double, double) - Method in class swervelib.SwerveController
-
Get the angle in radians based off of the heading joysticks.
- getMaximumAngularVelocity() - Method in class swervelib.SwerveDrive
-
Get the maximum angular velocity, either
SwerveDrive.attainableMaxRotationalVelocityRadiansPerSecond
orSwerveControllerConfiguration.maxAngularVelocity
. - getMaximumVelocity() - Method in class swervelib.SwerveDrive
-
Get the maximum velocity from
SwerveDrive.attainableMaxTranslationalSpeedMetersPerSecond
orSwerveDrive.maxSpeedMPS
whichever is higher. - getModuleConfigurationByName(String, SwerveDriveConfiguration) - Static method in class swervelib.parser.SwerveParser
-
Get the swerve module by the json name.
- getModuleMap() - Method in class swervelib.SwerveDrive
-
Get the
SwerveModule
's as aHashMap
where the key is the swerve module configuration name. - getModulePositions() - Method in class swervelib.SwerveDrive
-
Gets the current module positions (azimuth and wheel position (meters)).
- getModules() - Method in class swervelib.SwerveDrive
-
Get the
SwerveModule
s associated with theSwerveDrive
. - getMotor() - Method in class swervelib.motors.SparkFlexSwerve
-
Get the motor object from the module.
- getMotor() - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Get the motor object from the module.
- getMotor() - Method in class swervelib.motors.SparkMaxSwerve
-
Get the motor object from the module.
- getMotor() - Method in class swervelib.motors.SwerveMotor
-
Get the motor object from the module.
- getMotor() - Method in class swervelib.motors.TalonFXSwerve
-
Get the motor object from the module.
- getMotor() - Method in class swervelib.motors.TalonSRXSwerve
-
Get the motor object from the module.
- getOdometryHeading() - Method in class swervelib.SwerveDrive
-
Fetch the latest odometry heading, should be trusted over
SwerveDrive.getYaw()
. - getPitch() - Method in class swervelib.simulation.SwerveIMUSimulation
-
Pitch is not simulated currently, always returns 0.
- getPitch() - Method in class swervelib.SwerveDrive
-
Gets the current pitch angle of the robot, as reported by the imu.
- getPose() - Method in class swervelib.SwerveDrive
-
Gets the current pose (position and rotation) of the robot, as reported by odometry.
- getPosition() - Method in class swervelib.motors.SparkFlexSwerve
-
Get the position of the integrated encoder.
- getPosition() - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Get the position of the integrated encoder.
- getPosition() - Method in class swervelib.motors.SparkMaxSwerve
-
Get the position of the integrated encoder.
- getPosition() - Method in class swervelib.motors.SwerveMotor
-
Get the position of the integrated encoder.
- getPosition() - Method in class swervelib.motors.TalonFXSwerve
-
Get the position of the integrated encoder.
- getPosition() - Method in class swervelib.motors.TalonSRXSwerve
-
Get the position of the integrated encoder.
- getPosition() - Method in class swervelib.simulation.SwerveModuleSimulation
-
Get the simulated swerve module position.
- getPosition() - Method in class swervelib.SwerveModule
-
Get the position of the swerve module.
- getRate() - Method in class swervelib.imu.ADIS16448Swerve
-
Fetch the rotation rate from the IMU in degrees per second.
- getRate() - Method in class swervelib.imu.ADIS16470Swerve
-
Fetch the rotation rate from the IMU in degrees per second.
- getRate() - Method in class swervelib.imu.ADXRS450Swerve
-
Fetch the rotation rate from the IMU in degrees per second.
- getRate() - Method in class swervelib.imu.AnalogGyroSwerve
-
Fetch the rotation rate from the IMU in degrees per second.
- getRate() - Method in class swervelib.imu.CanandgyroSwerve
-
Fetch the rotation rate from the IMU in degrees per second.
- getRate() - Method in class swervelib.imu.NavXSwerve
-
Fetch the rotation rate from the IMU in degrees per second.
- getRate() - Method in class swervelib.imu.Pigeon2Swerve
-
Fetch the rotation rate from the IMU in degrees per second.
- getRate() - Method in class swervelib.imu.PigeonSwerve
-
Fetch the rotation rate from the IMU in degrees per second.
- getRate() - Method in class swervelib.imu.SwerveIMU
-
Fetch the rotation rate from the IMU in degrees per second.
- getRawAbsolutePosition() - Method in class swervelib.SwerveModule
-
Get the absolute position.
- getRawRotation3d() - Method in class swervelib.imu.ADIS16448Swerve
-
Fetch the
Rotation3d
from the IMU without any zeroing. - getRawRotation3d() - Method in class swervelib.imu.ADIS16470Swerve
-
Fetch the
Rotation3d
from the IMU without any zeroing. - getRawRotation3d() - Method in class swervelib.imu.ADXRS450Swerve
-
Fetch the
Rotation3d
from the IMU without any zeroing. - getRawRotation3d() - Method in class swervelib.imu.AnalogGyroSwerve
-
Fetch the
Rotation3d
from the IMU without any zeroing. - getRawRotation3d() - Method in class swervelib.imu.CanandgyroSwerve
-
Fetch the
Rotation3d
from the IMU without any zeroing. - getRawRotation3d() - Method in class swervelib.imu.NavXSwerve
-
Fetch the
Rotation3d
from the IMU without any zeroing. - getRawRotation3d() - Method in class swervelib.imu.Pigeon2Swerve
-
Fetch the
Rotation3d
from the IMU without any zeroing. - getRawRotation3d() - Method in class swervelib.imu.PigeonSwerve
-
Fetch the
Rotation3d
from the IMU without any zeroing. - getRawRotation3d() - Method in class swervelib.imu.SwerveIMU
-
Fetch the
Rotation3d
from the IMU without any zeroing. - getRawTargetSpeeds(double, double, double) - Method in class swervelib.SwerveController
-
Get the
ChassisSpeeds
based of raw speeds desired in meters/second and heading in radians. - getRawTargetSpeeds(double, double, double, double) - Method in class swervelib.SwerveController
-
Get the
ChassisSpeeds
based of raw speeds desired in meters/second and heading in radians. - getRelativePosition() - Method in class swervelib.SwerveModule
-
Get the relative angle in degrees.
- getRobotVelocity() - Method in class swervelib.SwerveDrive
-
Gets the current robot-relative velocity (x, y and omega) of the robot
- getRoll() - Method in class swervelib.simulation.SwerveIMUSimulation
-
Roll is not simulated currently, always returns 0.
- getRoll() - Method in class swervelib.SwerveDrive
-
Gets the current roll angle of the robot, as reported by the imu.
- getRotation3d() - Method in class swervelib.imu.ADIS16448Swerve
-
Fetch the
Rotation3d
from the IMU. - getRotation3d() - Method in class swervelib.imu.ADIS16470Swerve
-
Fetch the
Rotation3d
from the IMU. - getRotation3d() - Method in class swervelib.imu.ADXRS450Swerve
-
Fetch the
Rotation3d
from the IMU. - getRotation3d() - Method in class swervelib.imu.AnalogGyroSwerve
-
Fetch the
Rotation3d
from the IMU. - getRotation3d() - Method in class swervelib.imu.CanandgyroSwerve
-
Fetch the
Rotation3d
from the IMU. - getRotation3d() - Method in class swervelib.imu.NavXSwerve
-
Fetch the
Rotation3d
from the IMU. - getRotation3d() - Method in class swervelib.imu.Pigeon2Swerve
-
Fetch the
Rotation3d
from the IMU. - getRotation3d() - Method in class swervelib.imu.PigeonSwerve
-
Fetch the
Rotation3d
from the IMU. - getRotation3d() - Method in class swervelib.imu.SwerveIMU
-
Fetch the
Rotation3d
from the IMU. - getState() - Method in class swervelib.simulation.SwerveModuleSimulation
-
Get the
SwerveModuleState
of the simulated module. - getState() - Method in class swervelib.SwerveModule
-
Get the Swerve Module state.
- getStates() - Method in class swervelib.SwerveDrive
-
Gets the current module states (azimuth and velocity)
- getSwerveController() - Method in class swervelib.SwerveDrive
-
Helper function to get the
SwerveDrive.swerveController
for theSwerveDrive
which can be used to generateChassisSpeeds
for the robot to orient it correctly given axis or angles, and applySlewRateLimiter
to given inputs. - getSwerveModule(SwerveModule[], boolean, boolean) - Static method in class swervelib.math.SwerveMath
-
Get the fruthest module from center based on the module locations.
- getSwerveModulePoses(Pose2d) - Method in class swervelib.SwerveDrive
-
Get the swerve module poses and on the field relative to the robot.
- getTargetSpeeds(double, double, double, double, double) - Method in class swervelib.SwerveController
-
Get the chassis speeds based on controller input of 1 joystick [-1,1] and an angle.
- getTargetSpeeds(double, double, double, double, double, double) - Method in class swervelib.SwerveController
-
Get the chassis speeds based on controller input of 2 joysticks.
- getTranslation2d(ChassisSpeeds) - Static method in class swervelib.SwerveController
-
Helper function to get the
Translation2d
of the chassis speeds given theChassisSpeeds
. - getValue() - Method in class swervelib.parser.Cache
-
Get the most up to date cached value.
- getVelocity() - Method in class swervelib.encoders.AnalogAbsoluteEncoderSwerve
-
Get the velocity in degrees/sec.
- getVelocity() - Method in class swervelib.encoders.CanAndMagSwerve
-
Get the velocity in degrees/sec.
- getVelocity() - Method in class swervelib.encoders.CANCoderSwerve
-
Get the velocity in degrees/sec.
- getVelocity() - Method in class swervelib.encoders.PWMDutyCycleEncoderSwerve
-
Get the velocity in degrees/sec.
- getVelocity() - Method in class swervelib.encoders.SparkMaxAnalogEncoderSwerve
-
Get the velocity in degrees/sec.
- getVelocity() - Method in class swervelib.encoders.SparkMaxEncoderSwerve
-
Get the velocity in degrees/sec.
- getVelocity() - Method in class swervelib.encoders.SwerveAbsoluteEncoder
-
Get the velocity in degrees/sec.
- getVelocity() - Method in class swervelib.imu.IMUVelocity
-
Get the robot's angular velocity based on averaged meaasurements from the IMU.
- getVelocity() - Method in class swervelib.motors.SparkFlexSwerve
-
Get the velocity of the integrated encoder.
- getVelocity() - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Get the velocity of the integrated encoder.
- getVelocity() - Method in class swervelib.motors.SparkMaxSwerve
-
Get the velocity of the integrated encoder.
- getVelocity() - Method in class swervelib.motors.SwerveMotor
-
Get the velocity of the integrated encoder.
- getVelocity() - Method in class swervelib.motors.TalonFXSwerve
-
Get the velocity of the integrated encoder.
- getVelocity() - Method in class swervelib.motors.TalonSRXSwerve
-
Get the velocity of the integrated encoder.
- getVoltage() - Method in class swervelib.motors.SparkFlexSwerve
-
Get the voltage output of the motor controller.
- getVoltage() - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Get the voltage output of the motor controller.
- getVoltage() - Method in class swervelib.motors.SparkMaxSwerve
-
Get the voltage output of the motor controller.
- getVoltage() - Method in class swervelib.motors.SwerveMotor
-
Get the voltage output of the motor controller.
- getVoltage() - Method in class swervelib.motors.TalonFXSwerve
-
Get the voltage output of the motor controller.
- getVoltage() - Method in class swervelib.motors.TalonSRXSwerve
-
Get the voltage output of the motor controller.
- getYaw() - Method in class swervelib.simulation.SwerveIMUSimulation
-
Get the estimated angle of the robot.
- getYaw() - Method in class swervelib.SwerveDrive
-
Gets the current yaw angle of the robot, as reported by the imu.
H
- heading - Variable in class swervelib.parser.json.ControllerPropertiesJson
-
The PID used to control the robot heading.
- headingCalculate(double, double) - Method in class swervelib.SwerveController
-
Calculate the angular velocity given the current and target heading angle in radians.
- headingCorrection - Variable in class swervelib.SwerveDrive
-
Whether to correct heading when driving translationally.
- headingPIDF - Variable in class swervelib.parser.SwerveControllerConfiguration
-
PIDF for the heading of the robot.
- HIGH - Enum constant in enum class swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity
-
Full swerve drive data is sent back in both human and machine readable forms.
I
- i - Variable in class swervelib.parser.PIDFConfig
-
Integral Gain for PID.
- i2cLockupWarning - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
An
Alert
for if there is an I2C lockup issue on the roboRIO. - id - Variable in class swervelib.parser.json.DeviceJson
-
The CAN ID or pin ID of the device.
- imu - Variable in class swervelib.parser.json.SwerveDriveJson
-
Robot IMU used to determine heading of the robot.
- imu - Variable in class swervelib.parser.SwerveDriveConfiguration
-
Swerve IMU
- IMULinearMovingAverageFilter - Class in swervelib.math
-
A linear filter that does not calculate() each time a value is added to the DoubleCircularBuffer.
- IMULinearMovingAverageFilter(int) - Constructor for class swervelib.math.IMULinearMovingAverageFilter
-
Construct a linear moving average fitler
- imuReadingCache - Variable in class swervelib.SwerveDrive
-
IMU reading cache for robot readings.
- IMUVelocity - Class in swervelib.imu
-
Generic IMU Velocity filter.
- IMUVelocity(SwerveIMU, double, int) - Constructor for class swervelib.imu.IMUVelocity
-
Constructor for the IMU Velocity.
- INFO - Enum constant in enum class swervelib.telemetry.Alert.AlertType
-
Low priority alert - displayed last on the dashboard with a green "i" symbol.
- INFO - Enum constant in enum class swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity
-
Medium telemetry data, swerve directory
- inverted - Variable in class swervelib.parser.json.ModuleJson
-
Defines which motors are inverted.
- invertedIMU - Variable in class swervelib.parser.json.SwerveDriveJson
-
Invert the IMU of the robot.
- isAngleEmpty() - Method in class swervelib.parser.json.modules.ConversionFactorsJson
-
Check if the conversion factors are set for the angle motor.
- isAttachedAbsoluteEncoder() - Method in class swervelib.motors.SparkFlexSwerve
-
Queries whether the absolute encoder is directly attached to the motor controller.
- isAttachedAbsoluteEncoder() - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Queries whether the absolute encoder is directly attached to the motor controller.
- isAttachedAbsoluteEncoder() - Method in class swervelib.motors.SparkMaxSwerve
-
Queries whether the absolute encoder is directly attached to the motor controller.
- isAttachedAbsoluteEncoder() - Method in class swervelib.motors.SwerveMotor
-
Queries whether the absolute encoder is directly attached to the motor controller.
- isAttachedAbsoluteEncoder() - Method in class swervelib.motors.TalonFXSwerve
-
Queries whether the absolute encoder is directly attached to the motor controller.
- isAttachedAbsoluteEncoder() - Method in class swervelib.motors.TalonSRXSwerve
-
Queries whether the absolute encoder is directly attached to the motor controller.
- isDriveEmpty() - Method in class swervelib.parser.json.modules.ConversionFactorsJson
-
Check if the conversion factors are set for the drive motor.
- isDriveMotor - Variable in class swervelib.motors.SwerveMotor
-
Whether the swerve motor is a drive motor.
- isSimulation - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
State of simulation of the Robot, used to optimize retrieval.
- isStale() - Method in class swervelib.parser.Cache
-
Return whether the cache is stale.
- iz - Variable in class swervelib.parser.PIDFConfig
-
Integral zone of the PID.
K
- kinematics - Variable in class swervelib.SwerveDrive
-
Swerve Kinematics object.
L
- lastAngleScalar - Variable in class swervelib.SwerveController
-
Last angle as a scalar [-1,1] the robot was set to.
- left - Variable in class swervelib.parser.json.modules.LocationJson
-
Location of the swerve module in inches from the center of the robot vertically.
- limitVelocity(Translation2d, ChassisSpeeds, Pose2d, double, double, List<Matter>, SwerveDriveConfiguration) - Static method in class swervelib.math.SwerveMath
-
Limits a commanded velocity to prevent exceeding the maximum acceleration given by
SwerveMath.calcMaxAccel(edu.wpi.first.math.geometry.Rotation2d, java.util.List<swervelib.math.Matter>, double, swervelib.parser.SwerveDriveConfiguration)
. - location - Variable in class swervelib.parser.json.ModuleJson
-
The location of the swerve module from the center of the robot in inches.
- LocationJson - Class in swervelib.parser.json.modules
-
Location JSON parsed class.
- LocationJson() - Constructor for class swervelib.parser.json.modules.LocationJson
- lockPose() - Method in class swervelib.SwerveDrive
-
Point all modules toward the robot center, thus making the robot very difficult to move.
- logAngularMotorActivity(SwerveModule, SysIdRoutineLog, Supplier<Double>) - Static method in class swervelib.SwerveDriveTest
-
Logs info about the angle motor to the SysIdRoutineLog
- logAngularMotorDutyCycle(SwerveModule, SysIdRoutineLog) - Static method in class swervelib.SwerveDriveTest
-
Logs info about the angle motor to the SysIdRoutineLog.
- logAngularMotorVoltage(SwerveModule, SysIdRoutineLog) - Static method in class swervelib.SwerveDriveTest
-
Logs info about the angle motor to the SysIdRoutineLog
- logDriveMotorActivity(SwerveModule, SysIdRoutineLog, Supplier<Double>) - Static method in class swervelib.SwerveDriveTest
-
Logs power, position and velocuty info form the drive motor to the SysIdRoutineLog
- logDriveMotorDutyCycle(SwerveModule, SysIdRoutineLog) - Static method in class swervelib.SwerveDriveTest
-
Logs output, position and velocuty info form the drive motor to the SysIdRoutineLog
Although SysIdRoutine expects to be logging Voltage, this function logs in Duty-Cycle (percent output) because it results in correctly adjusted values in the analysis for use in this library. - logDriveMotorVoltage(SwerveModule, SysIdRoutineLog) - Static method in class swervelib.SwerveDriveTest
-
Logs voltage, position and velocuty info form the drive motor to the SysIdRoutineLog
- LOW - Enum constant in enum class swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity
-
Low telemetry data, only post the robot position on the field.
M
- MACHINE - Enum constant in enum class swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity
-
Only send the machine readable data related to swerve drive.
- mass - Variable in class swervelib.math.Matter
-
Mass in kg of object.
- massMoment() - Method in class swervelib.math.Matter
-
Get the center mass of the object.
- Matter - Class in swervelib.math
-
Object with significant mass that needs to be taken into account.
- Matter(Translation3d, double) - Constructor for class swervelib.math.Matter
-
Construct an object representing some significant matter on the robot.
- max - Variable in class swervelib.parser.deserializer.PIDFRange
-
Maximum value.
- maxAngularVelocity - Variable in class swervelib.parser.SwerveControllerConfiguration
-
Maximum angular velocity in rad/s
- maxAngularVelocity - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
The maximum achievable angular velocity of the robot.
- maximumRetries - Variable in class swervelib.encoders.SwerveAbsoluteEncoder
-
The maximum amount of times the swerve encoder will attempt to configure itself if failures occur.
- maximumRetries - Variable in class swervelib.motors.SwerveMotor
-
The maximum amount of times the swerve motor will attempt to configure a motor if failures occur.
- maxSpeed - Variable in class swervelib.SwerveModule
-
Maximum speed of the drive motors in meters per second.
- maxSpeed - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
The maximum achievable speed of the modules, used to adjust the size of the vectors.
- measuredChassisSpeeds - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
The maximum achievable angular velocity of the robot.
- measuredStates - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
An array of rotation and velocity values describing the measured state of each swerve module
- min - Variable in class swervelib.parser.deserializer.PIDFRange
-
Minimum value.
- moduleCount - Variable in class swervelib.parser.SwerveDriveConfiguration
-
Number of modules on the robot.
- moduleCount - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
The number of swerve modules
- ModuleJson - Class in swervelib.parser.json
-
SwerveModule
JSON parsed class. - ModuleJson() - Constructor for class swervelib.parser.json.ModuleJson
- moduleJsons - Static variable in class swervelib.parser.SwerveParser
-
Array holding the module jsons given in
SwerveDriveJson
. - moduleLocation - Variable in class swervelib.parser.SwerveModuleConfiguration
-
Swerve module location relative to the robot.
- moduleLocationsMeters - Variable in class swervelib.parser.SwerveDriveConfiguration
-
Swerve Module locations.
- moduleNumber - Variable in class swervelib.SwerveModule
-
Module number for kinematics, usually 0 to 3.
- modules - Variable in class swervelib.parser.json.SwerveDriveJson
-
Module JSONs in order clockwise order starting from front left.
- modules - Variable in class swervelib.parser.SwerveDriveConfiguration
-
Swerve Modules.
- MotorConfigDouble - Class in swervelib.parser.json
-
Used to store doubles for motor configuration.
- MotorConfigDouble() - Constructor for class swervelib.parser.json.MotorConfigDouble
-
Default constructor.
- MotorConfigDouble(double, double) - Constructor for class swervelib.parser.json.MotorConfigDouble
-
Default constructor.
- MotorConfigInt - Class in swervelib.parser.json
-
Used to store ints for motor configuration.
- MotorConfigInt() - Constructor for class swervelib.parser.json.MotorConfigInt
-
Default constructor.
- MotorConfigInt(int, int) - Constructor for class swervelib.parser.json.MotorConfigInt
-
Default constructor with values.
N
- name - Variable in class swervelib.parser.SwerveModuleConfiguration
-
Name for the swerve module for telemetry.
- NavXSwerve - Class in swervelib.imu
-
Communicates with the NavX(
AHRS
) as the IMU. - NavXSwerve(I2C.Port) - Constructor for class swervelib.imu.NavXSwerve
-
Constructor for the NavX(
AHRS
) swerve. - NavXSwerve(SerialPort.Port) - Constructor for class swervelib.imu.NavXSwerve
-
Constructor for the NavX(
AHRS
) swerve. - NavXSwerve(SPI.Port) - Constructor for class swervelib.imu.NavXSwerve
-
Constructor for the NavX(
AHRS
) swerve. - NONE - Enum constant in enum class swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity
-
No telemetry data is sent back.
- normalizeAngle(double) - Static method in class swervelib.math.SwerveMath
-
Normalize an angle to be within 0 to 360.
O
- optimalVoltage - Variable in class swervelib.parser.json.PhysicalPropertiesJson
-
The voltage to use for the smart motor voltage compensation, default is 12.
- optimalVoltage - Variable in class swervelib.parser.SwerveModulePhysicalCharacteristics
-
The voltage to use for the smart motor voltage compensation.
- output - Variable in class swervelib.parser.PIDFConfig
-
The PIDF output range.
P
- p - Variable in class swervelib.parser.PIDFConfig
-
Proportional Gain for PID.
- physicalCharacteristics - Variable in class swervelib.parser.SwerveDriveConfiguration
-
Physical characteristics of the swerve drive from physicalproperties.json.
- physicalCharacteristics - Variable in class swervelib.parser.SwerveModuleConfiguration
-
Physical characteristics of the swerve module.
- physicalPropertiesJson - Static variable in class swervelib.parser.SwerveParser
-
Parsed modules/physicalproperties.json
- PhysicalPropertiesJson - Class in swervelib.parser.json
-
SwerveModulePhysicalCharacteristics
parsed data. - PhysicalPropertiesJson() - Constructor for class swervelib.parser.json.PhysicalPropertiesJson
- pid - Variable in class swervelib.motors.SparkFlexSwerve
-
Closed-loop PID controller.
- pid - Variable in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Closed-loop PID controller.
- pid - Variable in class swervelib.motors.SparkMaxSwerve
-
Closed-loop PID controller.
- PIDFConfig - Class in swervelib.parser
-
Hold the PIDF and Integral Zone values for a PID.
- PIDFConfig() - Constructor for class swervelib.parser.PIDFConfig
-
Used when parsing PIDF values from JSON.
- PIDFConfig(double, double) - Constructor for class swervelib.parser.PIDFConfig
-
PIDF Config constructor to contain the values.
- PIDFConfig(double, double, double) - Constructor for class swervelib.parser.PIDFConfig
-
PIDF Config constructor to contain the values.
- PIDFConfig(double, double, double, double) - Constructor for class swervelib.parser.PIDFConfig
-
PIDF Config constructor to contain the values.
- PIDFConfig(double, double, double, double, double) - Constructor for class swervelib.parser.PIDFConfig
-
PIDF Config constructor to contain the values.
- pidfPropertiesJson - Static variable in class swervelib.parser.SwerveParser
-
Parsed modules/pidfproperties.json
- PIDFPropertiesJson - Class in swervelib.parser.json
-
SwerveModule
PID with Feedforward for the drive motor and angle motor. - PIDFPropertiesJson() - Constructor for class swervelib.parser.json.PIDFPropertiesJson
- PIDFRange - Class in swervelib.parser.deserializer
-
Class to hold the minimum and maximum input or output of the PIDF.
- PIDFRange() - Constructor for class swervelib.parser.deserializer.PIDFRange
- Pigeon2Swerve - Class in swervelib.imu
-
SwerveIMU interface for the
Pigeon2
- Pigeon2Swerve(int) - Constructor for class swervelib.imu.Pigeon2Swerve
-
Generate the SwerveIMU for
Pigeon2
. - Pigeon2Swerve(int, String) - Constructor for class swervelib.imu.Pigeon2Swerve
-
Generate the SwerveIMU for
Pigeon2
. - PigeonSwerve - Class in swervelib.imu
-
SwerveIMU interface for the
WPI_PigeonIMU
. - PigeonSwerve(int) - Constructor for class swervelib.imu.PigeonSwerve
-
Generate the SwerveIMU for
WPI_PigeonIMU
. - placeInAppropriate0To360Scope(double, double) - Static method in class swervelib.math.SwerveMath
-
Put an angle within the 360 deg scope of a reference.
- POSE - Enum constant in enum class swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity
-
Info level + field info
- PoseLog(Pose2d) - Static method in class swervelib.math.SwerveMath
-
Logical inverse of the Pose exponential from 254.
- position - Variable in class swervelib.math.Matter
-
Position in meters from robot center in 3d space.
- postTrajectory(Trajectory) - Method in class swervelib.SwerveDrive
-
Post the trajectory to the field
- powerAngleMotorsDutyCycle(SwerveDrive, double) - Static method in class swervelib.SwerveDriveTest
-
Power the angle motors for the swerve drive to a set percentage.
- powerAngleMotorsVoltage(SwerveDrive, double) - Static method in class swervelib.SwerveDriveTest
-
Power the angle motors for the swerve drive to a set voltage.
- powerDriveMotorsDutyCycle(SwerveDrive, double) - Static method in class swervelib.SwerveDriveTest
-
Power the drive motors for the swerve drive to a set duty cycle percentage.
- powerDriveMotorsVoltage(SwerveDrive, double) - Static method in class swervelib.SwerveDriveTest
-
Power the drive motors for the swerve drive to a set voltage.
- pushOffsetsToEncoders() - Method in class swervelib.SwerveDrive
-
Pushes the Absolute Encoder offsets to the Encoder or Motor Controller, depending on type.
- pushOffsetsToEncoders() - Method in class swervelib.SwerveModule
-
Push absolute encoder offset in the memory of the encoder or controller.
- PWMDutyCycleEncoderSwerve - Class in swervelib.encoders
-
DutyCycle encoders such as "US Digital MA3 with PWM Output, the CTRE Mag Encoder, the Rev Hex Encoder, and the AM Mag Encoder." attached via a PWM lane.
- PWMDutyCycleEncoderSwerve(int) - Constructor for class swervelib.encoders.PWMDutyCycleEncoderSwerve
-
Constructor for the PWM duty cycle encoder.
Q
- queueSynchronizeEncoders() - Method in class swervelib.SwerveModule
-
Queue synchronization of the integrated angle encoder with the absolute encoder.
R
- rampRate - Variable in class swervelib.parser.json.PhysicalPropertiesJson
-
The minimum number of seconds to take for the motor to go from 0 to full throttle.
- readingError - Variable in class swervelib.encoders.SwerveAbsoluteEncoder
-
Last angle reading was faulty.
- replaceSwerveModuleFeedforward(SimpleMotorFeedforward) - Method in class swervelib.SwerveDrive
-
Setup the swerve module feedforward.
- resetDriveEncoders() - Method in class swervelib.SwerveDrive
-
Reset the drive encoders on the robot, useful when manually resetting the robot without a reboot, like in autonomous.
- resetOdometry(Pose2d) - Method in class swervelib.SwerveDrive
-
Resets odometry to the given pose.
- restoreInternalOffset() - Method in class swervelib.SwerveDrive
-
Restores Internal YAGSL Encoder offsets and sets the Encoder stored offset back to 0
- restoreInternalOffset() - Method in class swervelib.SwerveModule
-
Restore internal offset in YAGSL and either sets absolute encoder offset to 0 or restores old value.
- robotRotation - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
The robot's current rotation based on odometry or gyro readings
- rotationUnit - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
The units of the module rotations and robot rotation
S
- scaleTranslation(Translation2d, double) - Static method in class swervelib.math.SwerveMath
-
Scale the
Translation2d
Polar coordinate magnitude. - serialCommsIssueWarning - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
NavX serial comm issue.
- set(boolean) - Method in class swervelib.telemetry.Alert
-
Sets whether the alert should currently be displayed.
- set(double) - Method in class swervelib.motors.SparkFlexSwerve
-
Set the percentage output.
- set(double) - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Set the percentage output.
- set(double) - Method in class swervelib.motors.SparkMaxSwerve
-
Set the percentage output.
- set(double) - Method in class swervelib.motors.SwerveMotor
-
Set the percentage output.
- set(double) - Method in class swervelib.motors.TalonFXSwerve
-
Set the percentage output.
- set(double) - Method in class swervelib.motors.TalonSRXSwerve
-
Set the percentage output.
- setAbsoluteEncoder(SwerveAbsoluteEncoder) - Method in class swervelib.motors.SparkFlexSwerve
-
Set the absolute encoder to be a compatible absolute encoder.
- setAbsoluteEncoder(SwerveAbsoluteEncoder) - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Set the absolute encoder to be a compatible absolute encoder.
- setAbsoluteEncoder(SwerveAbsoluteEncoder) - Method in class swervelib.motors.SparkMaxSwerve
-
Set the absolute encoder to be a compatible absolute encoder.
- setAbsoluteEncoder(SwerveAbsoluteEncoder) - Method in class swervelib.motors.SwerveMotor
-
Set the absolute encoder to be a compatible absolute encoder.
- setAbsoluteEncoder(SwerveAbsoluteEncoder) - Method in class swervelib.motors.TalonFXSwerve
-
Set the absolute encoder to be a compatible absolute encoder.
- setAbsoluteEncoder(SwerveAbsoluteEncoder) - Method in class swervelib.motors.TalonSRXSwerve
-
Set the absolute encoder to be a compatible absolute encoder.
- setAbsoluteEncoderOffset(double) - Method in class swervelib.encoders.AnalogAbsoluteEncoderSwerve
-
Cannot Set the offset of an Analog Absolute Encoder.
- setAbsoluteEncoderOffset(double) - Method in class swervelib.encoders.CanAndMagSwerve
-
Cannot set the offset of the CANandMag.
- setAbsoluteEncoderOffset(double) - Method in class swervelib.encoders.CANCoderSwerve
-
Sets the Absolute Encoder Offset within the CANcoder's Memory.
- setAbsoluteEncoderOffset(double) - Method in class swervelib.encoders.PWMDutyCycleEncoderSwerve
- setAbsoluteEncoderOffset(double) - Method in class swervelib.encoders.SparkMaxAnalogEncoderSwerve
-
Sets the Absolute Encoder offset at the Encoder Level.
- setAbsoluteEncoderOffset(double) - Method in class swervelib.encoders.SparkMaxEncoderSwerve
-
Sets the Absolute Encoder Offset inside of the SparkMax's Memory.
- setAbsoluteEncoderOffset(double) - Method in class swervelib.encoders.SwerveAbsoluteEncoder
-
Sets the Absolute Encoder offset at the Encoder Level.
- setAngle(double) - Method in class swervelib.simulation.SwerveIMUSimulation
-
Set the heading of the robot.
- setAngle(double) - Method in class swervelib.SwerveModule
-
Set the angle for the module.
- setAngleMotorConversionFactor(double) - Method in class swervelib.SwerveDrive
-
Set the conversion factor for the angle/azimuth motor controller.
- setAngleMotorConversionFactor(double) - Method in class swervelib.SwerveModule
-
Set the conversion factor for the angle/azimuth motor controller.
- setAngleMotorVoltageCompensation(double) - Method in class swervelib.SwerveModule
-
Set the voltage compensation for the swerve module motor.
- setAnglePIDF(PIDFConfig) - Method in class swervelib.SwerveModule
-
Set the angle/azimuth/steering motor PID
- setAngleSysIdRoutine(SysIdRoutine.Config, SubsystemBase, SwerveDrive) - Static method in class swervelib.SwerveDriveTest
-
Sets up the SysId runner and logger for the angle motors
- setAngularVelocityCompensation(boolean, boolean, double) - Method in class swervelib.SwerveDrive
-
Enables angular velocity skew correction in teleop and/or autonomous and sets the angular velocity coefficient for both modes
- setAntiJitter(boolean) - Method in class swervelib.SwerveModule
-
Set the antiJitter functionality, if true the modules will NOT auto center.
- setAutoCenteringModules(boolean) - Method in class swervelib.SwerveDrive
-
Enable auto-centering module wheels.
- setChassisDiscretization(boolean, boolean, double) - Method in class swervelib.SwerveDrive
-
Sets the Chassis discretization seconds as well as enableing/disabling the Chassis velocity correction in teleop and/or auto
- setChassisDiscretization(boolean, double) - Method in class swervelib.SwerveDrive
-
Sets the Chassis discretization seconds as well as enableing/disabling the Chassis velocity correction in teleop
- setChassisSpeeds(ChassisSpeeds) - Method in class swervelib.SwerveDrive
-
Set chassis speeds with closed-loop velocity control.
- setCosineCompensator(boolean) - Method in class swervelib.SwerveDrive
-
Enable or disable the
SwerveModuleConfiguration.useCosineCompensator
for allSwerveModule
's in the swerve drive. - setCurrentLimit(int) - Method in class swervelib.motors.SparkFlexSwerve
-
Set the current limit for the swerve drive motor, remember this may cause jumping if used in conjunction with voltage compensation.
- setCurrentLimit(int) - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Set the current limit for the swerve drive motor, remember this may cause jumping if used in conjunction with voltage compensation.
- setCurrentLimit(int) - Method in class swervelib.motors.SparkMaxSwerve
-
Set the current limit for the swerve drive motor, remember this may cause jumping if used in conjunction with voltage compensation.
- setCurrentLimit(int) - Method in class swervelib.motors.SwerveMotor
-
Set the current limit for the swerve drive motor, remember this may cause jumping if used in conjunction with voltage compensation.
- setCurrentLimit(int) - Method in class swervelib.motors.TalonFXSwerve
-
Set the current limit for the swerve drive motor, remember this may cause jumping if used in conjunction with voltage compensation.
- setCurrentLimit(int) - Method in class swervelib.motors.TalonSRXSwerve
-
Set the current limit for the swerve drive motor, remember this may cause jumping if used in conjunction with voltage compensation.
- setDesiredState(SwerveModuleState, boolean, boolean) - Method in class swervelib.SwerveModule
-
Set the desired state of the swerve module.
- setDriveMotorConversionFactor(double) - Method in class swervelib.SwerveDrive
-
Set the conversion factor for the drive motor controller.
- setDriveMotorConversionFactor(double) - Method in class swervelib.SwerveModule
-
Set the conversion factor for the drive motor controller.
- setDriveMotorVoltageCompensation(double) - Method in class swervelib.SwerveModule
-
Set the voltage compensation for the swerve module motor.
- setDrivePIDF(PIDFConfig) - Method in class swervelib.SwerveModule
-
Set the drive PIDF values.
- setDriveSysIdRoutine(SysIdRoutine.Config, SubsystemBase, SwerveDrive, double) - Static method in class swervelib.SwerveDriveTest
-
Sets up the SysId runner and logger for the drive motors
- setEncoderAutoSynchronize(boolean) - Method in class swervelib.SwerveModule
-
Enable auto synchronization for encoders during a match.
- setEncoderAutoSynchronize(boolean, double) - Method in class swervelib.SwerveModule
-
Enable auto synchronization for encoders during a match.
- setFeedforward(SimpleMotorFeedforward) - Method in class swervelib.SwerveModule
-
Set the feedforward attributes to the given parameters.
- setGyro(Rotation3d) - Method in class swervelib.SwerveDrive
-
Set the expected gyroscope angle using a
Rotation3d
object. - setGyroOffset(Rotation3d) - Method in class swervelib.SwerveDrive
-
Set the gyro scope offset to a desired known rotation.
- setHeadingCorrection(boolean) - Method in class swervelib.SwerveDrive
-
Set the heading correction capabilities of YAGSL.
- setHeadingCorrection(boolean, double) - Method in class swervelib.SwerveDrive
-
Set the heading correction capabilities of YAGSL.
- setInverted(boolean) - Method in class swervelib.imu.ADIS16448Swerve
-
Set the gyro to invert its default direction
- setInverted(boolean) - Method in class swervelib.imu.ADIS16470Swerve
-
Set the gyro to invert its default direction
- setInverted(boolean) - Method in class swervelib.imu.ADXRS450Swerve
-
Set the gyro to invert its default direction
- setInverted(boolean) - Method in class swervelib.imu.AnalogGyroSwerve
-
Set the gyro to invert its default direction
- setInverted(boolean) - Method in class swervelib.imu.CanandgyroSwerve
-
Set the gyro to invert its default direction
- setInverted(boolean) - Method in class swervelib.imu.NavXSwerve
-
Set the gyro to invert its default direction
- setInverted(boolean) - Method in class swervelib.imu.Pigeon2Swerve
-
Set the gyro to invert its default direction
- setInverted(boolean) - Method in class swervelib.imu.PigeonSwerve
-
Set the gyro to invert its default direction
- setInverted(boolean) - Method in class swervelib.imu.SwerveIMU
-
Set the gyro to invert its default direction.
- setInverted(boolean) - Method in class swervelib.motors.SparkFlexSwerve
-
Set the motor to be inverted.
- setInverted(boolean) - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Set the motor to be inverted.
- setInverted(boolean) - Method in class swervelib.motors.SparkMaxSwerve
-
Set the motor to be inverted.
- setInverted(boolean) - Method in class swervelib.motors.SwerveMotor
-
Set the motor to be inverted.
- setInverted(boolean) - Method in class swervelib.motors.TalonFXSwerve
-
Set the motor to be inverted.
- setInverted(boolean) - Method in class swervelib.motors.TalonSRXSwerve
-
Set the motor to be inverted.
- setLoopRampRate(double) - Method in class swervelib.motors.SparkFlexSwerve
-
Set the maximum rate the open/closed loop output can change by.
- setLoopRampRate(double) - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Set the maximum rate the open/closed loop output can change by.
- setLoopRampRate(double) - Method in class swervelib.motors.SparkMaxSwerve
-
Set the maximum rate the open/closed loop output can change by.
- setLoopRampRate(double) - Method in class swervelib.motors.SwerveMotor
-
Set the maximum rate the open/closed loop output can change by.
- setLoopRampRate(double) - Method in class swervelib.motors.TalonFXSwerve
-
Set the maximum rate the open/closed loop output can change by.
- setLoopRampRate(double) - Method in class swervelib.motors.TalonSRXSwerve
-
Set the maximum rate the open/closed loop output can change by.
- setMaximumAngularVelocity(double) - Method in class swervelib.SwerveController
-
Set a new maximum angular velocity that is different from the auto-generated one.
- setMaximumSpeed(double) - Method in class swervelib.SwerveDrive
-
Set the maximum speed of the drive motors, modified
SwerveDrive.maxSpeedMPS
which is used for theSwerveDrive.setRawModuleStates(SwerveModuleState[], ChassisSpeeds, boolean)
function andSwerveController.getTargetSpeeds(double, double, double, double, double)
functions. - setMaximumSpeed(double, boolean, double) - Method in class swervelib.SwerveDrive
-
Set the maximum speed of the drive motors, modified
SwerveDrive.maxSpeedMPS
which is used for theSwerveDrive.setRawModuleStates(SwerveModuleState[], ChassisSpeeds, boolean)
function andSwerveController.getTargetSpeeds(double, double, double, double, double)
functions. - setMaximumSpeeds(double, double, double) - Method in class swervelib.SwerveDrive
-
Set the maximum speeds for desaturation.
- setModuleEncoderAutoSynchronize(boolean, double) - Method in class swervelib.SwerveDrive
-
Enable auto synchronization for encoders during a match.
- setModuleStates(SwerveModuleState[], boolean) - Method in class swervelib.SwerveDrive
-
Set the module states (azimuth and velocity) directly.
- setMotorBrake(boolean) - Method in class swervelib.motors.SparkFlexSwerve
-
Set the idle mode.
- setMotorBrake(boolean) - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Set the idle mode.
- setMotorBrake(boolean) - Method in class swervelib.motors.SparkMaxSwerve
-
Set the idle mode.
- setMotorBrake(boolean) - Method in class swervelib.motors.SwerveMotor
-
Set the idle mode.
- setMotorBrake(boolean) - Method in class swervelib.motors.TalonFXSwerve
-
Set the idle mode.
- setMotorBrake(boolean) - Method in class swervelib.motors.TalonSRXSwerve
-
Set the idle mode.
- setMotorBrake(boolean) - Method in class swervelib.SwerveModule
-
Set the brake mode.
- setMotorIdleMode(boolean) - Method in class swervelib.SwerveDrive
-
Sets the drive motors to brake/coast mode.
- setOdometryPeriod(double) - Method in class swervelib.SwerveDrive
-
Set the odometry update period in seconds.
- setOffset(Rotation3d) - Method in class swervelib.imu.ADIS16448Swerve
-
Set the gyro offset.
- setOffset(Rotation3d) - Method in class swervelib.imu.ADIS16470Swerve
-
Set the gyro offset.
- setOffset(Rotation3d) - Method in class swervelib.imu.ADXRS450Swerve
-
Set the gyro offset.
- setOffset(Rotation3d) - Method in class swervelib.imu.AnalogGyroSwerve
-
Set the gyro offset.
- setOffset(Rotation3d) - Method in class swervelib.imu.CanandgyroSwerve
-
Set the gyro offset.
- setOffset(Rotation3d) - Method in class swervelib.imu.NavXSwerve
-
Set the gyro offset.
- setOffset(Rotation3d) - Method in class swervelib.imu.Pigeon2Swerve
-
Set the gyro offset.
- setOffset(Rotation3d) - Method in class swervelib.imu.PigeonSwerve
-
Set the gyro offset.
- setOffset(Rotation3d) - Method in class swervelib.imu.SwerveIMU
-
Set the gyro offset.
- setPosition(double) - Method in class swervelib.motors.SparkFlexSwerve
-
Set the integrated encoder position.
- setPosition(double) - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Set the integrated encoder position.
- setPosition(double) - Method in class swervelib.motors.SparkMaxSwerve
-
Set the integrated encoder position.
- setPosition(double) - Method in class swervelib.motors.SwerveMotor
-
Set the integrated encoder position.
- setPosition(double) - Method in class swervelib.motors.TalonFXSwerve
-
Set the integrated encoder position.
- setPosition(double) - Method in class swervelib.motors.TalonSRXSwerve
-
Set the integrated encoder position.
- setReference(double, double) - Method in class swervelib.motors.SparkFlexSwerve
-
Set the closed loop PID controller reference point.
- setReference(double, double) - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Set the closed loop PID controller reference point.
- setReference(double, double) - Method in class swervelib.motors.SparkMaxSwerve
-
Set the closed loop PID controller reference point.
- setReference(double, double) - Method in class swervelib.motors.SwerveMotor
-
Set the closed loop PID controller reference point.
- setReference(double, double) - Method in class swervelib.motors.TalonFXSwerve
-
Set the closed loop PID controller reference point.
- setReference(double, double) - Method in class swervelib.motors.TalonSRXSwerve
-
Set the closed loop PID controller reference point.
- setReference(double, double, double) - Method in class swervelib.motors.SparkFlexSwerve
-
Set the closed loop PID controller reference point.
- setReference(double, double, double) - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Set the closed loop PID controller reference point.
- setReference(double, double, double) - Method in class swervelib.motors.SparkMaxSwerve
-
Set the closed loop PID controller reference point.
- setReference(double, double, double) - Method in class swervelib.motors.SwerveMotor
-
Set the closed loop PID controller reference point.
- setReference(double, double, double) - Method in class swervelib.motors.TalonFXSwerve
-
Set the closed loop PID controller reference point.
- setReference(double, double, double) - Method in class swervelib.motors.TalonSRXSwerve
-
Set the closed loop PID controller reference point.
- setText(String) - Method in class swervelib.telemetry.Alert
-
Updates current alert text.
- setVisionMeasurementStdDevs(Matrix<N3, N1>) - Method in class swervelib.SwerveDrive
-
Sets the pose estimator's trust of global measurements.
- setVoltage(double) - Method in class swervelib.motors.SparkFlexSwerve
-
Set the voltage of the motor.
- setVoltage(double) - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Set the voltage of the motor.
- setVoltage(double) - Method in class swervelib.motors.SparkMaxSwerve
-
Set the voltage of the motor.
- setVoltage(double) - Method in class swervelib.motors.SwerveMotor
-
Set the voltage of the motor.
- setVoltage(double) - Method in class swervelib.motors.TalonFXSwerve
-
Set the voltage of the motor.
- setVoltage(double) - Method in class swervelib.motors.TalonSRXSwerve
-
Set the voltage of the motor.
- setVoltageCompensation(double) - Method in class swervelib.motors.SparkFlexSwerve
-
Set the voltage compensation for the swerve module motor.
- setVoltageCompensation(double) - Method in class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Set the voltage compensation for the swerve module motor.
- setVoltageCompensation(double) - Method in class swervelib.motors.SparkMaxSwerve
-
Set the voltage compensation for the swerve module motor.
- setVoltageCompensation(double) - Method in class swervelib.motors.SwerveMotor
-
Set the voltage compensation for the swerve module motor.
- setVoltageCompensation(double) - Method in class swervelib.motors.TalonFXSwerve
-
Set the voltage compensation for the swerve module motor.
- setVoltageCompensation(double) - Method in class swervelib.motors.TalonSRXSwerve
-
Set the voltage compensation for the swerve module motor.
- sizeFrontBack - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
The distance between the front and back modules.
- sizeLeftRight - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
The distance between the left and right modules.
- SparkFlexSwerve - Class in swervelib.motors
-
An implementation of
CANSparkFlex
as aSwerveMotor
. - SparkFlexSwerve(int, boolean) - Constructor for class swervelib.motors.SparkFlexSwerve
-
Initialize the
SwerveMotor
as aCANSparkMax
connected to a Brushless Motor. - SparkFlexSwerve(CANSparkFlex, boolean) - Constructor for class swervelib.motors.SparkFlexSwerve
-
Initialize the swerve motor.
- SparkMaxAnalogEncoderSwerve - Class in swervelib.encoders
-
SparkMax absolute encoder, attached through the data port analog pin.
- SparkMaxAnalogEncoderSwerve(SwerveMotor, double) - Constructor for class swervelib.encoders.SparkMaxAnalogEncoderSwerve
-
Create the
SparkMaxAnalogEncoderSwerve
object as a analog sensor from theCANSparkMax
motor data port analog pin. - SparkMaxBrushedMotorSwerve - Class in swervelib.motors
-
Brushed motor control with
CANSparkMax
. - SparkMaxBrushedMotorSwerve(int, boolean, SparkRelativeEncoder.Type, int, boolean) - Constructor for class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Initialize the
SwerveMotor
as aCANSparkMax
connected to a Brushless Motor. - SparkMaxBrushedMotorSwerve(CANSparkMax, boolean, SparkRelativeEncoder.Type, int, boolean) - Constructor for class swervelib.motors.SparkMaxBrushedMotorSwerve
-
Initialize the swerve motor.
- SparkMaxEncoderSwerve - Class in swervelib.encoders
-
SparkMax absolute encoder, attached through the data port.
- SparkMaxEncoderSwerve(SwerveMotor, int) - Constructor for class swervelib.encoders.SparkMaxEncoderSwerve
-
Create the
SparkMaxEncoderSwerve
object as a duty cycle from theCANSparkMax
motor. - SparkMaxSwerve - Class in swervelib.motors
-
An implementation of
CANSparkMax
as aSwerveMotor
. - SparkMaxSwerve(int, boolean) - Constructor for class swervelib.motors.SparkMaxSwerve
-
Initialize the
SwerveMotor
as aCANSparkMax
connected to a Brushless Motor. - SparkMaxSwerve(CANSparkMax, boolean) - Constructor for class swervelib.motors.SparkMaxSwerve
-
Initialize the swerve motor.
- STATUS_TIMEOUT_SECONDS - Static variable in class swervelib.encoders.CANCoderSwerve
-
Wait time for status frames to show up.
- STATUS_TIMEOUT_SECONDS - Static variable in class swervelib.imu.CanandgyroSwerve
-
Wait time for status frames to show up.
- STATUS_TIMEOUT_SECONDS - Static variable in class swervelib.imu.Pigeon2Swerve
-
Wait time for status frames to show up.
- STATUS_TIMEOUT_SECONDS - Static variable in class swervelib.motors.TalonFXSwerve
-
Wait time for status frames to show up.
- stopOdometryThread() - Method in class swervelib.SwerveDrive
-
Stop the odometry thread in favor of manually updating odometry.
- SwerveAbsoluteEncoder - Class in swervelib.encoders
-
Swerve abstraction class to define a standard interface with absolute encoders for swerve modules..
- SwerveAbsoluteEncoder() - Constructor for class swervelib.encoders.SwerveAbsoluteEncoder
- swerveController - Variable in class swervelib.SwerveDrive
-
Swerve controller for controlling heading of the robot.
- SwerveController - Class in swervelib
-
Controller class used to convert raw inputs into robot speeds.
- SwerveController(SwerveControllerConfiguration) - Constructor for class swervelib.SwerveController
-
Construct the SwerveController object which is used for determining the speeds of the robot based on controller input.
- SwerveControllerConfiguration - Class in swervelib.parser
-
Swerve Controller configuration class which is used to configure
SwerveController
. - SwerveControllerConfiguration(SwerveDriveConfiguration, PIDFConfig, double) - Constructor for class swervelib.parser.SwerveControllerConfiguration
-
Construct the swerve controller configuration.
- SwerveControllerConfiguration(SwerveDriveConfiguration, PIDFConfig, double, double) - Constructor for class swervelib.parser.SwerveControllerConfiguration
-
Construct the swerve controller configuration.
- SwerveDrive - Class in swervelib
-
Swerve Drive class representing and controlling the swerve drive.
- SwerveDrive(SwerveDriveConfiguration, SwerveControllerConfiguration, double) - Constructor for class swervelib.SwerveDrive
-
Creates a new swerve drivebase subsystem.
- swerveDriveConfiguration - Variable in class swervelib.SwerveDrive
-
Swerve drive configuration.
- SwerveDriveConfiguration - Class in swervelib.parser
-
Swerve drive configurations used during SwerveDrive construction.
- SwerveDriveConfiguration(SwerveModuleConfiguration[], SwerveIMU, boolean, SimpleMotorFeedforward, SwerveModulePhysicalCharacteristics) - Constructor for class swervelib.parser.SwerveDriveConfiguration
-
Create swerve drive configuration.
- swerveDriveJson - Static variable in class swervelib.parser.SwerveParser
-
Parsed swervedrive.json
- SwerveDriveJson - Class in swervelib.parser.json
-
SwerveDrive
JSON parsed class. - SwerveDriveJson() - Constructor for class swervelib.parser.json.SwerveDriveJson
- swerveDrivePoseEstimator - Variable in class swervelib.SwerveDrive
-
Swerve odometry.
- SwerveDriveTelemetry - Class in swervelib.telemetry
-
Telemetry to describe the
SwerveDrive
following frc-web-components. - SwerveDriveTelemetry() - Constructor for class swervelib.telemetry.SwerveDriveTelemetry
- SwerveDriveTelemetry.TelemetryVerbosity - Enum Class in swervelib.telemetry
-
Verbosity of telemetry data sent back.
- SwerveDriveTest - Class in swervelib
-
Class to perform tests on the swerve drive.
- SwerveDriveTest() - Constructor for class swervelib.SwerveDriveTest
- SwerveIMU - Class in swervelib.imu
-
Swerve IMU abstraction to define a standard interface with a swerve drive.
- SwerveIMU() - Constructor for class swervelib.imu.SwerveIMU
- SwerveIMUSimulation - Class in swervelib.simulation
-
Simulation for
SwerveDrive
IMU. - SwerveIMUSimulation() - Constructor for class swervelib.simulation.SwerveIMUSimulation
-
Create the swerve drive IMU simulation.
- swervelib - package swervelib
-
Yet-Another Generic Swerve Library (YAGSL) main package AKA swervelib.
- swervelib.encoders - package swervelib.encoders
-
Absolute encoders for the swerve drive, all implement
SwerveAbsoluteEncoder
. - swervelib.imu - package swervelib.imu
-
IMUs used for controlling the robot heading.
- swervelib.math - package swervelib.math
-
Mathematics for swerve drives.
- swervelib.motors - package swervelib.motors
-
Swerve motor controller wrappers which implement
SwerveMotor
. - swervelib.parser - package swervelib.parser
-
JSON Parser for YAGSL configurations.
- swervelib.parser.deserializer - package swervelib.parser.deserializer
-
Deserialize specific variables for outside the parser.
- swervelib.parser.json - package swervelib.parser.json
-
JSON Mapped classes for parsing configuration files.
- swervelib.parser.json.modules - package swervelib.parser.json.modules
-
JSON Mapped Configuration types for modules.
- swervelib.simulation - package swervelib.simulation
-
Classes used to simulate the swerve drive.
- swervelib.telemetry - package swervelib.telemetry
-
Telemetry package for sending data to NT4 or SmartDashboard.
- SwerveMath - Class in swervelib.math
-
Mathematical functions which pertain to swerve drive.
- SwerveMath() - Constructor for class swervelib.math.SwerveMath
- SwerveModule - Class in swervelib
-
The Swerve Module class which represents and controls Swerve Modules for the swerve drive.
- SwerveModule(int, SwerveModuleConfiguration, SimpleMotorFeedforward) - Constructor for class swervelib.SwerveModule
-
Construct the swerve module and initialize the swerve module motors and absolute encoder.
- SwerveModuleConfiguration - Class in swervelib.parser
-
Swerve Module configuration class which is used to configure
SwerveModule
. - SwerveModuleConfiguration(SwerveMotor, SwerveMotor, MotorConfigDouble, SwerveAbsoluteEncoder, double, double, double, PIDFConfig, PIDFConfig, SwerveModulePhysicalCharacteristics, boolean, boolean, boolean, String, boolean) - Constructor for class swervelib.parser.SwerveModuleConfiguration
-
Construct a configuration object for swerve modules.
- SwerveModuleConfiguration(SwerveMotor, SwerveMotor, MotorConfigDouble, SwerveAbsoluteEncoder, double, double, double, PIDFConfig, PIDFConfig, SwerveModulePhysicalCharacteristics, String, boolean) - Constructor for class swervelib.parser.SwerveModuleConfiguration
-
Construct a configuration object for swerve modules.
- SwerveModulePhysicalCharacteristics - Class in swervelib.parser
-
Configuration class which stores physical characteristics shared between every swerve module.
- SwerveModulePhysicalCharacteristics(MotorConfigDouble, double, double) - Constructor for class swervelib.parser.SwerveModulePhysicalCharacteristics
-
Construct the swerve module physical characteristics.
- SwerveModulePhysicalCharacteristics(MotorConfigDouble, double, double, int, int, double, double) - Constructor for class swervelib.parser.SwerveModulePhysicalCharacteristics
-
Construct the swerve module physical characteristics.
- SwerveModuleSimulation - Class in swervelib.simulation
-
Class to hold simulation data for
SwerveModule
- SwerveModuleSimulation() - Constructor for class swervelib.simulation.SwerveModuleSimulation
-
Create simulation class and initialize module at 0.
- SwerveMotor - Class in swervelib.motors
-
Swerve motor abstraction which defines a standard interface for motors within a swerve module.
- SwerveMotor() - Constructor for class swervelib.motors.SwerveMotor
- SwerveParser - Class in swervelib.parser
-
Helper class used to parse the JSON directory with specified configuration options.
- SwerveParser(File) - Constructor for class swervelib.parser.SwerveParser
-
Construct a swerve parser.
- synchronizeModuleEncoders() - Method in class swervelib.SwerveDrive
-
Synchronize angle motor integrated encoders with data from absolute encoders.
T
- TalonFXSwerve - Class in swervelib.motors
-
TalonFX
Swerve Motor. - TalonFXSwerve(int, boolean) - Constructor for class swervelib.motors.TalonFXSwerve
-
Construct the TalonFX swerve motor given the ID.
- TalonFXSwerve(int, String, boolean) - Constructor for class swervelib.motors.TalonFXSwerve
-
Construct the TalonFX swerve motor given the ID and CANBus.
- TalonFXSwerve(TalonFX, boolean) - Constructor for class swervelib.motors.TalonFXSwerve
-
Constructor for TalonFX swerve motor.
- TalonSRXSwerve - Class in swervelib.motors
-
WPI_TalonSRX
Swerve Motor. - TalonSRXSwerve(int, boolean) - Constructor for class swervelib.motors.TalonSRXSwerve
-
Construct the TalonSRX swerve motor given the ID.
- TalonSRXSwerve(WPI_TalonSRX, boolean) - Constructor for class swervelib.motors.TalonSRXSwerve
-
Constructor for TalonSRX swerve motor.
- thetaController - Variable in class swervelib.SwerveController
-
PID Controller for the robot heading.
- type - Variable in class swervelib.parser.json.DeviceJson
-
The device type, e.g.
U
- update() - Method in class swervelib.parser.Cache
-
Update the cache value and timestamp.
- updateCacheValidityPeriods(long, long, long) - Method in class swervelib.SwerveDrive
-
Update the cache validity period for the robot.
- updateData() - Static method in class swervelib.telemetry.SwerveDriveTelemetry
-
Upload data to smartdashboard
- updateOdometry() - Method in class swervelib.SwerveDrive
-
Update odometry should be run every loop.
- updateOdometry(SwerveDriveKinematics, SwerveModuleState[], Pose2d[], Field2d) - Method in class swervelib.simulation.SwerveIMUSimulation
- updateStateAndPosition(SwerveModuleState) - Method in class swervelib.simulation.SwerveModuleSimulation
-
Update the position and state of the module.
- updateSupplier(Supplier<T>) - Method in class swervelib.parser.Cache
-
Update the supplier to a new source.
- updateTelemetry() - Method in class swervelib.SwerveModule
-
Update data sent to
SmartDashboard
. - updateValidityPeriod(long) - Method in class swervelib.parser.Cache
-
Update the validity period for the cached value, also updates the value.
- useCosineCompensator - Variable in class swervelib.parser.json.ModuleJson
-
Should do cosine compensation when not pointing correct direction;.
- useCosineCompensator - Variable in class swervelib.parser.SwerveModuleConfiguration
-
Should do cosine compensation when not pointing correct direction;.
V
- valueOf(String) - Static method in enum class swervelib.telemetry.Alert.AlertType
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity
-
Returns the enum constant of this class with the specified name.
- values() - Static method in enum class swervelib.telemetry.Alert.AlertType
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity
-
Returns an array containing the constants of this enum class, in the order they are declared.
- velocityPIDF - Variable in class swervelib.parser.SwerveModuleConfiguration
-
PIDF configuration options for the drive motor closed-loop PID controller.
- verbosity - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
The current telemetry verbosity level.
W
- WARNING - Enum constant in enum class swervelib.telemetry.Alert.AlertType
-
Medium priority alert - displayed second on the dashboard with a yellow "!" symbol.
- WARNING_TRACE - Enum constant in enum class swervelib.telemetry.Alert.AlertType
-
Medium priority alert - displayed second on the dashboard with a yellow "!" symbol.
- wheelGripCoefficientOfFriction - Variable in class swervelib.parser.json.PhysicalPropertiesJson
-
The grip tape coefficient of friction on carpet.
- wheelGripCoefficientOfFriction - Variable in class swervelib.parser.SwerveModulePhysicalCharacteristics
-
Wheel grip tape coefficient of friction on carpet, as described by the vendor.
- wheelLocations - Static variable in class swervelib.telemetry.SwerveDriveTelemetry
-
The Locations of the swerve drive wheels.
- withinHypotDeadband(double, double) - Method in class swervelib.SwerveController
-
Calculate the hypot deadband and check if the joystick is within it.
X
- x - Variable in class swervelib.parser.json.modules.LocationJson
-
Location of the swerve module in inches from the center of the robot horizontally.
- xLimiter - Variable in class swervelib.SwerveController
-
SlewRateLimiter
for movement in the X direction in meters/second.
Y
- y - Variable in class swervelib.parser.json.modules.LocationJson
-
Location of the swerve module in inches from the center of the robot vertically.
- yLimiter - Variable in class swervelib.SwerveController
-
SlewRateLimiter
for movement in the Y direction in meters/second.
Z
- zeroGyro() - Method in class swervelib.SwerveDrive
-
Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0.
All Classes and Interfaces|All Packages|Constant Field Values