A B C D E F G H I J K L M N O P R S T U V W X Y Z 
All Classes All Packages

A

AbstractDriveTrain - Class in io.github.frc5024.lib5k.bases.drivetrain
 
AbstractDriveTrain() - Constructor for class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
Create an AbstractDriveTrain
AbstractDriveTrain.State - Enum in io.github.frc5024.lib5k.bases.drivetrain
 
acceleration - Variable in class io.github.frc5024.purepursuit.util.WPI_PathPoint
 
addAutonomous(AutonomousSequence) - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
Add a new autonomous sequence
addCurrentLimit(CurrentLimit) - Static method in class io.github.frc5024.lib5k.hardware.common.pdp.CurrentLimitManager
 
addSeries(String, List<Double>, List<Double>) - Method in class io.github.frc5024.lib5k.unittest.Grapher
Add an X/Y series to the graph
addState(T, Consumer<StateMetadata<T>>) - Method in class io.github.frc5024.libkontrol.statemachines.StateMachine
Add a state to the StateMachine
ADGyro - Class in io.github.frc5024.lib5k.hardware.generic.gyroscopes
A wrapper around the Analog Devices ADXRS450.
ADGyro() - Constructor for class io.github.frc5024.lib5k.hardware.generic.gyroscopes.ADGyro
Connect to a gyro on the onboard SPI port
allStates - Variable in class io.github.frc5024.libkontrol.statemachines.StateMachine
 
angle - Variable in class io.github.frc5024.common_drive.queue.DriveTrainSensors
Deprecated.
 
angularRate - Variable in class io.github.frc5024.common_drive.queue.DriveTrainSensors
Deprecated.
 
AQUA - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
arcade(double, double) - Static method in class io.github.frc5024.common_drive.calculation.DifferentialDriveCalculation
Deprecated.
Calculate a percent motor output from speed and rotation inputs using "arcade calculation"
ArmMath - Class in io.github.frc5024.lib5k.control_loops.statespace.util.easylqr
This class contains utils for calculating parameters of arms
ArmMath() - Constructor for class io.github.frc5024.lib5k.control_loops.statespace.util.easylqr.ArmMath
 
AsyncADXRS450_Gyro - Class in io.github.frc5024.asynchal.sensors
 
AsyncADXRS450_Gyro() - Constructor for class io.github.frc5024.asynchal.sensors.AsyncADXRS450_Gyro
Default-construct an AsyncADXRS450_Gyro connected to the onboard SPI port
AsyncDigitalInput - Class in io.github.frc5024.asynchal.sensors
An asynchronous wrapper for DigitalInput
AsyncDigitalInput(int) - Constructor for class io.github.frc5024.asynchal.sensors.AsyncDigitalInput
Create an instance of a Digital Input class.
atReference() - Method in interface io.github.frc5024.lib5k.control_loops.base.Controller
Check if the system is at its reference
atReference() - Method in class io.github.frc5024.lib5k.control_loops.ExtendedPIDController
 
atReference() - Method in class io.github.frc5024.lib5k.control_loops.TBHController
 
atSetpoint() - Method in class io.github.frc5024.lib5k.control_loops.ExtendedPIDController
 
AutoCamera - Class in io.github.frc5024.lib5k.hardware.generic.cameras
Automatic camera streaming.
AutoCamera() - Constructor for class io.github.frc5024.lib5k.hardware.generic.cameras.AutoCamera
Create a dynamic auto camera
AutoCamera(int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.cameras.AutoCamera
Connect to a camera in a specific USB slot
AutoCamera(String, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.cameras.AutoCamera
Connect to a camera in a specific USB slot
autoConfig(double, double) - Static method in class io.github.frc5024.lib5k.control_loops.models.PIDProfile
Deprecated.
Generate a PIDProfile using the Zeigler-Nichols tuning method.
autonomous(boolean) - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
This is run during autonomous
autonomousInit() - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
 
autonomousPeriodic() - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
 
AutonomousSequence - Interface in io.github.frc5024.lib5k.autonomous
A wrapper for everything needed in an autonomous sequence
AxisAlignedBoundingBox - Class in io.github.frc5024.lib5k.vision.types
A computer-vision axis-aligned bounding box.
AxisAlignedBoundingBox(Translation2d, Translation2d) - Constructor for class io.github.frc5024.lib5k.vision.types.AxisAlignedBoundingBox
Create an AxisAlignedBoundingBox from opposing corners
AxisAlignedBoundingBox(Translation2d, Translation2d, Rotation2d, Rotation2d) - Constructor for class io.github.frc5024.lib5k.vision.types.AxisAlignedBoundingBox
Create an AxisAlignedBoundingBox from opposing corners, with angles relative to a camera

B

BaseController - Interface in io.github.frc5024.common_drive.controller
Deprecated, for removal: This API element is subject to removal in a future version.
BaseLimeLight - Class in io.github.frc5024.lib5k.hardware.limelightvision
The base for interaction with LimeLight products.
BaseLimeLight(NetworkTable, String, double, double) - Constructor for class io.github.frc5024.lib5k.hardware.limelightvision.BaseLimeLight
Create a BaseLimeLight
becomeNeutral() - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
This puts the drivetrain in "neutral mode".
beginTimingGeneration() - Method in class io.github.frc5024.purepursuit.pathgen.Path
Begins an internal timer for profiling path gen time
BezierPath - Class in io.github.frc5024.purepursuit.pathgen
This class is used to generate points along a bezier curves
BezierPath(Translation2d[]) - Constructor for class io.github.frc5024.purepursuit.pathgen.BezierPath
 
BezierPath(Translation2d[], double[]) - Constructor for class io.github.frc5024.purepursuit.pathgen.BezierPath
 
BezierPath(Translation2d[], double[], double) - Constructor for class io.github.frc5024.purepursuit.pathgen.BezierPath
 
BLACK - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
BLINK - io.github.frc5024.lib5k.hardware.generic.cameras.USBVisionCamera.LEDMode
 
BLINK - io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightLEDMode
 
BlinkinDriver - Class in io.github.frc5024.lib5k.hardware.generic.ledstrips
A wrapper for the REV Blinkin LED driver
http://www.revrobotics.com/rev-11-1105/
BlinkinDriver(int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver
A wrapper for the REV Blinkin LED driver
BlinkinDriver.LEDSetting - Enum in io.github.frc5024.lib5k.hardware.generic.ledstrips
 
BLUE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
BLUE_GREEN - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
BLUE_SHOT - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
BLUE_VIOLET - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
BPM_1_AND_2 - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
BPM_FOREST - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
BPM_LAVA - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
BPM_OCEAN - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
BPM_RAINBOW - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
BREATH_BLUE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
BREATH_GRAY - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
BREATH_RED - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 

C

ca.retrylife.frc.templates.arms - package ca.retrylife.frc.templates.arms
 
ca.retrylife.frc.templates.turrets - package ca.retrylife.frc.templates.turrets
 
calculate() - Method in class io.github.frc5024.lib5k.utils.TimeScale
Calculate a scaling factor since the last time this function was called
calculate(double) - Method in interface io.github.frc5024.lib5k.control_loops.base.Controller
Calculate the next output
calculate(double) - Method in class io.github.frc5024.lib5k.control_loops.base.ControllerBase
Deprecated.
Internal controller calculation
calculate(double) - Method in class io.github.frc5024.lib5k.control_loops.ExtendedPIDController
 
calculate(double) - Method in class io.github.frc5024.lib5k.control_loops.JRADController
Calculate a system output voltage
calculate(double) - Method in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Calculate a system output with a custom error value
calculate(double) - Method in class io.github.frc5024.lib5k.control_loops.TBHController
 
calculate(double, double) - Method in interface io.github.frc5024.common_drive.controller.BaseController
Deprecated.
Calculate a new controller output
calculate(double, double) - Method in class io.github.frc5024.common_drive.controller.PDFController
Deprecated.
Calculate the controller output with FeedForward
calculate(double, double) - Method in class io.github.frc5024.common_drive.controller.PIFController
Deprecated.
Calculate the controller output with FeedForward
calculate(double, double) - Method in interface io.github.frc5024.lib5k.control_loops.base.Controller
Calculate the next output
calculate(double, double) - Method in class io.github.frc5024.lib5k.control_loops.TBHController
 
calculate(double, double, boolean) - Method in class io.github.frc5024.common_drive.controller.PDFController
Deprecated.
Calculate the controller output
calculate(double, double, boolean) - Method in class io.github.frc5024.common_drive.controller.PIFController
Deprecated.
Calculate the controller output
calculateHolonomic(Pose2d) - Method in class io.github.frc5024.purepursuit.PurePursuitController
Calculate outputs for a holonomic drivebase
calculateJ(double, double, double, double) - Static method in class io.github.frc5024.lib5k.control_loops.statespace.util.easylqr.FlywheelMath
Calculate the Moment of Inertia (J) for a flywheel with given parameters.
calculateSJIJ(double, double) - Static method in class io.github.frc5024.lib5k.control_loops.statespace.util.easylqr.ArmMath
Calculate the Moment of Inertia (J) for a single jointed arm with given parameters.
calculateTank(Pose2d) - Method in class io.github.frc5024.purepursuit.PurePursuitController
Calculate ou tputs for a tank drivebase
calculateThrottleCorrectionFactor(Rotation2d) - Static method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
Calculates a corrective factor for throttle values, as per: https://bitbucket.org/kaleb_dodd/simbot2019public/src/abc56f5220b5c94bca216f86e3b6b5757d0ffeff/src/main/java/frc/subsystems/Drive.java#lines-337
calibrate() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.GyroSimUtil
Calibrate the sensor (this resets everything)
calibrate() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedPigeonIMU
 
calibrate() - Method in class io.github.frc5024.lib5k.hardware.generic.gyroscopes.ADGyro
 
calibrate() - Method in class io.github.frc5024.lib5k.hardware.kauai.gyroscopes.NavX
 
call(boolean, T) - Method in class io.github.frc5024.libkontrol.statemachines.StateHandler
Call the action function
CANIfierEncoder - Class in io.github.frc5024.lib5k.hardware.ctre.sensors
A wrapper around the CTRE CANIfier's encoder interface that integrates with 5024's encoder system
CANIfierEncoder(int, int) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.sensors.CANIfierEncoder
Constructor.
CARRIAGE_MASS_KG - Static variable in class io.github.frc5024.lib5k.utils.RobotPresets.Imaginary.ElevatorPreset
 
CARRIAGE_MAX_ACCELERATION - Static variable in class io.github.frc5024.lib5k.utils.RobotPresets.Imaginary.ElevatorPreset
 
CARRIAGE_MAX_VELOCITY - Static variable in class io.github.frc5024.lib5k.utils.RobotPresets.Imaginary.ElevatorPreset
 
CHASE_BLUE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
CHASE_GRAY - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
CHASE_RED - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
Chassis - Class in io.github.frc5024.lib5k.bases.drivetrain
Utils relating to a chassis
Chassis() - Constructor for class io.github.frc5024.lib5k.bases.drivetrain.Chassis
 
Chassis.Side - Enum in io.github.frc5024.lib5k.bases.drivetrain
Side face of the chassis
ChassisSide - Enum in io.github.frc5024.common_drive.types
Deprecated, for removal: This API element is subject to removal in a future version.
checkForUpdates() - Method in interface io.github.frc5024.asynchal.Pollable
Check for, and handle any updates since the last call.
checkForUpdates() - Method in class io.github.frc5024.asynchal.sensors.AsyncADXRS450_Gyro
 
checkForUpdates() - Method in class io.github.frc5024.asynchal.sensors.AsyncDigitalInput
 
clearAllFaults() - Method in class io.github.frc5024.lib5k.hardware.generic.motors.LinearActuator
Clear all PCM faults for the attached PCM
close() - Method in class io.github.frc5024.asynchal.sensors.AsyncADXRS450_Gyro
 
close() - Method in class io.github.frc5024.asynchal.sensors.AsyncDigitalInput
 
close() - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
 
close() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.EncoderSimUtil
 
close() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.GyroSimUtil
 
close() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.CANIfierEncoder
 
close() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedCANCoder
 
close() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedPigeonIMU
 
close() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.TalonEncoder
 
close() - Method in class io.github.frc5024.lib5k.hardware.generic.gyroscopes.ADGyro
 
close() - Method in class io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver
 
close() - Method in class io.github.frc5024.lib5k.hardware.generic.motors.LinearActuator
 
close() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.LineBreak
 
close() - Method in class io.github.frc5024.lib5k.hardware.kauai.gyroscopes.NavX
 
close() - Method in class io.github.frc5024.lib5k.hardware.revrobotics.sensors.SparkMaxEncoder
 
close() - Method in class io.github.frc5024.lib5k.logging.CSVFile
Close the file
close() - Method in class io.github.frc5024.lib5k.logging.USBLogger
 
COLOR_1_AND_2_NO_BLEND - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR1_BLEND_TO_BLACK - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR1_BREATH_FAST - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR1_BREATH_SLOW - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR1_CHASE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR1_HEARTBEAT_FAST - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR1_HEARTBEAT_MEDIUM - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR1_HEARTBEAT_SLOW - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR1_LARSON - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR1_SHOT - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR1_STROBE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR2_BLEND_TO_BLACK - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR2_BREATH_FAST - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR2_BREATH_SLOW - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR2_CHASE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR2_HEARTBEAT_FAST - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR2_HEARTBEAT_MEDIUM - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR2_HEARTBEAT_SLOW - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR2_LARSON - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR2_SHOT - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
COLOR2_STROBE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
ColorUtils - Class in io.github.frc5024.lib5k.utils
 
ColorUtils() - Constructor for class io.github.frc5024.lib5k.utils.ColorUtils
 
CommonEncoder - Interface in io.github.frc5024.lib5k.hardware.common.sensors.interfaces
The CommonEncoder interface is designed to provide a unified interface between the 3 encoder sources (ctre, wpi, revrobotics).
ComponentTelemetry - Class in io.github.frc5024.lib5k.telemetry
 
computeArcadeOutputs(double, double) - Static method in class io.github.frc5024.lib5k.math.DifferentialDriveMath
Compute tank voltages for arcade output
computeConstantCurvatureOutputs(double, double) - Static method in class io.github.frc5024.lib5k.math.DifferentialDriveMath
Compute tank voltages for constant curvature output
computeNextVoltage(double) - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SimpleFlywheelController
Compute the voltage to send to the motor
computeNextVoltage(double, double) - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SimpleFlywheelController
Compute the voltage to send to the motor
computeSemiConstantCurvatureOutputs(double, double) - Static method in class io.github.frc5024.lib5k.math.DifferentialDriveMath
Compute tank voltages for semi-constant curvature output
computeVoltage(double) - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.EncoderElevatorController
Calculate the controller output
computeVoltage(double) - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.RangeFinderElevatorController
Calculate the controller output
computeVoltage(double) - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SingleJointedArmController
Compute the next output voltage
computeVoltage(double, double) - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.EncoderElevatorController
Calculate the controller output
CONFETTI - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
config - Variable in class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedTalonFX
 
config - Variable in class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedTalonSRX
 
config - Variable in class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedVictorSPX
 
config - Variable in class io.github.frc5024.lib5k.hardware.revrobotics.motors.ExtendedSparkMax
 
config(double, double, double) - Method in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Configure the PID controller with new gains
config(PIDProfile) - Method in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Configure the PID controller with a new PIDProfile
configCurrentLimit(WPI_TalonSRX, int, int, int, int) - Static method in class io.github.frc5024.lib5k.hardware.ctre.util.TalonHelper
Configure a WPI_TalonSRX current limiting
configFactoryDefault - Variable in class io.github.frc5024.lib5k.hardware.ctre.motors.CTREConfig
 
configLookahead(double) - Method in class io.github.frc5024.purepursuit.PurePursuitController
Set the lookahead distance
configLookahead(double, double) - Method in class io.github.frc5024.purepursuit.PurePursuitController
Set the lookahead distance and gain
ConfigValidator - Class in io.github.frc5024.lib5k.unittest
A tool for validating JSON configs
ConfigValidator(SingleInstanceJSONConfig) - Constructor for class io.github.frc5024.lib5k.unittest.ConfigValidator
Create a JSON config validator
constructDeployPath(String) - Static method in class io.github.frc5024.lib5k.utils.FileUtils
Append a filename to the deploy path
Consts - Class in io.github.frc5024.lib5k.utils
 
Consts() - Constructor for class io.github.frc5024.lib5k.utils.Consts
 
consume() - Method in class io.github.frc5024.common_drive.queue.WriteLock
Get the value, and set write to false
consumeOutputs(DriveTrainOutput) - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Handle all outputs
User must override this.
contains(Translation2d) - Method in class io.github.frc5024.lib5k.vision.types.AxisAlignedBoundingBox
 
contains(Translation2d) - Method in class io.github.frc5024.lib5k.vision.types.Contour
Check if this contour contains a point
Contour - Class in io.github.frc5024.lib5k.vision.types
Contour is the base class for any type of computer-vision Contour
Contour() - Constructor for class io.github.frc5024.lib5k.vision.types.Contour
Create a Contour at 0,0
Contour(double, double) - Constructor for class io.github.frc5024.lib5k.vision.types.Contour
Create a contour with a position
Contour(double, double, Rotation2d, Rotation2d) - Constructor for class io.github.frc5024.lib5k.vision.types.Contour
Create a contour with a position and rotation from the camera
Controller - Interface in io.github.frc5024.lib5k.control_loops.base
The base class for all controllers
ControllerBase - Class in io.github.frc5024.lib5k.control_loops.base
Deprecated, for removal: This API element is subject to removal in a future version.
ControllerBase() - Constructor for class io.github.frc5024.lib5k.control_loops.base.ControllerBase
Deprecated.
 
convert(double, double, double) - Static method in class io.github.frc5024.lib5k.utils.Measurement
Converts a measurement into specified units
copy() - Method in class io.github.frc5024.common_drive.queue.DriveTrainSensors
Deprecated.
Create a copy of this object
cpr - Variable in class io.github.frc5024.lib5k.config.types.JSONEncoder
 
createFileReader(String) - Static method in class io.github.frc5024.lib5k.utils.FileManagement
Create a FileReader for a file inside the current session
createFileWriter(String) - Static method in class io.github.frc5024.lib5k.utils.FileManagement
Create a FileWriter for a file inside the current session
createPathingCommand(Path, boolean, double, double) - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
createPathingCommand(Path, double) - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Create and configure a command that will follow a path using this drivetrain.
createPathingCommand(Path, double) - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
Create and configure a command that will follow a path using this drivetrain.
createSparkMax(int, CANSparkMaxLowLevel.MotorType) - Static method in class io.github.frc5024.lib5k.hardware.revrobotics.motors.RevMotorFactory
Creates a new Spark Max
createSparkMax(int, RevConfig) - Static method in class io.github.frc5024.lib5k.hardware.revrobotics.motors.RevMotorFactory
Creates a new Spark Max
createTalonFX(int) - Static method in class io.github.frc5024.lib5k.hardware.ctre.motors.CTREMotorFactory
Creates a TalonFX
createTalonFX(int, CTREConfig) - Static method in class io.github.frc5024.lib5k.hardware.ctre.motors.CTREMotorFactory
Creates a TalonFX
createTalonSRX(int) - Static method in class io.github.frc5024.lib5k.hardware.ctre.motors.CTREMotorFactory
Creates a Default TalonSRX Motor
createTalonSRX(int, CTREConfig) - Static method in class io.github.frc5024.lib5k.hardware.ctre.motors.CTREMotorFactory
Creates a Talon SRX
createTurnCommand(Rotation2d, Rotation2d, double, boolean) - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
Create a new TurnToCommand for this drivetrain.
createVictorSPX(int) - Static method in class io.github.frc5024.lib5k.hardware.ctre.motors.CTREMotorFactory
Returns a VictorSPX motor
createVictorSPX(int, CTREConfig) - Static method in class io.github.frc5024.lib5k.hardware.ctre.motors.CTREMotorFactory
Creates a VictorSPX
CSVFile - Class in io.github.frc5024.lib5k.logging
CSVFile is a class designed for one-time use.
CSVFile(String, boolean, String...) - Constructor for class io.github.frc5024.lib5k.logging.CSVFile
Create a new CSVFile
CSVFile(String, String...) - Constructor for class io.github.frc5024.lib5k.logging.CSVFile
Create a new CSVFile
CTREConfig - Class in io.github.frc5024.lib5k.hardware.ctre.motors
A config class for Talons
CTREConfig() - Constructor for class io.github.frc5024.lib5k.hardware.ctre.motors.CTREConfig
Default Config Constructor
CTREConfig(boolean) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.motors.CTREConfig
Config Constructor for changing motor inversion
CTREConfig(boolean, boolean, boolean, int, int, int, int, boolean) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.motors.CTREConfig
Creates a custom config
CTREConfig(boolean, int, int, int, int, boolean) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.motors.CTREConfig
Config Constructor for Configuring Current Limits
CTREMotorFactory - Class in io.github.frc5024.lib5k.hardware.ctre.motors
A Class for making talons
CUBIC - io.github.frc5024.lib5k.utils.InputUtils.ScalingMode
 
CurrentLimit - Class in io.github.frc5024.lib5k.hardware.common.pdp
 
CurrentLimit(int, double, double, int, Consumer<Double>) - Constructor for class io.github.frc5024.lib5k.hardware.common.pdp.CurrentLimit
Creates a new current limit
CurrentLimitManager - Class in io.github.frc5024.lib5k.hardware.common.pdp
A class for running current limits
CurrentLimitManager(PowerDistributionPanel) - Constructor for class io.github.frc5024.lib5k.hardware.common.pdp.CurrentLimitManager
 
curvature - Variable in class io.github.frc5024.purepursuit.util.WPI_PathPoint
 
customPeriodic() - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Override this with your custom periodic code

D

DARK_BLUE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
DARK_GRAY - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
DARK_GREEN - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
DARK_RED - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
DarthRaider() - Constructor for class io.github.frc5024.lib5k.utils.RobotPresets.DarthRaider
 
DCBrushedMotor - Class in io.github.frc5024.lib5k.control_loops.models
DC Brushed motor constants.
DCBrushedMotor(DCMotor) - Constructor for class io.github.frc5024.lib5k.control_loops.models.DCBrushedMotor
Create a DCBrushedMotor from a DCMotor
deadzone - Variable in class ca.retrylife.frc.templates.turrets.TurretBase
 
debug - Variable in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
 
DEFAULT - io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightLEDMode
 
defaultHighGear - Variable in class io.github.frc5024.common_drive.DriveTrainConfig
Deprecated.
 
defaultRampSeconds - Variable in class io.github.frc5024.common_drive.DriveTrainConfig
Deprecated.
 
defaultStateKey - Variable in class io.github.frc5024.libkontrol.statemachines.StateMachine
 
deregister(Pollable) - Method in class io.github.frc5024.asynchal.Poller
de-Register a pollable component
desiredStateKey - Variable in class io.github.frc5024.libkontrol.statemachines.StateMachine
 
DifferentialDriveCalculation - Class in io.github.frc5024.common_drive.calculation
Deprecated, for removal: This API element is subject to removal in a future version.
DifferentialDriveCalculation() - Constructor for class io.github.frc5024.common_drive.calculation.DifferentialDriveCalculation
Deprecated.
 
DifferentialDriveMath - Class in io.github.frc5024.lib5k.math
Utils for working with tank drives
DifferentialDriveMath() - Constructor for class io.github.frc5024.lib5k.math.DifferentialDriveMath
 
DifferentialVoltages - Class in io.github.frc5024.lib5k.utils.types
Reperesents two differential voltages named left, and right.
DifferentialVoltages() - Constructor for class io.github.frc5024.lib5k.utils.types.DifferentialVoltages
Create new DifferentialVoltages with no voltage
DifferentialVoltages(double) - Constructor for class io.github.frc5024.lib5k.utils.types.DifferentialVoltages
Create new DifferentialVoltages
DifferentialVoltages(double, double) - Constructor for class io.github.frc5024.lib5k.utils.types.DifferentialVoltages
Create new DifferentialVoltages
disable() - Method in class io.github.frc5024.lib5k.hardware.generic.motors.MockSpeedController
 
disabled(boolean) - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
This is run during disabled
disabledInit() - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
 
disabledPeriodic() - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
 
distanceController - Variable in class io.github.frc5024.common_drive.DriveTrainConfig
Deprecated.
 
drive(double, double, InputUtils.ScalingMode) - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Drive the robot with controller inputs
DRIVER - io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightOperationMode
 
driveTo(Translation2d, double) - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Set the robot to drive to a point smoothly.
DriveTrainBase - Class in io.github.frc5024.common_drive
Deprecated, for removal: This API element is subject to removal in a future version.
DriveTrainBase(DriveTrainConfig) - Constructor for class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Create a DriveTrainBase
DriveTrainBase.States - Enum in io.github.frc5024.common_drive
Deprecated.
 
DriveTrainConfig - Class in io.github.frc5024.common_drive
Deprecated, for removal: This API element is subject to removal in a future version.
DriveTrainConfig() - Constructor for class io.github.frc5024.common_drive.DriveTrainConfig
Deprecated.
 
DriveTrainOutput - Class in io.github.frc5024.common_drive.queue
Deprecated, for removal: This API element is subject to removal in a future version.
DriveTrainOutput() - Constructor for class io.github.frc5024.common_drive.queue.DriveTrainOutput
Deprecated.
 
DriveTrainSensors - Class in io.github.frc5024.common_drive.queue
Deprecated, for removal: This API element is subject to removal in a future version.
DriveTrainSensors() - Constructor for class io.github.frc5024.common_drive.queue.DriveTrainSensors
Deprecated.
 
DualPIDTankDriveTrain - Class in io.github.frc5024.lib5k.bases.drivetrain.implementations
DualPIDTankDriveTrain is a TankDriveTrain implementation that uses two PID controllers to control autonomous robot movement
DualPIDTankDriveTrain(Controller) - Constructor for class io.github.frc5024.lib5k.bases.drivetrain.implementations.DualPIDTankDriveTrain
Create a new DualPIDTankDriveTrain
DualPIDTankDriveTrain(Controller, double) - Constructor for class io.github.frc5024.lib5k.bases.drivetrain.implementations.DualPIDTankDriveTrain
Create a new DualPIDTankDriveTrain
durationMS - Variable in class io.github.frc5024.lib5k.hardware.ctre.motors.CTREConfig
 

E

ElevatorPreset() - Constructor for class io.github.frc5024.lib5k.utils.RobotPresets.Imaginary.ElevatorPreset
 
ElevatorSystemSimulator - Class in io.github.frc5024.lib5k.simulation.systems
ElevatorSystemSimulator is a utility for simulating the outputs of an Elevator system based on its characteristics.
ElevatorSystemSimulator(LinearSystem<N2, N1, N1>, DCBrushedMotor, double, double, double, double) - Constructor for class io.github.frc5024.lib5k.simulation.systems.ElevatorSystemSimulator
Creates a simulated elevator mechanism.
ElevatorSystemSimulator(LinearSystem<N2, N1, N1>, DCBrushedMotor, double, double, double, double, Matrix<N1, N1>) - Constructor for class io.github.frc5024.lib5k.simulation.systems.ElevatorSystemSimulator
Creates a simulated elevator mechanism.
ElevatorSystemSimulator(LinearSystem<N2, N1, N1>, SystemCharacteristics, double, double, double) - Constructor for class io.github.frc5024.lib5k.simulation.systems.ElevatorSystemSimulator
Creates a simulated elevator mechanism.
ElevatorSystemSimulator(LinearSystem<N2, N1, N1>, SystemCharacteristics, double, double, double, Matrix<N1, N1>) - Constructor for class io.github.frc5024.lib5k.simulation.systems.ElevatorSystemSimulator
Creates a simulated elevator mechanism.
ElevatorSystemSimulator(DCBrushedMotor, double, double, double, double, double) - Constructor for class io.github.frc5024.lib5k.simulation.systems.ElevatorSystemSimulator
Creates a simulated elevator mechanism.
ElevatorSystemSimulator(DCBrushedMotor, double, double, double, double, double, Matrix<N1, N1>) - Constructor for class io.github.frc5024.lib5k.simulation.systems.ElevatorSystemSimulator
Creates a simulated elevator mechanism.
ElevatorSystemSimulator(StateSpaceSystem, double, double, double) - Constructor for class io.github.frc5024.lib5k.simulation.systems.ElevatorSystemSimulator
Creates a simulated elevator mechanism.
ElevatorSystemSimulator(StateSpaceSystem, double, double, double, Matrix<N1, N1>) - Constructor for class io.github.frc5024.lib5k.simulation.systems.ElevatorSystemSimulator
Creates a simulated elevator mechanism.
enableBrakes - Variable in class io.github.frc5024.lib5k.hardware.revrobotics.motors.RevConfig
 
enableBrakes(boolean) - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
TO BE OVERRIDDEN BY THE USER.
enableConstantCurvature(boolean) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
Set if constant-curvature control should be used
enableCurrentLimit - Variable in class io.github.frc5024.lib5k.hardware.ctre.motors.CTREConfig
 
enableCurrentLimit(boolean) - Method in interface io.github.frc5024.lib5k.hardware.common.motors.interfaces.ICurrentController
Enable current limiting
enableCurrentLimit(boolean) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
Set if current limiting should be enabled
enableLogging(boolean) - Method in class io.github.frc5024.lib5k.telemetry.FlywheelTuner
Enable a logging session
enableRampRateLimiting(boolean) - Method in interface io.github.frc5024.lib5k.hardware.common.motors.interfaces.IRampRateController
Set if ramp rate limiting should be enabled for the controller
enableRampRateLimiting(boolean) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
 
enableRampRateLimiting(boolean) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.VictorSPXCollection
Deprecated.
 
enableRampRateLimiting(boolean) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.MixedMotorCollection
Deprecated.
 
enableRampRateLimiting(boolean) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.SparkCollection
Deprecated.
 
enableSnapshots(boolean) - Method in class io.github.frc5024.lib5k.hardware.limelightvision.BaseLimeLight
Set if the camera should be saving a frame once every 2 seconds to internal storage.
enableSystemClockOverride(boolean, double) - Static method in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.FPGAClock
THIS IS NOT RECOMMENDED UNLESS RUNNING A UNIT TEST.
enableUSBLogging(USBLogger) - Method in class io.github.frc5024.lib5k.logging.RobotLogger
Enable logging to a USB
EncoderBase - Class in io.github.frc5024.lib5k.hardware.generic.sensors
Deprecated, for removal: This API element is subject to removal in a future version.
EncoderBase() - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.EncoderBase
Deprecated.
 
EncoderElevatorController - Class in io.github.frc5024.lib5k.control_loops.statespace.wrappers
This is a wrapper around a state space plant, observer, motion profiling, and LQR.
EncoderElevatorController(DCBrushedMotor, double, double, double, double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.statespace.wrappers.EncoderElevatorController
Create an EncoderElevatorController
EncoderElevatorController(DCBrushedMotor, double, double, double, double, double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.statespace.wrappers.EncoderElevatorController
Create an EncoderElevatorController
EncoderElevatorController(DCBrushedMotor, double, double, double, double, double, double, double, double, double, double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.statespace.wrappers.EncoderElevatorController
Create an EncoderElevatorController
EncoderSimulation - Interface in io.github.frc5024.lib5k.hardware.common.sensors.interfaces
 
EncoderSimUtil - Class in io.github.frc5024.lib5k.hardware.common.sensors.simulation
An internal class used for simulating encoder hardware
EncoderSimUtil(String, int, int, SpeedController, double, double, double) - Constructor for class io.github.frc5024.lib5k.hardware.common.sensors.simulation.EncoderSimUtil
Create a new EncoderSim utility
end(boolean) - Method in class io.github.frc5024.common_drive.commands.PathFollowCommand
Deprecated.
 
end(boolean) - Method in class io.github.frc5024.lib5k.bases.drivetrain.commands.PathFollowerCommand
 
end(boolean) - Method in class io.github.frc5024.lib5k.bases.drivetrain.commands.TurnToCommand
 
END_BLEND - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
END_BLEND_1_AND_2 - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
epsilonEquals(Pose2d, Pose2d, Pose2d) - Static method in class io.github.frc5024.lib5k.utils.RobotMath
Check if two poses are equal within epsilon
epsilonEquals(Translation2d, Translation2d, Translation2d) - Static method in class io.github.frc5024.lib5k.utils.RobotMath
Check if two translations are equal within epsilon
epsilonEquals(Color, Color, double) - Static method in class io.github.frc5024.lib5k.utils.ColorUtils
Check if two colors are equal to eachother within epsilon
execute() - Method in class io.github.frc5024.common_drive.commands.PathFollowCommand
Deprecated.
 
execute() - Method in class io.github.frc5024.lib5k.autonomous.commands.LogCommand
 
execute() - Method in class io.github.frc5024.lib5k.bases.drivetrain.commands.PathFollowerCommand
 
execute() - Method in class io.github.frc5024.lib5k.bases.drivetrain.commands.TurnToCommand
 
ExtendedCANCoder - Class in io.github.frc5024.lib5k.hardware.ctre.sensors
A wrapper around CTRE's CANCoder that integrates with 5024's encoder system
ExtendedCANCoder(int, int) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedCANCoder
Constructor.
ExtendedPIDController - Class in io.github.frc5024.lib5k.control_loops
ExtendedPIDController is an extension of WPILib's PIDController that adds a few quality-of-life features
ExtendedPIDController(double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.ExtendedPIDController
Create an ExtendedPIDController
ExtendedPIDController(double, double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.ExtendedPIDController
Create an ExtendedPIDController
ExtendedPIDController(double, double, double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.ExtendedPIDController
Create an ExtendedPIDController
ExtendedPigeonIMU - Class in io.github.frc5024.lib5k.hardware.ctre.sensors
A wrapper for the CTRE PigeonIMU that brings it into the 5024 ecosystem.
ExtendedPigeonIMU(int) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedPigeonIMU
Connect to a Pigeon IMU
ExtendedPigeonIMU(TalonSRX) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedPigeonIMU
Connect to a Pigeon IMU
ExtendedSparkMax - Class in io.github.frc5024.lib5k.hardware.revrobotics.motors
An extension of the CANSparkMax with simulation support, and mappings from CANEncoder to CommonEncoder for hot-swappability with CTRE products
ExtendedSparkMax(int, CANSparkMaxLowLevel.MotorType) - Constructor for class io.github.frc5024.lib5k.hardware.revrobotics.motors.ExtendedSparkMax
Create an extended spark max
ExtendedSparkMax(int, RevConfig) - Constructor for class io.github.frc5024.lib5k.hardware.revrobotics.motors.ExtendedSparkMax
Create an extended spark max
ExtendedTalonFX - Class in io.github.frc5024.lib5k.hardware.ctre.motors
The ExtendedTalonFX contains two extra features from WPI_TalonFX: - Ablilty to get the attached sensor as a CommonEncoder object - Small fixes for 2020 simulation voltage bugs in HALSIM
ExtendedTalonFX(int) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedTalonFX
Create an extended Talon FX
ExtendedTalonFX(int, CTREConfig) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedTalonFX
Create an extended Talon FX
ExtendedTalonSRX - Class in io.github.frc5024.lib5k.hardware.ctre.motors
The ExtendedTalonSRX contains two extra features from WPI_TalonSRX: - Ability to get the attached sensor as a CommonEncoder object - Small fixes for 2020 simulation voltage bugs in HALSIM
ExtendedTalonSRX(int) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedTalonSRX
Create an extended Talon SRX
ExtendedTalonSRX(int, CTREConfig) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedTalonSRX
Create an extended Talon SRX
ExtendedVictorSPX - Class in io.github.frc5024.lib5k.hardware.ctre.motors
The ExtendedVictorSPX contains an extra feature from WPI_VictorSPX: - Small fixes for 2020 simulation voltage bugs in HALSIM
ExtendedVictorSPX(int) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedVictorSPX
Create an extended Victor SPX
ExtendedVictorSPX(int, CTREConfig) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedVictorSPX
Create an extended Victor SPX

F

FakeScheduler - Class in io.github.frc5024.lib5k.unittest
FakeScheduler allows a user to Simulate robot timekeeping and task scheduling in a unit test
FakeScheduler(double, double) - Constructor for class io.github.frc5024.lib5k.unittest.FakeScheduler
Create a FakeScheduler
FakeScheduler(CommandScheduler, double, double) - Constructor for class io.github.frc5024.lib5k.unittest.FakeScheduler
Create a FakeScheduler
FaultReporter - Class in io.github.frc5024.lib5k.hardware.ni.roborio
Utility for tracking and reporting RoboRIO FPGA faults.
feed(boolean) - Method in class io.github.frc5024.lib5k.utils.Toggle
Feed the input state to the toggle
feed(double) - Method in class io.github.frc5024.lib5k.control_loops.PID
Deprecated.
Feed the controller with a sensor reading
feed(double) - Method in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Feed the system with the current sensor reading
feed(double) - Method in class io.github.frc5024.lib5k.control_loops.SlewLimiter
Limit a value, and update the system
feed(double) - Method in class io.github.frc5024.lib5k.control_loops.TimedSlewLimiter
Limit a value, and update the system.
feedError(double) - Method in class io.github.frc5024.lib5k.control_loops.PID
Deprecated.
Feed the controller with a sensor error
FF - Variable in class io.github.frc5024.lib5k.config.types.JSONPIDGains
 
FIELD_SIZE - Static variable in class io.github.frc5024.lib5k.utils.FRCFieldConstants
 
FieldTested - Annotation Type in io.github.frc5024.lib5k.utils.annotations
Indicates that a class or method was successfully used by a team on an FRC field (on or off season)
FileManagement - Class in io.github.frc5024.lib5k.utils
This class handles session-based file management for the robot.
FileManagement() - Constructor for class io.github.frc5024.lib5k.utils.FileManagement
 
FileUtils - Class in io.github.frc5024.lib5k.utils
Tools for working with the filesystem
FileUtils() - Constructor for class io.github.frc5024.lib5k.utils.FileUtils
 
findDistanceFromAToB(Rotation2d, Rotation2d) - Method in class ca.retrylife.frc.templates.turrets.TurretBase
Find the fastest and safest way to get from A to B.
finish() - Method in class io.github.frc5024.lib5k.unittest.FakeScheduler
Called when done
FIRE_LARGE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
FIRE_MEDIUM - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
flush() - Method in class io.github.frc5024.lib5k.hardware.generic.pneumatics.LazySolenoid
re-send the current state to flush CAN
flush() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.LineBreak
Flush the CAN bus and send a new packet to keep external power enabled
flush() - Method in class io.github.frc5024.lib5k.logging.RobotLogger
Manually flush the logs (only use this in unit tests)
FLYWHEEL_DIAMETER - Static variable in class io.github.frc5024.lib5k.utils.RobotPresets.DarthRaider.FlywheelPreset
 
FLYWHEEL_MASS_KG - Static variable in class io.github.frc5024.lib5k.utils.RobotPresets.DarthRaider.FlywheelPreset
 
FlywheelMath - Class in io.github.frc5024.lib5k.control_loops.statespace.util.easylqr
This class contains utils for calculating parameters of flywheels
FlywheelMath() - Constructor for class io.github.frc5024.lib5k.control_loops.statespace.util.easylqr.FlywheelMath
 
FlywheelPreset() - Constructor for class io.github.frc5024.lib5k.utils.RobotPresets.DarthRaider.FlywheelPreset
 
FlywheelSystemSimulator - Class in io.github.frc5024.lib5k.simulation.systems
FlywheelSystemSimulator is a utility for simulating the outputs of a Flywheel system based on its characteristics.
FlywheelSystemSimulator(LinearSystem<N1, N1, N1>, DCBrushedMotor, double) - Constructor for class io.github.frc5024.lib5k.simulation.systems.FlywheelSystemSimulator
Creates a simulated flywheel mechanism.
FlywheelSystemSimulator(LinearSystem<N1, N1, N1>, DCBrushedMotor, double, Matrix<N1, N1>) - Constructor for class io.github.frc5024.lib5k.simulation.systems.FlywheelSystemSimulator
Creates a simulated flywheel mechanism.
FlywheelSystemSimulator(LinearSystem<N1, N1, N1>, SystemCharacteristics) - Constructor for class io.github.frc5024.lib5k.simulation.systems.FlywheelSystemSimulator
Creates a simulated flywheel mechanism.
FlywheelSystemSimulator(LinearSystem<N1, N1, N1>, SystemCharacteristics, Matrix<N1, N1>) - Constructor for class io.github.frc5024.lib5k.simulation.systems.FlywheelSystemSimulator
Creates a simulated flywheel mechanism.
FlywheelSystemSimulator(DCBrushedMotor, double, double) - Constructor for class io.github.frc5024.lib5k.simulation.systems.FlywheelSystemSimulator
Creates a simulated flywheel mechanism.
FlywheelSystemSimulator(DCBrushedMotor, double, double, Matrix<N1, N1>) - Constructor for class io.github.frc5024.lib5k.simulation.systems.FlywheelSystemSimulator
Creates a simulated flywheel mechanism.
FlywheelSystemSimulator(StateSpaceSystem) - Constructor for class io.github.frc5024.lib5k.simulation.systems.FlywheelSystemSimulator
Creates a simulated flywheel mechanism.
FlywheelSystemSimulator(StateSpaceSystem, Matrix<N1, N1>) - Constructor for class io.github.frc5024.lib5k.simulation.systems.FlywheelSystemSimulator
Creates a simulated flywheel mechanism.
FlywheelTuner - Class in io.github.frc5024.lib5k.telemetry
A utility class for providing data to a robot telemetry client
FlywheelTuner(String, DoubleSupplier) - Constructor for class io.github.frc5024.lib5k.telemetry.FlywheelTuner
Create a FlywheelTuner server
FMSNetworking - Class in io.github.frc5024.lib5k.utils
 
FMSNetworking() - Constructor for class io.github.frc5024.lib5k.utils.FMSNetworking
 
FMSNetworking.SocketType - Enum in io.github.frc5024.lib5k.utils
 
Follower - Class in io.github.frc5024.purepursuit
A lookahead finder for finding new points in a 2D path.
Follower(Path, double, double, double) - Constructor for class io.github.frc5024.purepursuit.Follower
Create a path follower
forEachSlave(Consumer<WPI_TalonSRX>) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
For-Each over each slave controller
forEachSlave(Consumer<WPI_VictorSPX>) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.VictorSPXCollection
Deprecated.
For-Each over each slave controller
forEachSlave(Consumer<Spark>) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.SparkCollection
Deprecated.
For-Each over each slave controller
forEachSlave(Consumer<SpeedController>) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.MixedMotorCollection
Deprecated.
For-Each over each slave controller
FPGAClock - Class in io.github.frc5024.lib5k.hardware.ni.roborio.fpga
Tools for interacting with the FPGA's high-precision clock
FPGAClock() - Constructor for class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.FPGAClock
 
FRCFieldConstants - Class in io.github.frc5024.lib5k.utils
Standard FRC field measurements.
FRCFieldConstants() - Constructor for class io.github.frc5024.lib5k.utils.FRCFieldConstants
 
freeLimit - Variable in class io.github.frc5024.lib5k.hardware.revrobotics.motors.RevConfig
 
fromThrottleAndSteering(double, double) - Static method in class io.github.frc5024.lib5k.utils.types.DifferentialVoltages
Create new DifferentialVoltages from a throttle and steering value
fromThrottleAndSteering(ThrottleSteering) - Static method in class io.github.frc5024.lib5k.utils.types.DifferentialVoltages
Create new DifferentialVoltages from a throttle and steering value
fullReset() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.EncoderBase
Deprecated.
Reset the encoder "0" position

G

gear - Variable in class io.github.frc5024.common_drive.queue.DriveTrainOutput
Deprecated.
 
Gear - Enum in io.github.frc5024.common_drive.gearing
Shifter state
GenericEncoder - Class in io.github.frc5024.lib5k.hardware.generic.sensors
 
GenericEncoder(int, int, boolean, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
Encoder constructor.
GenericEncoder(int, int, boolean, CounterBase.EncodingType, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
Encoder constructor.
GenericEncoder(int, int, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
Encoder constructor.
GenericEncoder(int, int, int, boolean, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
Encoder constructor.
GenericEncoder(int, int, int, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
Encoder constructor.
GenericEncoder(DigitalSource, DigitalSource, boolean, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
Encoder constructor.
GenericEncoder(DigitalSource, DigitalSource, boolean, CounterBase.EncodingType, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
Encoder constructor.
GenericEncoder(DigitalSource, DigitalSource, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
Encoder constructor.
GenericEncoder(DigitalSource, DigitalSource, DigitalSource, boolean, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
Encoder constructor.
GenericEncoder(DigitalSource, DigitalSource, DigitalSource, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
Encoder constructor.
get() - Method in interface io.github.frc5024.lib5k.hardware.common.sensors.interfaces.IBinarySensor
Get binary sensor reading
get() - Method in enum io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
Get the PWM value
get() - Method in class io.github.frc5024.lib5k.hardware.generic.motors.MockSpeedController
 
get() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.HallEffect
 
get() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.LimitSwitch
 
get() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.MockDigitalInput
 
get() - Method in class io.github.frc5024.lib5k.hardware.revrobotics.motors.ExtendedSparkMax
 
get() - Method in class io.github.frc5024.lib5k.utils.Toggle
This is to be used in a situation were you are not looking to toggle the value, just read
getActivePipelineID() - Method in class io.github.frc5024.lib5k.hardware.limelightvision.BaseLimeLight
Get the ID of the currently active image processing pipeline on-device
getAngle() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.GyroSimUtil
Get the sensor angle
getAngle() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedPigeonIMU
 
getAngle() - Method in class io.github.frc5024.lib5k.hardware.generic.gyroscopes.ADGyro
 
getAngle() - Method in class io.github.frc5024.lib5k.hardware.kauai.gyroscopes.NavX
 
getAngularErrorDegrees(Rotation2d, Rotation2d) - Static method in class io.github.frc5024.lib5k.math.RotationMath
Get the error in degrees between two rotations
getAspectRatio() - Method in class io.github.frc5024.lib5k.vision.types.AxisAlignedBoundingBox
Get the aspect ratio of this box as width/height
getAverageSpeed() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.EncoderBase
Deprecated.
 
getBackupFilePath() - Method in class io.github.frc5024.lib5k.config.SingleInstanceJSONConfig
Builds a file path for the config inside session folder
getBottomBoundRotation() - Method in class io.github.frc5024.lib5k.vision.types.HyperbolicAxisAlignedBoundingBox
Get the rotation from the center to the bottom bound
getBottomLeftCorner() - Method in class io.github.frc5024.lib5k.vision.types.AxisAlignedBoundingBox
Get the bottom left corner of this box expressed as a percentage of the frame from the center (top left is -1,1)
getBottomRightCorner() - Method in class io.github.frc5024.lib5k.vision.types.AxisAlignedBoundingBox
Get the bottom right corner of this box expressed as a percentage of the frame from the center (top left is -1,1)
getCalibrated() - Method in interface io.github.frc5024.lib5k.hardware.common.sensors.interfaces.IGyroscope
Get if the sensor has been calibrated
getCalibrated() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedPigeonIMU
 
getCalibrated() - Method in class io.github.frc5024.lib5k.hardware.generic.gyroscopes.ADGyro
 
getCalibrated() - Method in class io.github.frc5024.lib5k.hardware.kauai.gyroscopes.NavX
 
getChart() - Method in class io.github.frc5024.lib5k.unittest.Grapher
Access the internal XYChart
getCommand() - Method in interface io.github.frc5024.lib5k.autonomous.AutonomousSequence
Get the command that runs the sequence
getCommonEncoder() - Method in class io.github.frc5024.lib5k.hardware.revrobotics.motors.ExtendedSparkMax
Returns and object for interfacing with the encoder connected to the encoder pins or front port of the SPARK MAX.
getCommonEncoder(int) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedTalonFX
Get the attached encoder
getCommonEncoder(int) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedTalonSRX
Get the attached encoder
getCommonEncoder(EncoderType, int) - Method in class io.github.frc5024.lib5k.hardware.revrobotics.motors.ExtendedSparkMax
Returns and object for interfacing with the encoder connected to the encoder pins or front port of the SPARK MAX.
getConfig() - Method in class io.github.frc5024.lib5k.config.SingleInstanceJSONConfig
Get an instance of the loaded config, or load the config
getCurrentHeading() - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
TO BE OVERRIDDEN BY THE USER.
getCurrentState() - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
Get the internal state of the DriveTrain
getCurrentState() - Method in class io.github.frc5024.libkontrol.statemachines.StateMachine
Get the system's current state
getDashboardTab() - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
Get a reference to the ShuffleboardTab used by this program
getDefaultEncoder() - Method in interface io.github.frc5024.lib5k.hardware.generic.sensors.interfaces.IEncoderProvider
Deprecated.
Get the default encoder
getDeployPath() - Static method in class io.github.frc5024.lib5k.utils.FileUtils
Query WPIlib's filesystem for deploy path
getDrivebaseWidth() - Method in class io.github.frc5024.purepursuit.Follower
Get the width of the drivebase
getEncoder(int, boolean) - Method in interface io.github.frc5024.lib5k.hardware.generic.sensors.interfaces.IEncoderProvider
Deprecated.
Get an encoder of a specific ID.
getEpsilon() - Method in class io.github.frc5024.lib5k.control_loops.base.ControllerBase
Deprecated.
Get acceptable error around goal
getError() - Method in class io.github.frc5024.lib5k.control_loops.PID
Deprecated.
Get the last recorded error
getEstimatedVoltage() - Method in interface io.github.frc5024.lib5k.hardware.common.motors.interfaces.IVoltageOutputController
Estimate controller output voltage from speed
getEstimatedVoltage() - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
 
getEstimatedVoltage() - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.VictorSPXCollection
Deprecated.
 
getEstimatedVoltage() - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.MixedMotorCollection
Deprecated.
 
getEstimatedVoltage() - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.SparkCollection
Deprecated.
 
getFeed() - Method in class io.github.frc5024.lib5k.hardware.generic.cameras.AutoCamera
Get the camera feed object
getFinalPose() - Method in class io.github.frc5024.purepursuit.Follower
Get the final pose of the path
getFPGAMilliseconds() - Static method in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.FPGAClock
Get the number of milliseconds since the robot timer started
getFPGASeconds() - Static method in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.FPGAClock
Get the number of seconds since the robot timer started
getFreeSpeedRPM() - Method in class io.github.frc5024.lib5k.control_loops.models.DCBrushedMotor
Get the motor's free spinning speed in RPM
getFrontSide() - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
Get which side is the front
getGearRatio() - Method in interface io.github.frc5024.lib5k.control_loops.models.SystemCharacteristics
System gear ratio expressed as output over input
getGearRatio() - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.EncoderElevatorController
 
getGearRatio() - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SimpleFlywheelController
 
getGoal() - Method in class io.github.frc5024.lib5k.control_loops.base.ControllerBase
Deprecated.
Get the system goal
getHeading() - Method in interface io.github.frc5024.lib5k.hardware.common.sensors.interfaces.IGyroscope
Returns the current heading heading
getHeading() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedPigeonIMU
 
getHeading() - Method in class io.github.frc5024.lib5k.hardware.generic.gyroscopes.ADGyro
 
getHeading() - Method in class io.github.frc5024.lib5k.hardware.kauai.gyroscopes.NavX
 
getHeight() - Method in class io.github.frc5024.lib5k.vision.types.AxisAlignedBoundingBox
Get box height
getHome() - Static method in class io.github.frc5024.lib5k.utils.FileUtils
Deprecated.
getHorizontalTheta() - Method in class io.github.frc5024.lib5k.vision.types.HyperbolicAxisAlignedBoundingBox
Get the theta between the left and right bounds
getImageProcessingLatencyMS() - Method in class io.github.frc5024.lib5k.hardware.limelightvision.BaseLimeLight
Get the number of MS of latency the camera takes to process an image
getInstance() - Static method in class io.github.frc5024.asynchal.Poller
Get a poller instance
getInstance() - Static method in class io.github.frc5024.lib5k.hardware.generic.gyroscopes.ADGyro
Get the Default NavX instance
getInstance() - Static method in class io.github.frc5024.lib5k.hardware.kauai.gyroscopes.NavX
Get the Default NavX instance
getInstance() - Static method in class io.github.frc5024.lib5k.hardware.ni.roborio.FaultReporter
Get the FaultReporter instance
getInstance() - Static method in class io.github.frc5024.lib5k.logging.RobotLogger
Get a RobotLogger instance
getInstance() - Static method in class io.github.frc5024.lib5k.telemetry.ComponentTelemetry
Get the ComponentTelemetry instance
getInstance() - Static method in class io.github.frc5024.lib5k.utils.IMGUIFieldReporter
Get reporter instance
getInternalState() - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Read the current state of the internal state machine.
getInverted() - Method in interface io.github.frc5024.lib5k.hardware.common.sensors.interfaces.CommonEncoder
Get the phase of the sensor.
getInverted() - Method in interface io.github.frc5024.lib5k.hardware.common.sensors.interfaces.IGyroscope
Get if the readings are inverted
getInverted() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.EncoderSimUtil
Get if encoder is inverted
getInverted() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.GyroSimUtil
Get if the sensor is inverted
getInverted() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.CANIfierEncoder
 
getInverted() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedCANCoder
 
getInverted() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedPigeonIMU
 
getInverted() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.TalonEncoder
 
getInverted() - Method in class io.github.frc5024.lib5k.hardware.generic.gyroscopes.ADGyro
 
getInverted() - Method in class io.github.frc5024.lib5k.hardware.generic.motors.MockSpeedController
 
getInverted() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
 
getInverted() - Method in class io.github.frc5024.lib5k.hardware.kauai.gyroscopes.NavX
 
getInverted() - Method in class io.github.frc5024.lib5k.hardware.revrobotics.sensors.SparkMaxEncoder
 
getIRange() - Method in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Get the integrator range
getKv() - Method in class io.github.frc5024.lib5k.control_loops.models.DCBrushedMotor
Get the motor's Kv in RPM
getLastCANWriteTimestampSeconds() - Method in class io.github.frc5024.lib5k.hardware.generic.pneumatics.LazySolenoid
Gets the timestamp of the last time a CAN packet was written
getLastKnownPosition() - Method in class ca.retrylife.frc.templates.arms.SensorlessArm
Get the last known position of the arm
getLastMeasurement() - Method in class io.github.frc5024.lib5k.control_loops.base.ControllerBase
Deprecated.
Get the last known measurement
getLeftBoundRotation() - Method in class io.github.frc5024.lib5k.vision.types.HyperbolicAxisAlignedBoundingBox
Get the rotation from the center to the left bound
getLeftBusPercentage() - Method in class io.github.frc5024.lib5k.utils.types.DifferentialVoltages
Get the left voltage as a percentage of the current robot bus voltage
getLeftMeters() - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Get the scalar distance traveled by the left side of the drivetrain
getLeftMeters() - Method in interface io.github.frc5024.lib5k.hardware.common.drivebase.IDifferentialDrivebase
Get left side distance traveled in meters
getLeftPercentage() - Method in class io.github.frc5024.lib5k.utils.types.DifferentialVoltages
Get the left voltage as a percentage of the maximum robot bus voltage
getLeftVolts() - Method in class io.github.frc5024.lib5k.utils.types.DifferentialVoltages
Get the left voltage
getLibraryVersion() - Static method in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.RR_HAL
Get the Lib5K version (wpi version + Lib5K identifier + FRC year)
getLookaheadDistance() - Method in class io.github.frc5024.purepursuit.Follower
Get the current lookahead distance
getLookaheadGain() - Method in class io.github.frc5024.purepursuit.Follower
Get the lookahead gain
getLQR() - Method in interface io.github.frc5024.lib5k.control_loops.statespace.StateSpaceSystem
Get the system linear-quadratic regulator
getLQR() - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.EncoderElevatorController
 
getLQR() - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SimpleFlywheelController
 
getMaster() - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
Get the master TalonSRX
getMaster() - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.VictorSPXCollection
Deprecated.
Get the master VictorSPX
getMeters(int, double) - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.EncoderBase
Deprecated.
Get sensor distance traveled in meters
getMetersPerCycle(int, double) - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.EncoderBase
Deprecated.
Get sensor distance traveled in meters since last cycle
getMillisecondCycle(double) - Static method in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.FPGAClock
A utility for anything that needs to toggle every N milliseconds (for example, a blinking light)
getMostRecentGoal() - Method in class io.github.frc5024.lib5k.bases.drivetrain.commands.PathFollowerCommand
Get the most recent goal pose
getMotorCharacteristics() - Method in interface io.github.frc5024.lib5k.control_loops.models.SystemCharacteristics
System motor characteristics
getMotorCharacteristics() - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.EncoderElevatorController
 
getMotorCharacteristics() - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SimpleFlywheelController
 
getMotorOutputVoltage() - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedTalonFX
 
getMotorOutputVoltage() - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedTalonSRX
 
getMotorOutputVoltage() - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedVictorSPX
 
getName() - Method in interface io.github.frc5024.lib5k.autonomous.AutonomousSequence
Get the name of the sequence
getNewID() - Method in class io.github.frc5024.lib5k.utils.ObjectCounter
Every time this is called, it will return the next int in the counter.
getNextPoint(Pose2d) - Method in class io.github.frc5024.purepursuit.Follower
Get the next goal pose
getObserver() - Method in interface io.github.frc5024.lib5k.control_loops.statespace.StateSpaceSystem
Get the system observer
getObserver() - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.EncoderElevatorController
 
getObserver() - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SimpleFlywheelController
 
getPackageName(StackTraceElement) - Static method in class io.github.frc5024.lib5k.logging.RobotLogger
Gets a friendly package name for a StackTraceElement
getParent() - Method in class io.github.frc5024.libkontrol.statemachines.StateMetadata
Get the StateMachine object that this state belongs to
getPathVisualization() - Method in class io.github.frc5024.purepursuit.pathgen.Path
Get a chart showing every generated path point in 2D space.
getPlant() - Method in interface io.github.frc5024.lib5k.control_loops.statespace.StateSpaceSystem
Get the system plant
getPlant() - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.EncoderElevatorController
 
getPlant() - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SimpleFlywheelController
 
getPose() - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Get the robot pose
getPose() - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
Get the robot's current pose
getPose() - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
 
getPoses() - Method in class io.github.frc5024.purepursuit.pathgen.Path
Get a list of all poses along the path
getPosition() - Method in interface io.github.frc5024.lib5k.hardware.common.sensors.interfaces.CommonEncoder
Get the position of the motor.
getPosition() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.CANIfierEncoder
 
getPosition() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedCANCoder
 
getPosition() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.TalonEncoder
 
getPosition() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
 
getPosition() - Method in class io.github.frc5024.lib5k.hardware.revrobotics.sensors.SparkMaxEncoder
 
getPressurePSI() - Method in class io.github.frc5024.lib5k.hardware.revrobotics.sensors.PressureSensor
Get the sensed air pressure in PSI
getPreviousStateKey() - Method in class io.github.frc5024.libkontrol.statemachines.StateMetadata
Get the key of the last state to run.
getRampRate() - Method in interface io.github.frc5024.lib5k.hardware.common.motors.interfaces.IRampRateController
Get the configured ramp rate
getRampRate() - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
 
getRampRate() - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.VictorSPXCollection
Deprecated.
 
getRampRate() - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.MixedMotorCollection
Deprecated.
 
getRampRate() - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.SparkCollection
Deprecated.
 
getRate() - Method in class io.github.frc5024.lib5k.control_loops.SlewLimiter
Get the maximum amount of change allowed by the system
getRate() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.GyroSimUtil
Get the sensor rate
getRate() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedPigeonIMU
 
getRate() - Method in class io.github.frc5024.lib5k.hardware.generic.gyroscopes.ADGyro
 
getRate() - Method in class io.github.frc5024.lib5k.hardware.kauai.gyroscopes.NavX
 
getRawTicks() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.EncoderBase
Deprecated.
Get the raw sensor reading from encoder
getRestMS() - Method in class io.github.frc5024.lib5k.control_loops.base.SettlingController
Deprecated.
Get the amount of time the system must be stable for in order for "is at goal" to be true
getRightBoundRotation() - Method in class io.github.frc5024.lib5k.vision.types.HyperbolicAxisAlignedBoundingBox
Get the rotation from the center to the right bound
getRightBusPercentage() - Method in class io.github.frc5024.lib5k.utils.types.DifferentialVoltages
Get the right voltage as a percentage of the current robot bus voltage
getRightMeters() - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Get the scalar distance traveled by the right side of the drivetrain
getRightMeters() - Method in interface io.github.frc5024.lib5k.hardware.common.drivebase.IDifferentialDrivebase
Get right side distance traveled in meters
getRightPercentage() - Method in class io.github.frc5024.lib5k.utils.types.DifferentialVoltages
Get the right voltage as a percentage of the maximum robot bus voltage
getRightVolts() - Method in class io.github.frc5024.lib5k.utils.types.DifferentialVoltages
Get the right voltage
getRobotName() - Static method in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.RR_HAL
Returns the name of the robot if the name cannot be found, returns Unknown Robot
getRotation() - Method in interface io.github.frc5024.lib5k.hardware.common.sensors.interfaces.IGyroscope
Get the heading as a Rotation2d object
getRotations() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.EncoderSimUtil
Get rotation count
getSelectedAutonomous() - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
Get the selected autonomous.
getSensorReading() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.EncoderBase
Deprecated.
 
getSessionDirectory() - Static method in class io.github.frc5024.lib5k.utils.FileManagement
Get a file object for the session directory
getSessionDirectoryPath() - Static method in class io.github.frc5024.lib5k.utils.FileManagement
Get the filepath to the session directory
getSetpoint() - Method in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Get the controller setpoint
getSimSafeVoltage() - Static method in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.RR_HAL
Get the robot voltage, but return 12.0v if the robot is running in simulation, and the "real" voltage is set to 0.0v (this solves allwpilib PR #2224)
getSpeed() - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
Get the robot's speed in meters per period
getSpeed() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.EncoderBase
Deprecated.
Get the speed of the encoder in Ticks per cycle (usually 20ms)
getStartingPose() - Method in interface io.github.frc5024.lib5k.autonomous.AutonomousSequence
Get the robot's initial pose for this sequence
getSteering() - Method in class io.github.frc5024.lib5k.utils.types.ThrottleSteering
Get the steering value
getTableForComponent(String) - Method in class io.github.frc5024.lib5k.telemetry.ComponentTelemetry
Get the NetworkTable for a component
getTargetBoundsOrNull() - Method in class io.github.frc5024.lib5k.hardware.limelightvision.BaseLimeLight
Get the bounding box for the LimeLight target, or NULL if no target is found
getThrottle() - Method in class io.github.frc5024.lib5k.utils.types.ThrottleSteering
Get the throttle value
getTicks() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.EncoderSimUtil
Get raw tick count
getTicks() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.EncoderBase
Deprecated.
Get sensor reading accounting for offsets
getTopBoundRotation() - Method in class io.github.frc5024.lib5k.vision.types.HyperbolicAxisAlignedBoundingBox
Get the rotation from the center to the top bound
getTopLeftCorner() - Method in class io.github.frc5024.lib5k.vision.types.AxisAlignedBoundingBox
Get the top left corner of this box expressed as a percentage of the frame from the center (top left is -1,1)
getTopRightCorner() - Method in class io.github.frc5024.lib5k.vision.types.AxisAlignedBoundingBox
Get the top right corner of this box expressed as a percentage of the frame from the center (top left is -1,1)
getTranslation() - Method in class io.github.frc5024.purepursuit.util.WPI_PathPoint
Convert the WPI_PathPoint into a Translation2d
getUnderlyingRunnable() - Method in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.SafeNotifier
ADVANCED USE ONLY.
getUnderlyingThread() - Method in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.SafeNotifier
ADVANCED USE ONLY.
getUSBStickBasePath() - Static method in class io.github.frc5024.lib5k.utils.FileManagement
Get the base path to the attached USB stick
getValue() - Method in enum io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightLEDMode
Get the LimeLightLEDMode setting value
getValue() - Method in enum io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightOperationMode
Get the LimeLightOperationMode setting value
getValue() - Method in enum io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightStreamMode
Get the LimeLightStreamMode setting value
getVelocity() - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
Get the robot's velocity in meters per period
getVelocity() - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
 
getVelocity() - Method in interface io.github.frc5024.lib5k.hardware.common.sensors.interfaces.CommonEncoder
Get the velocity of the motor.
getVelocity() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.EncoderSimUtil
Get velocity in RPM
getVelocity() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.CANIfierEncoder
 
getVelocity() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedCANCoder
 
getVelocity() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.TalonEncoder
 
getVelocity() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
 
getVelocity() - Method in class io.github.frc5024.lib5k.hardware.revrobotics.sensors.SparkMaxEncoder
 
getVerticalTheta() - Method in class io.github.frc5024.lib5k.vision.types.HyperbolicAxisAlignedBoundingBox
Get the theta between the top and bottom bounds
getWheelCircumference() - Method in class io.github.frc5024.common_drive.DriveTrainConfig
Deprecated.
Get the wheel circumference
getWidth() - Method in class io.github.frc5024.lib5k.vision.types.AxisAlignedBoundingBox
Get box width
getWidthMeters() - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
 
getWidthMeters() - Method in interface io.github.frc5024.lib5k.hardware.common.drivebase.IDifferentialDrivebase
Get track width in meters
getWrappedAngle() - Method in interface io.github.frc5024.lib5k.hardware.common.sensors.interfaces.IGyroscope
Get the gyro angle, wrapped by 360 degrees
getXRotation() - Method in class io.github.frc5024.lib5k.vision.types.Contour
Get the X angle from the camera
getYRotation() - Method in class io.github.frc5024.lib5k.vision.types.Contour
Get the Y angle from the camera
globallyOverrideCalculationOutput(Double) - Static method in class io.github.frc5024.lib5k.utils.TimeScale
Deprecated.
GOLD - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
GRADIENT_1_AND_2 - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
Grapher - Class in io.github.frc5024.lib5k.unittest
Grapher is a utility for producing graphs from a unit test
Grapher(String, String) - Constructor for class io.github.frc5024.lib5k.unittest.Grapher
Create a Grapher (this only works in unit tests)
Grapher(String, String, int, int) - Constructor for class io.github.frc5024.lib5k.unittest.Grapher
Create a Grapher (this only works in unit tests)
GRAY - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
GREEN - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
GyroSimUtil - Class in io.github.frc5024.lib5k.hardware.common.sensors.simulation
A utility class for simulating gyroscope data based on two encoders
GyroSimUtil(String, int, IDifferentialDrivebase) - Constructor for class io.github.frc5024.lib5k.hardware.common.sensors.simulation.GyroSimUtil
Create a GyroSimUtil
GyroSimUtil(String, int, IDifferentialDrivebase, double, double) - Constructor for class io.github.frc5024.lib5k.hardware.common.sensors.simulation.GyroSimUtil
Create a GyroSimUtil

H

HALF_FIELD_LENGTH - Static variable in class io.github.frc5024.lib5k.utils.FRCFieldConstants
 
HALF_FIELD_SIZE - Static variable in class io.github.frc5024.lib5k.utils.FRCFieldConstants
 
HALF_FIELD_WIDTH - Static variable in class io.github.frc5024.lib5k.utils.FRCFieldConstants
 
HallEffect - Class in io.github.frc5024.lib5k.hardware.generic.sensors
Hall effect sensor
HallEffect(int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.HallEffect
Create a digital Hall Effect sensor object
handleAutonomousRotation(StateMetadata<AbstractDriveTrain.State>, Rotation2d, Rotation2d) - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
State handler for autonomous rotation control
handleAutonomousRotation(StateMetadata<AbstractDriveTrain.State>, Rotation2d, Rotation2d) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.DualPIDTankDriveTrain
 
handleAutonomousRotation(StateMetadata<AbstractDriveTrain.State>, Rotation2d, Rotation2d) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.OpenLoopTankDriveTrain
 
handleDriverInputs(double, double) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
Handle inputs from a human operator
handleDrivingToPose(StateMetadata<AbstractDriveTrain.State>, Translation2d, Translation2d) - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
State handler for driving to a new pose autonomously
handleDrivingToPose(StateMetadata<AbstractDriveTrain.State>, Translation2d, Translation2d) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.DualPIDTankDriveTrain
 
handleDrivingToPose(StateMetadata<AbstractDriveTrain.State>, Translation2d, Translation2d) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.OpenLoopTankDriveTrain
 
handleGearShift(Gear) - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
TO BE OVERRIDDEN BY THE USER.
handleOpenLoopControl(StateMetadata<AbstractDriveTrain.State>) - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
State handler for open-loop control
handleOpenLoopControl(StateMetadata<AbstractDriveTrain.State>) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
 
handleVoltage(double, double) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
TO BE OVERRIDDEN BY THE USER.
hasLoadedConfig() - Method in class io.github.frc5024.lib5k.config.SingleInstanceJSONConfig
Get if the config has been loaded yet
hasTarget() - Method in class io.github.frc5024.lib5k.hardware.limelightvision.BaseLimeLight
Check if the LimeLight can see its target
HEARTBEAT_BLUE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
HEARTBEAT_GRAY - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
HEARTBEAT_RED - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
HEARTBEAT_WHITE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
HIGH - io.github.frc5024.common_drive.gearing.Gear
 
highGearRatio - Variable in class io.github.frc5024.common_drive.DriveTrainConfig
Deprecated.
 
holdAmps - Variable in class io.github.frc5024.lib5k.hardware.ctre.motors.CTREConfig
 
holdPosition() - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
This locks the drivetrain, and tells it to hold its position
HOT_PINK - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
HyperbolicAxisAlignedBoundingBox - Class in io.github.frc5024.lib5k.vision.types
HyperbolicAxisAlignedBoundingBox is a non-euclidean AxisAlignedBoundingBox in hyperbolic space
HyperbolicAxisAlignedBoundingBox(Translation2d, Translation2d, Rotation2d, Rotation2d) - Constructor for class io.github.frc5024.lib5k.vision.types.HyperbolicAxisAlignedBoundingBox
Create a HyperbolicAxisAlignedBoundingBox from a horizontal and vertical theta
HyperbolicAxisAlignedBoundingBox(Translation2d, Translation2d, Rotation2d, Rotation2d, Rotation2d, Rotation2d) - Constructor for class io.github.frc5024.lib5k.vision.types.HyperbolicAxisAlignedBoundingBox
Create a HyperbolicAxisAlignedBoundingBox from a horizontal and vertical theta
HyperbolicAxisAlignedBoundingBox(Translation2d, Translation2d, Rotation2d, Rotation2d, Rotation2d, Rotation2d, Rotation2d, Rotation2d) - Constructor for class io.github.frc5024.lib5k.vision.types.HyperbolicAxisAlignedBoundingBox
Create a HyperbolicAxisAlignedBoundingBox using rotations for each side

I

IBinarySensor - Interface in io.github.frc5024.lib5k.hardware.common.sensors.interfaces
Interface for binary sensors
ICurrentController - Interface in io.github.frc5024.lib5k.hardware.common.motors.interfaces
Common interface for devices that with current output controls
id - Variable in class io.github.frc5024.lib5k.config.types.JSONMotor
 
IDifferentialDrivebase - Interface in io.github.frc5024.lib5k.hardware.common.drivebase
Interface for a simple differential drivebase
IEncoderProvider - Interface in io.github.frc5024.lib5k.hardware.generic.sensors.interfaces
Deprecated, for removal: This API element is subject to removal in a future version.
IGyroscope - Interface in io.github.frc5024.lib5k.hardware.common.sensors.interfaces
Common interface for all gyroscopes
Imaginary() - Constructor for class io.github.frc5024.lib5k.utils.RobotPresets.Imaginary
 
IMGUIFieldReporter - Class in io.github.frc5024.lib5k.utils
A tool that hooks into HALSIM to report the robot's simulated position to IMGUI
IMotorCollection - Interface in io.github.frc5024.lib5k.hardware.common.motors.interfaces
Common interface for any collection of motor controllers
IMotorGroupSafety - Interface in io.github.frc5024.lib5k.hardware.common.motors.interfaces
Common interface for groups of motors with safety features
incrementSystemClockOverride(double) - Static method in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.FPGAClock
HIS IS NOT RECOMMENDED UNLESS RUNNING A UNIT TEST.
init() - Method in class io.github.frc5024.lib5k.unittest.FakeScheduler
Called on init
initDrivebaseSimulation(IDifferentialDrivebase) - Method in interface io.github.frc5024.lib5k.hardware.common.sensors.interfaces.ISimGyro
Set up drivebase-locked gyro simulation.
initDrivebaseSimulation(IDifferentialDrivebase) - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedPigeonIMU
 
initDrivebaseSimulation(IDifferentialDrivebase) - Method in class io.github.frc5024.lib5k.hardware.generic.gyroscopes.ADGyro
 
initDrivebaseSimulation(IDifferentialDrivebase) - Method in class io.github.frc5024.lib5k.hardware.kauai.gyroscopes.NavX
Init gyroscope simulation from fusing encoder readings
initDrivebaseSimulation(IDifferentialDrivebase, boolean) - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedPigeonIMU
Init gyroscope simulation from fusing encoder readings
initDrivebaseSimulation(IDifferentialDrivebase, boolean) - Method in class io.github.frc5024.lib5k.hardware.generic.gyroscopes.ADGyro
Init gyroscope simulation from fusing encoder readings
initDrivebaseSimulation(IDifferentialDrivebase, boolean) - Method in class io.github.frc5024.lib5k.hardware.kauai.gyroscopes.NavX
Init gyroscope simulation from fusing encoder readings
initialize() - Method in class io.github.frc5024.common_drive.commands.PathFollowCommand
Deprecated.
 
initialize() - Method in class io.github.frc5024.lib5k.bases.drivetrain.commands.PathFollowerCommand
 
initialize() - Method in class io.github.frc5024.lib5k.bases.drivetrain.commands.TurnToCommand
 
initSendable(SendableBuilder) - Method in class io.github.frc5024.lib5k.control_loops.PID
Deprecated.
This is for use by WPIlib.
initSendable(SendableBuilder) - Method in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
This is for use by WPIlib.
initSendable(SendableBuilder) - Method in class io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver
This method handles interaction with some internal WPIlib services
initSendable(SendableBuilder) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.LinearActuator
 
initSendable(SendableBuilder) - Method in class io.github.frc5024.lib5k.hardware.limelightvision.BaseLimeLight
 
initSendable(SendableBuilder) - Method in class io.github.frc5024.lib5k.hardware.revrobotics.motors.ExtendedSparkMax
 
initSimulationDevice(SpeedController, double, double, double) - Method in interface io.github.frc5024.lib5k.hardware.common.sensors.interfaces.EncoderSimulation
Init simulation for this encoder
initSimulationDevice(SpeedController, double, double, double) - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.CANIfierEncoder
 
initSimulationDevice(SpeedController, double, double, double) - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedCANCoder
 
initSimulationDevice(SpeedController, double, double, double) - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.TalonEncoder
 
initSimulationDevice(SpeedController, double, double, double) - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
 
initSimulationDevice(SpeedController, double, double, double) - Method in class io.github.frc5024.lib5k.hardware.revrobotics.sensors.SparkMaxEncoder
 
initSimulationDevice(SpeedController, int, double, double, double) - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.EncoderBase
Deprecated.
 
InputUtils - Class in io.github.frc5024.lib5k.utils
Utils for working with drive inputs
InputUtils() - Constructor for class io.github.frc5024.lib5k.utils.InputUtils
 
InputUtils.ScalingMode - Enum in io.github.frc5024.lib5k.utils
Scale type / mode
inReverse(boolean) - Method in class io.github.frc5024.common_drive.commands.PathFollowCommand
Deprecated.
Configure reverse path following
inverted - Variable in class io.github.frc5024.lib5k.config.types.JSONEncoder
 
inverted - Variable in class io.github.frc5024.lib5k.config.types.JSONMotor
 
invertSensorPhase - Variable in class io.github.frc5024.common_drive.queue.DriveTrainOutput
Deprecated.
 
io.github.frc5024.asynchal - package io.github.frc5024.asynchal
Asynchronous interfaces for robot I/O
io.github.frc5024.asynchal.sensors - package io.github.frc5024.asynchal.sensors
 
io.github.frc5024.common_drive - package io.github.frc5024.common_drive
Robot-agnostic DriveTrain code.
io.github.frc5024.common_drive.calculation - package io.github.frc5024.common_drive.calculation
 
io.github.frc5024.common_drive.commands - package io.github.frc5024.common_drive.commands
 
io.github.frc5024.common_drive.controller - package io.github.frc5024.common_drive.controller
 
io.github.frc5024.common_drive.gearing - package io.github.frc5024.common_drive.gearing
 
io.github.frc5024.common_drive.queue - package io.github.frc5024.common_drive.queue
 
io.github.frc5024.common_drive.types - package io.github.frc5024.common_drive.types
 
io.github.frc5024.lib5k.autonomous - package io.github.frc5024.lib5k.autonomous
 
io.github.frc5024.lib5k.autonomous.commands - package io.github.frc5024.lib5k.autonomous.commands
 
io.github.frc5024.lib5k.bases.drivetrain - package io.github.frc5024.lib5k.bases.drivetrain
 
io.github.frc5024.lib5k.bases.drivetrain.commands - package io.github.frc5024.lib5k.bases.drivetrain.commands
 
io.github.frc5024.lib5k.bases.drivetrain.implementations - package io.github.frc5024.lib5k.bases.drivetrain.implementations
 
io.github.frc5024.lib5k.config - package io.github.frc5024.lib5k.config
 
io.github.frc5024.lib5k.config.types - package io.github.frc5024.lib5k.config.types
 
io.github.frc5024.lib5k.control_loops - package io.github.frc5024.lib5k.control_loops
Closed-loop controllers
io.github.frc5024.lib5k.control_loops.base - package io.github.frc5024.lib5k.control_loops.base
 
io.github.frc5024.lib5k.control_loops.models - package io.github.frc5024.lib5k.control_loops.models
Mathematical models and datatypes
io.github.frc5024.lib5k.control_loops.statespace - package io.github.frc5024.lib5k.control_loops.statespace
 
io.github.frc5024.lib5k.control_loops.statespace.util.easylqr - package io.github.frc5024.lib5k.control_loops.statespace.util.easylqr
 
io.github.frc5024.lib5k.control_loops.statespace.wrappers - package io.github.frc5024.lib5k.control_loops.statespace.wrappers
 
io.github.frc5024.lib5k.hardware.common.drivebase - package io.github.frc5024.lib5k.hardware.common.drivebase
 
io.github.frc5024.lib5k.hardware.common.motors.interfaces - package io.github.frc5024.lib5k.hardware.common.motors.interfaces
 
io.github.frc5024.lib5k.hardware.common.pdp - package io.github.frc5024.lib5k.hardware.common.pdp
 
io.github.frc5024.lib5k.hardware.common.sensors.interfaces - package io.github.frc5024.lib5k.hardware.common.sensors.interfaces
 
io.github.frc5024.lib5k.hardware.common.sensors.simulation - package io.github.frc5024.lib5k.hardware.common.sensors.simulation
 
io.github.frc5024.lib5k.hardware.ctre.motors - package io.github.frc5024.lib5k.hardware.ctre.motors
 
io.github.frc5024.lib5k.hardware.ctre.motors.collections - package io.github.frc5024.lib5k.hardware.ctre.motors.collections
 
io.github.frc5024.lib5k.hardware.ctre.sensors - package io.github.frc5024.lib5k.hardware.ctre.sensors
 
io.github.frc5024.lib5k.hardware.ctre.util - package io.github.frc5024.lib5k.hardware.ctre.util
 
io.github.frc5024.lib5k.hardware.generic.cameras - package io.github.frc5024.lib5k.hardware.generic.cameras
 
io.github.frc5024.lib5k.hardware.generic.gyroscopes - package io.github.frc5024.lib5k.hardware.generic.gyroscopes
 
io.github.frc5024.lib5k.hardware.generic.ledstrips - package io.github.frc5024.lib5k.hardware.generic.ledstrips
 
io.github.frc5024.lib5k.hardware.generic.motors - package io.github.frc5024.lib5k.hardware.generic.motors
 
io.github.frc5024.lib5k.hardware.generic.motors.motorcollection - package io.github.frc5024.lib5k.hardware.generic.motors.motorcollection
 
io.github.frc5024.lib5k.hardware.generic.pneumatics - package io.github.frc5024.lib5k.hardware.generic.pneumatics
 
io.github.frc5024.lib5k.hardware.generic.sensors - package io.github.frc5024.lib5k.hardware.generic.sensors
 
io.github.frc5024.lib5k.hardware.generic.sensors.interfaces - package io.github.frc5024.lib5k.hardware.generic.sensors.interfaces
 
io.github.frc5024.lib5k.hardware.generic.servos - package io.github.frc5024.lib5k.hardware.generic.servos
 
io.github.frc5024.lib5k.hardware.kauai.gyroscopes - package io.github.frc5024.lib5k.hardware.kauai.gyroscopes
 
io.github.frc5024.lib5k.hardware.limelightvision - package io.github.frc5024.lib5k.hardware.limelightvision
 
io.github.frc5024.lib5k.hardware.limelightvision.products - package io.github.frc5024.lib5k.hardware.limelightvision.products
 
io.github.frc5024.lib5k.hardware.limelightvision.settings - package io.github.frc5024.lib5k.hardware.limelightvision.settings
 
io.github.frc5024.lib5k.hardware.ni.roborio - package io.github.frc5024.lib5k.hardware.ni.roborio
 
io.github.frc5024.lib5k.hardware.ni.roborio.fpga - package io.github.frc5024.lib5k.hardware.ni.roborio.fpga
 
io.github.frc5024.lib5k.hardware.revrobotics.motors - package io.github.frc5024.lib5k.hardware.revrobotics.motors
 
io.github.frc5024.lib5k.hardware.revrobotics.sensors - package io.github.frc5024.lib5k.hardware.revrobotics.sensors
 
io.github.frc5024.lib5k.logging - package io.github.frc5024.lib5k.logging
Tools for logging system data coming from robot controllers and systems
io.github.frc5024.lib5k.math - package io.github.frc5024.lib5k.math
 
io.github.frc5024.lib5k.simulation.systems - package io.github.frc5024.lib5k.simulation.systems
 
io.github.frc5024.lib5k.telemetry - package io.github.frc5024.lib5k.telemetry
Telemetry tools
io.github.frc5024.lib5k.unittest - package io.github.frc5024.lib5k.unittest
 
io.github.frc5024.lib5k.utils - package io.github.frc5024.lib5k.utils
Various FRC-specific tools and utils
io.github.frc5024.lib5k.utils.annotations - package io.github.frc5024.lib5k.utils.annotations
 
io.github.frc5024.lib5k.utils.interfaces - package io.github.frc5024.lib5k.utils.interfaces
 
io.github.frc5024.lib5k.utils.types - package io.github.frc5024.lib5k.utils.types
 
io.github.frc5024.lib5k.vision.types - package io.github.frc5024.lib5k.vision.types
 
io.github.frc5024.libkontrol.statemachines - package io.github.frc5024.libkontrol.statemachines
5024's in-house StateMachine tooling for FRC
io.github.frc5024.purepursuit - package io.github.frc5024.purepursuit
PurePursuit (aka: Rabbit Chase) implementation for FRC
io.github.frc5024.purepursuit.pathgen - package io.github.frc5024.purepursuit.pathgen
Point-to-point path generation tools
io.github.frc5024.purepursuit.util - package io.github.frc5024.purepursuit.util
Utilities for working with point-to-point paths
IRampRateController - Interface in io.github.frc5024.lib5k.hardware.common.motors.interfaces
A common interface for devices with configurable output ramp rates
isAligned() - Method in class ca.retrylife.frc.templates.turrets.ProfiledTurret
 
isAligned() - Method in class ca.retrylife.frc.templates.turrets.TurretBase
Get if the turret is aligned with its goal
isAtGoal() - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Check if the drivetrain is currently done doing its task, and is sitting at it's goal.
isAtGoal() - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
Check if the drivetrain is currently at its goal
isAtGoal() - Method in class io.github.frc5024.lib5k.control_loops.base.ControllerBase
Deprecated.
Check if the system is at it's goal
isAtGoal() - Method in class io.github.frc5024.lib5k.control_loops.base.SettlingController
Deprecated.
 
isBalanced() - Method in class io.github.frc5024.lib5k.vision.types.HyperbolicAxisAlignedBoundingBox
Get if isHorizontalBalanced and isVerticalBalanced are both true
isCalibrated() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.GyroSimUtil
Get if the sensor has been calibrated yet
isDeployed() - Method in class io.github.frc5024.lib5k.hardware.generic.motors.LinearActuator
Get if the actuator is deployed
isFinished() - Method in class io.github.frc5024.common_drive.commands.PathFollowCommand
Deprecated.
 
isFinished() - Method in class io.github.frc5024.lib5k.bases.drivetrain.commands.PathFollowerCommand
 
isFinished() - Method in class io.github.frc5024.lib5k.bases.drivetrain.commands.TurnToCommand
 
isFinished() - Method in class io.github.frc5024.lib5k.unittest.FakeScheduler
Check if the scheduler is finished early
isFinished(double) - Method in class io.github.frc5024.lib5k.control_loops.PID
Deprecated.
Checks if the error is within a reasonable range, then waits a bit before returning completion
isFinished(double) - Method in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Check if the system is finished
isFirstRun() - Method in class io.github.frc5024.libkontrol.statemachines.StateMetadata
Is this the first loop of this action?
isHooked() - Method in class io.github.frc5024.lib5k.utils.IMGUIFieldReporter
Check if this tool has successfully hooked into HALSIM
isHorizontalBalanced() - Method in class io.github.frc5024.lib5k.vision.types.HyperbolicAxisAlignedBoundingBox
Get if the left and right rotations are of equal proportion
ISimGyro - Interface in io.github.frc5024.lib5k.hardware.common.sensors.interfaces
 
isPortAllowedByFMS(int, FMSNetworking.SocketType) - Static method in class io.github.frc5024.lib5k.utils.FMSNetworking
Check if a network port is allowed through the FMS firewall
isUSBAttached() - Static method in class io.github.frc5024.lib5k.utils.FileManagement
Get if the USB stick is plugged in
isVerticalBalanced() - Method in class io.github.frc5024.lib5k.vision.types.HyperbolicAxisAlignedBoundingBox
Get if the top and bottom rotations are of equal proportion
IVoltageOutputController - Interface in io.github.frc5024.lib5k.hardware.common.motors.interfaces
A common interface for devices that can be controlled with a desired output voltage

J

JRADController - Class in io.github.frc5024.lib5k.control_loops
A flywheel velocity controller designed by team 254, adapted and ported for use by team 5024.
JRADController(double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.JRADController
Create a JRAD controller.
JSONEncoder - Class in io.github.frc5024.lib5k.config.types
JSON object for an encoder
JSONEncoder() - Constructor for class io.github.frc5024.lib5k.config.types.JSONEncoder
 
JSONMotor - Class in io.github.frc5024.lib5k.config.types
JSON object for a motor
JSONMotor() - Constructor for class io.github.frc5024.lib5k.config.types.JSONMotor
 
JSONPIDGains - Class in io.github.frc5024.lib5k.config.types
JSON object for PID gains
JSONPIDGains() - Constructor for class io.github.frc5024.lib5k.config.types.JSONPIDGains
 
jsonToPath(File) - Static method in class io.github.frc5024.purepursuit.util.PathImporter
Load a WPILib PathWeaver JSON file as a Lib5K Path

K

kAutonomousRotation - io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain.State
 
kBack - io.github.frc5024.lib5k.bases.drivetrain.Chassis.Side
 
kBrake - io.github.frc5024.common_drive.types.MotorMode
Deprecated.
 
kCoast - io.github.frc5024.common_drive.types.MotorMode
Deprecated.
 
kd - Variable in class io.github.frc5024.lib5k.control_loops.models.PIDProfile
Deprecated.
 
kD - Variable in class io.github.frc5024.common_drive.controller.PDFGains
Deprecated.
 
Kd - Variable in class io.github.frc5024.lib5k.config.types.JSONPIDGains
 
kDebug - io.github.frc5024.lib5k.logging.RobotLogger.Level
 
kDefault - io.github.frc5024.common_drive.types.MotorMode
Deprecated.
 
kDEPLOYED - io.github.frc5024.lib5k.hardware.generic.motors.LinearActuator.ActuatorState
 
kDrivingToPose - io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain.State
 
keepCameraAwake(boolean) - Method in class io.github.frc5024.lib5k.hardware.generic.cameras.AutoCamera
Set the camera connection mode
kEpsilon - Static variable in class io.github.frc5024.lib5k.utils.Consts
 
kFF - Variable in class io.github.frc5024.common_drive.controller.PDFGains
Deprecated.
 
kFF - Variable in class io.github.frc5024.common_drive.controller.PIFGains
Deprecated.
 
kFieldRelative - io.github.frc5024.lib5k.utils.PoseRelation
 
kFront - io.github.frc5024.lib5k.bases.drivetrain.Chassis.Side
 
ki - Variable in class io.github.frc5024.lib5k.control_loops.models.PIDProfile
Deprecated.
 
kI - Variable in class io.github.frc5024.common_drive.controller.PIFGains
Deprecated.
 
Ki - Variable in class io.github.frc5024.lib5k.config.types.JSONPIDGains
 
kINACTIVE - io.github.frc5024.lib5k.hardware.generic.motors.LinearActuator.ActuatorState
 
kInfo - io.github.frc5024.lib5k.logging.RobotLogger.Level
 
kLeft - io.github.frc5024.lib5k.bases.drivetrain.Chassis.Side
 
kLibrary - io.github.frc5024.lib5k.logging.RobotLogger.Level
 
kLocked - io.github.frc5024.common_drive.DriveTrainBase.States
Deprecated.
 
kLowered - ca.retrylife.frc.templates.arms.SensorlessArm.SystemState
 
kNeutral - io.github.frc5024.common_drive.DriveTrainBase.States
Deprecated.
 
kOpenLoop - io.github.frc5024.common_drive.DriveTrainBase.States
Deprecated.
 
kOpenLoopControl - io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain.State
 
kp - Variable in class io.github.frc5024.lib5k.control_loops.models.PIDProfile
Deprecated.
 
kP - Variable in class io.github.frc5024.common_drive.controller.PDFGains
Deprecated.
 
kP - Variable in class io.github.frc5024.common_drive.controller.PIFGains
Deprecated.
 
Kp - Variable in class io.github.frc5024.lib5k.config.types.JSONPIDGains
 
kPivoting - io.github.frc5024.common_drive.DriveTrainBase.States
Deprecated.
 
kPrimary - io.github.frc5024.common_drive.types.ChassisSide
Deprecated.
 
kRabbitChase - io.github.frc5024.common_drive.DriveTrainBase.States
Deprecated.
 
kRaised - ca.retrylife.frc.templates.arms.SensorlessArm.SystemState
 
kRight - io.github.frc5024.lib5k.bases.drivetrain.Chassis.Side
 
kRobot - io.github.frc5024.lib5k.logging.RobotLogger.Level
 
kRobotRelative - io.github.frc5024.lib5k.utils.PoseRelation
 
kSecondary - io.github.frc5024.common_drive.types.ChassisSide
Deprecated.
 
kStopped - ca.retrylife.frc.templates.arms.SensorlessArm.SystemState
 
kWarning - io.github.frc5024.lib5k.logging.RobotLogger.Level
 

L

LARSON_GRAY - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
LARSON_RED - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
lastStateKey - Variable in class io.github.frc5024.libkontrol.statemachines.StateMachine
 
LAUNCHER_DIAMETER - Static variable in class io.github.frc5024.lib5k.utils.RobotPresets.DarthRaider.FlywheelPreset
 
LAUNCHER_MASS_KG - Static variable in class io.github.frc5024.lib5k.utils.RobotPresets.DarthRaider.FlywheelPreset
 
LAWN_GREEN - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
LazySolenoid - Class in io.github.frc5024.lib5k.hardware.generic.pneumatics
Buffer solenoid commands to reduce CAN spam.
LazySolenoid(int, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.pneumatics.LazySolenoid
Create a LazySolenoid
leftEncoder - Variable in class io.github.frc5024.common_drive.queue.Position
Deprecated.
 
leftEncoderMetres - Variable in class io.github.frc5024.common_drive.queue.DriveTrainSensors
Deprecated.
 
leftShifter - Variable in class io.github.frc5024.common_drive.queue.Position
Deprecated.
 
leftSpeed - Variable in class io.github.frc5024.common_drive.queue.Position
Deprecated.
 
leftVoltage - Variable in class io.github.frc5024.common_drive.queue.DriveTrainOutput
Deprecated.
 
LIB5K_TO_WPILIB_COORDINATE_TRANSFORM - Static variable in class io.github.frc5024.lib5k.utils.FRCFieldConstants
 
LIME - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
LimeLight1 - Class in io.github.frc5024.lib5k.hardware.limelightvision.products
Client for the LimeLight version 1.0
LimeLight1(NetworkTable, String) - Constructor for class io.github.frc5024.lib5k.hardware.limelightvision.products.LimeLight1
Create a LimeLight1 client
LimeLight1(String) - Constructor for class io.github.frc5024.lib5k.hardware.limelightvision.products.LimeLight1
Create a LimeLight1 client using the default NT table "limelight"
LimeLight1(String, String) - Constructor for class io.github.frc5024.lib5k.hardware.limelightvision.products.LimeLight1
Create a LimeLight1 client
LimeLight2 - Class in io.github.frc5024.lib5k.hardware.limelightvision.products
Client for the LimeLight version 2.0 and 2+
LimeLight2(NetworkTable, String) - Constructor for class io.github.frc5024.lib5k.hardware.limelightvision.products.LimeLight2
Create a LimeLight2 client
LimeLight2(String) - Constructor for class io.github.frc5024.lib5k.hardware.limelightvision.products.LimeLight2
Create a LimeLight2 client using the default NT table "limelight"
LimeLight2(String, String) - Constructor for class io.github.frc5024.lib5k.hardware.limelightvision.products.LimeLight2
Create a LimeLight2 client
LimeLightLEDMode - Enum in io.github.frc5024.lib5k.hardware.limelightvision.settings
Limelight LED mode setting
LimeLightOperationMode - Enum in io.github.frc5024.lib5k.hardware.limelightvision.settings
Limelight operation mode setting
LimeLightStreamMode - Enum in io.github.frc5024.lib5k.hardware.limelightvision.settings
Limelight stream mode setting
LimitSwitch - Class in io.github.frc5024.lib5k.hardware.generic.sensors
 
LimitSwitch(int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.LimitSwitch
Create a digital Limit Switch sensor object
LINEAR - io.github.frc5024.lib5k.utils.InputUtils.ScalingMode
 
LinearActuator - Class in io.github.frc5024.lib5k.hardware.generic.motors
PCM-Powered Linear actuator
LinearActuator(int, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.motors.LinearActuator
Create a Linear Actuator that is powered via a Pneumatic Control Module
LinearActuator.ActuatorState - Enum in io.github.frc5024.lib5k.hardware.generic.motors
 
LineBreak - Class in io.github.frc5024.lib5k.hardware.generic.sensors
 
LineBreak(int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.LineBreak
Create a Line Break sensor object for a sensor that is powered via an external source
LineBreak(int, int, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.LineBreak
Create a Line Break sensor object for a sensor that is powered via a Pneumatic Control Module
LineBreak(int, Solenoid) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.LineBreak
Create a Line Break sensor object for a sensor that is powered via a Pneumatic Control Module
loadJsonConfig(String) - Method in class io.github.frc5024.lib5k.hardware.generic.cameras.AutoCamera
Load a json file as a config
log(String, RobotLogger.Level, Object...) - Method in class io.github.frc5024.lib5k.logging.RobotLogger
Write a log message to the logfile and message buffer.
log(String, Object...) - Method in class io.github.frc5024.lib5k.logging.RobotLogger
Write a log message to the logfile and message buffer.
log(String, String) - Method in class io.github.frc5024.lib5k.logging.RobotLogger
Deprecated.
log(String, String, RobotLogger.Level) - Method in class io.github.frc5024.lib5k.logging.RobotLogger
Deprecated.
LogCommand - Class in io.github.frc5024.lib5k.autonomous.commands
A command that will simply log a pre-set message to the console when run
LogCommand(String) - Constructor for class io.github.frc5024.lib5k.autonomous.commands.LogCommand
A command that will simply log a pre-set message to the console when run
LogCommand(String, String) - Constructor for class io.github.frc5024.lib5k.autonomous.commands.LogCommand
A command that will simply log a pre-set message to the console when run
Loggable - Interface in io.github.frc5024.lib5k.logging
Common interface for components that can be logged
logger - Variable in class io.github.frc5024.lib5k.autonomous.RobotProgram
 
logger - Variable in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
 
logStatus() - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
Log all component data with RobotLogger
logStatus() - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.VictorSPXCollection
Deprecated.
Log all component data with RobotLogger
logStatus() - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.MixedMotorCollection
Deprecated.
 
logStatus() - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.SparkCollection
Deprecated.
 
logStatus() - Method in class io.github.frc5024.lib5k.hardware.generic.pneumatics.LazySolenoid
 
logStatus() - Method in interface io.github.frc5024.lib5k.logging.Loggable
Log component status
lookAt(Rotation2d) - Method in class ca.retrylife.frc.templates.turrets.ProfiledTurret
 
lookAt(Rotation2d) - Method in class ca.retrylife.frc.templates.turrets.TurretBase
Tell the turret to look at a robot-relative angle
lookAt(Translation2d) - Method in class ca.retrylife.frc.templates.turrets.TurretBase
Tell the turret to look at a robot-relative point in space, where (1,1) is 45 degrees
LOW - io.github.frc5024.common_drive.gearing.Gear
 
lowGearRatio - Variable in class io.github.frc5024.common_drive.DriveTrainConfig
Deprecated.
 

M

m_controller - Variable in class io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver
 
m_path - Variable in class io.github.frc5024.purepursuit.Follower
 
makeSlave(int) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedTalonFX
Make a slave of this controller
makeSlave(int) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedTalonSRX
Make a slave of this controller
makeSlave(int) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedVictorSPX
Make a slave of this controller
makeSlave(int) - Method in class io.github.frc5024.lib5k.hardware.revrobotics.motors.ExtendedSparkMax
Make a slave of this motor
makeSlave(int, boolean) - Method in class io.github.frc5024.lib5k.hardware.revrobotics.motors.ExtendedSparkMax
Make a slave of this motor
MAXIMUM_BUS_VOLTAGE - Static variable in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.RR_HAL
 
maxSpeedPercent - Variable in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
 
Measurement - Class in io.github.frc5024.lib5k.utils
 
Measurement() - Constructor for class io.github.frc5024.lib5k.utils.Measurement
 
MILLISECONDS - io.github.frc5024.lib5k.utils.TimeScale.Mode
 
MiniBot() - Constructor for class io.github.frc5024.lib5k.utils.RobotPresets.MiniBot
 
MixedMotorCollection - Class in io.github.frc5024.lib5k.hardware.generic.motors.motorcollection
Deprecated.
MixedMotorCollection(SpeedController, SpeedController...) - Constructor for class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.MixedMotorCollection
Deprecated.
 
MockDigitalInput - Class in io.github.frc5024.lib5k.hardware.generic.sensors
For mocking a digital input in tests
MockDigitalInput(int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.sensors.MockDigitalInput
Create a MockDigitalInput
MockSpeedController - Class in io.github.frc5024.lib5k.hardware.generic.motors
For mocking a speed controller in tests
MockSpeedController() - Constructor for class io.github.frc5024.lib5k.hardware.generic.motors.MockSpeedController
 
mode(CircularBuffer, int) - Static method in class io.github.frc5024.lib5k.utils.RobotMath
Get the mode of a buffer
modify(PIDProfile) - Method in class io.github.frc5024.lib5k.control_loops.models.PIDProfile
Deprecated.
Modify the profile
MOTD - Class in io.github.frc5024.lib5k.hardware.ni.roborio
 
MOTD() - Constructor for class io.github.frc5024.lib5k.hardware.ni.roborio.MOTD
 
MOTOR_TYPE - Static variable in class io.github.frc5024.lib5k.utils.RobotPresets.DarthRaider.FlywheelPreset
 
MOTOR_TYPE - Static variable in class io.github.frc5024.lib5k.utils.RobotPresets.Imaginary.ElevatorPreset
 
motorMode - Variable in class io.github.frc5024.common_drive.queue.DriveTrainOutput
Deprecated.
 
MotorMode - Enum in io.github.frc5024.common_drive.types
Deprecated, for removal: This API element is subject to removal in a future version.
motorRamp - Variable in class io.github.frc5024.common_drive.queue.DriveTrainOutput
Deprecated.
 
motorType - Variable in class io.github.frc5024.lib5k.hardware.revrobotics.motors.RevConfig
 

N

name - Variable in enum io.github.frc5024.lib5k.logging.RobotLogger.Level
 
name - Variable in class io.github.frc5024.purepursuit.pathgen.Path
 
NavX - Class in io.github.frc5024.lib5k.hardware.kauai.gyroscopes
A wrapper for the AHRS / NavX gyroscope This wrapper adds support for gyro simulation, and adds some lib5k-specific methods
NavX() - Constructor for class io.github.frc5024.lib5k.hardware.kauai.gyroscopes.NavX
Connect to a NavX on the MXP port
NavX(SPI.Port) - Constructor for class io.github.frc5024.lib5k.hardware.kauai.gyroscopes.NavX
Connect to a NavX
NO_ROTATION - Static variable in class io.github.frc5024.lib5k.vision.types.Contour
 
NO_SHIFTER - io.github.frc5024.common_drive.types.ShifterType
 
normalize() - Method in class io.github.frc5024.lib5k.utils.types.DifferentialVoltages
Normalize the voltages below the maximum robot bus voltage.
normalize(DifferentialDriveWheelSpeeds) - Static method in class io.github.frc5024.common_drive.calculation.DifferentialDriveCalculation
Deprecated.
Normalize a percent output DriveSignal
note() - Method in annotation type io.github.frc5024.lib5k.utils.annotations.Tested
A note about testing

O

ObjectCounter - Class in io.github.frc5024.lib5k.utils
A helper for counting the number of an object that exists
ObjectCounter() - Constructor for class io.github.frc5024.lib5k.utils.ObjectCounter
Create an ObjectCounter with a count of 0
ObjectCounter(int) - Constructor for class io.github.frc5024.lib5k.utils.ObjectCounter
Create an object counter with a specific starting count
OFF - io.github.frc5024.lib5k.hardware.generic.cameras.USBVisionCamera.LEDMode
 
OFF - io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightLEDMode
 
ON - io.github.frc5024.lib5k.hardware.generic.cameras.USBVisionCamera.LEDMode
 
ON - io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightLEDMode
 
OpenLoopTankDriveTrain - Class in io.github.frc5024.lib5k.bases.drivetrain.implementations
OpenLoopTankDriveTrain is a TankDriveTrain implementation that can only be controlled manually.
OpenLoopTankDriveTrain() - Constructor for class io.github.frc5024.lib5k.bases.drivetrain.implementations.OpenLoopTankDriveTrain
Create a OpenLoopTankDriveTrain
ORANGE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
overlaps(AxisAlignedBoundingBox) - Method in class io.github.frc5024.lib5k.vision.types.AxisAlignedBoundingBox
 
overlaps(AxisAlignedBoundingBox) - Method in class io.github.frc5024.lib5k.vision.types.Contour
Check if this contour overlaps with an AxisAlignedBoundingBox
overrideCalculationOutput(Double) - Method in class io.github.frc5024.lib5k.utils.TimeScale
Deprecated.

P

Path - Class in io.github.frc5024.purepursuit.pathgen
A "Path" is a list of closely spaces points in space for a robot to follow.
Path(double, Translation2d...) - Constructor for class io.github.frc5024.purepursuit.pathgen.Path
Create a motion path from points
Path(Translation2d...) - Constructor for class io.github.frc5024.purepursuit.pathgen.Path
Create a motion path from points
PathFollowCommand - Class in io.github.frc5024.common_drive.commands
Deprecated, for removal: This API element is subject to removal in a future version.
PathFollowCommand(DriveTrainBase, Path, double) - Constructor for class io.github.frc5024.common_drive.commands.PathFollowCommand
Deprecated.
Create a PathFollowCommand.
PathFollowerCommand - Class in io.github.frc5024.lib5k.bases.drivetrain.commands
PathFollowCommand is a CommandBase object generated by AbstractDriveTrain, and can be used to follow paths with the drivetrain.
PathFollowerCommand(AbstractDriveTrain, Path, double) - Constructor for class io.github.frc5024.lib5k.bases.drivetrain.commands.PathFollowerCommand
Create a PathFollowCommand.
pathGenStartTimeMs - Variable in class io.github.frc5024.purepursuit.pathgen.Path
 
pathGenTimeMs - Variable in class io.github.frc5024.purepursuit.pathgen.Path
 
PathImporter - Class in io.github.frc5024.purepursuit.pathgen
Deprecated, for removal: This API element is subject to removal in a future version.
PathImporter - Class in io.github.frc5024.purepursuit.util
The PathImporter is a tool for importing Paths from config files
PathImporter() - Constructor for class io.github.frc5024.purepursuit.pathgen.PathImporter
Deprecated.
 
PathImporter() - Constructor for class io.github.frc5024.purepursuit.util.PathImporter
 
pathingRampSeconds - Variable in class io.github.frc5024.common_drive.DriveTrainConfig
Deprecated.
 
PDFController - Class in io.github.frc5024.common_drive.controller
Deprecated, for removal: This API element is subject to removal in a future version.
PDFController(PDFGains, boolean) - Constructor for class io.github.frc5024.common_drive.controller.PDFController
Deprecated.
Create a PDFController
PDFGains - Class in io.github.frc5024.common_drive.controller
Deprecated, for removal: This API element is subject to removal in a future version.
PDFGains(double, double) - Constructor for class io.github.frc5024.common_drive.controller.PDFGains
Deprecated.
Create gains for a PDF controller
PDFGains(double, double, double) - Constructor for class io.github.frc5024.common_drive.controller.PDFGains
Deprecated.
Create gains for a PDF controller
peakAmps - Variable in class io.github.frc5024.lib5k.hardware.ctre.motors.CTREConfig
 
performCurrentLimits() - Method in class io.github.frc5024.lib5k.hardware.common.pdp.CurrentLimitManager
Runs the current limit for all active current limit
periodic() - Method in class ca.retrylife.frc.templates.arms.SensorlessArm
 
periodic() - Method in class ca.retrylife.frc.templates.turrets.ProfiledTurret
 
periodic() - Method in class ca.retrylife.frc.templates.turrets.TurretBase
 
periodic() - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
 
periodic() - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
 
periodic() - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
 
periodic(boolean) - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
This is run all the time
periodic(double, double, double, double) - Method in class io.github.frc5024.lib5k.unittest.FakeScheduler
Called every loop
PeriodicComponent - Interface in io.github.frc5024.lib5k.utils.interfaces
Common interface for components that require periodic updates
PI - Static variable in class io.github.frc5024.lib5k.utils.Consts
 
PID - Class in io.github.frc5024.lib5k.control_loops
Deprecated, for removal: This API element is subject to removal in a future version.
PID(double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.PID
Deprecated.
PID Constructor
PID(PIDProfile) - Constructor for class io.github.frc5024.lib5k.control_loops.PID
Deprecated.
Create a PID controller using a PIDProfile
PIDProfile - Class in io.github.frc5024.lib5k.control_loops.models
Deprecated, for removal: This API element is subject to removal in a future version.
PIDProfile(double) - Constructor for class io.github.frc5024.lib5k.control_loops.models.PIDProfile
Deprecated.
Create a P profile
PIDProfile(double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.models.PIDProfile
Deprecated.
Create a PI profile
PIDProfile(double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.models.PIDProfile
Deprecated.
Create a PID profile
PIDv2 - Class in io.github.frc5024.lib5k.control_loops
Deprecated, for removal: This API element is subject to removal in a future version.
PIDv2(double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Create a PIDv2 object using gains
PIDv2(PIDProfile) - Constructor for class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Create a PIDv2 object using a PIDProfile
pidWrite(double) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
 
pidWrite(double) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.VictorSPXCollection
Deprecated.
 
pidWrite(double) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.MockSpeedController
 
pidWrite(double) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.MixedMotorCollection
Deprecated.
 
pidWrite(double) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.SparkCollection
Deprecated.
 
PIFController - Class in io.github.frc5024.common_drive.controller
Deprecated, for removal: This API element is subject to removal in a future version.
PIFController(PIFGains, boolean) - Constructor for class io.github.frc5024.common_drive.controller.PIFController
Deprecated.
Create a PIFController
PIFGains - Class in io.github.frc5024.common_drive.controller
Deprecated, for removal: This API element is subject to removal in a future version.
PIFGains(double, double) - Constructor for class io.github.frc5024.common_drive.controller.PIFGains
Deprecated.
Create gains for a PIF controller
PIFGains(double, double, double) - Constructor for class io.github.frc5024.common_drive.controller.PIFGains
Deprecated.
Create gains for a PIF controller
PIP_MAIN - io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightStreamMode
 
PIP_SECONDARY - io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightStreamMode
 
points - Variable in class io.github.frc5024.purepursuit.pathgen.Path
 
Pollable - Interface in io.github.frc5024.asynchal
 
Poller - Class in io.github.frc5024.asynchal
You have been lied to.
portForwardCameraStream(int) - Method in class io.github.frc5024.lib5k.hardware.limelightvision.BaseLimeLight
Port-forward the camera stream through the RoboRIO
pose - Variable in class io.github.frc5024.purepursuit.util.WPI_PathPoint
 
PoseRelation - Enum in io.github.frc5024.lib5k.utils
Relation types
Position - Class in io.github.frc5024.common_drive.queue
Deprecated, for removal: This API element is subject to removal in a future version.
Position() - Constructor for class io.github.frc5024.common_drive.queue.Position
Deprecated.
Create a position of 0
POSITION_EPSILON - Static variable in class io.github.frc5024.lib5k.utils.RobotPresets.Imaginary.ElevatorPreset
 
PressureSensor - Class in io.github.frc5024.lib5k.hardware.revrobotics.sensors
A wrapper for the Rev Robotics Analog Pressure Sensor https://www.revrobotics.com/rev-11-1107/
PressureSensor(int) - Constructor for class io.github.frc5024.lib5k.hardware.revrobotics.sensors.PressureSensor
Construct a pressure sensor.
previousError - Variable in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
 
printFullMOTD() - Static method in class io.github.frc5024.lib5k.hardware.ni.roborio.MOTD
Print an MOTD with some version info
ProfiledTurret - Class in ca.retrylife.frc.templates.turrets
The ProfiledTurret class is to be used to control a turret of any kind.
ProfiledTurret(SpeedController, Supplier<Rotation2d>, ProfiledPIDController, Rotation2d, Rotation2d, Rotation2d) - Constructor for class ca.retrylife.frc.templates.turrets.ProfiledTurret
Create a ProfiledTurret
publishChooser(Sendable) - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
For publishing the chooser (this can be overridden for custom dashboards)
PurePursuitController - Class in io.github.frc5024.purepursuit
A pure pursuit controller implementation
PurePursuitController(Path, double, double, double, double) - Constructor for class io.github.frc5024.purepursuit.PurePursuitController
Create a PurePursuit Controller
PurePursuitController(Path, double, double, double, double, boolean) - Constructor for class io.github.frc5024.purepursuit.PurePursuitController
Create a PurePursuit Controller

R

radians - Variable in class io.github.frc5024.purepursuit.util.WPI_PathPoint.WPI_PathPose.WPI_PathRotation
 
RAINBOW - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
RAINBOW_FOREST - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
RAINBOW_GLITTER - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
RAINBOW_LAVA - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
RAINBOW_OCEAN - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
RAINBOW_PARTY - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
RangeFinderElevatorController - Class in io.github.frc5024.lib5k.control_loops.statespace.wrappers
This is a wrapper around a state space plant, observer, motion profiling, and LQR.
RangeFinderElevatorController(DCBrushedMotor, double, double, double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.statespace.wrappers.RangeFinderElevatorController
Create a RangeFinderElevatorController
RangeFinderElevatorController(DCBrushedMotor, double, double, double, double, double, double, double, double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.statespace.wrappers.RangeFinderElevatorController
Create a RangeFinderElevatorController
rawIsAtGoal() - Method in class io.github.frc5024.lib5k.control_loops.base.SettlingController
Deprecated.
Check if the system is at it's goal without waiting for the timer
RawPath - Class in io.github.frc5024.purepursuit.pathgen
The RawPath class lets you define Paths completely manually.
RawPath(Translation2d...) - Constructor for class io.github.frc5024.purepursuit.pathgen.RawPath
Create a raw path from a pre-generated list of points
readFile(String) - Static method in class io.github.frc5024.lib5k.utils.FileUtils
Reads a file, and returns it's contents as a UTF8 string
readInputs() - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Get all sensor readings that the base needs
User must override this.
REALISTIC_MAX_VELOCITY_RPM - Static variable in class io.github.frc5024.lib5k.utils.RobotPresets.DarthRaider.FlywheelPreset
 
RED - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
RED_ORANGE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
RED_SHOT - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
register(Pollable) - Method in class io.github.frc5024.asynchal.Poller
Register a pollable component
registerAngleCallback(Consumer<Double>) - Method in class io.github.frc5024.asynchal.sensors.AsyncADXRS450_Gyro
Register a callback for changes in gyro angle in degrees.
registerMotionCallback(Runnable, double) - Method in class io.github.frc5024.asynchal.sensors.AsyncADXRS450_Gyro
Register a callback for gyro motion.
registerReleaseCallback(Runnable) - Method in class io.github.frc5024.asynchal.sensors.AsyncDigitalInput
Register a callback function to be run when the input is pulled low
registerTriggerCallback(Runnable) - Method in class io.github.frc5024.asynchal.sensors.AsyncDigitalInput
Register a callback function to be run when the input is pulled high
removeCurrentLimit(CurrentLimit) - Static method in class io.github.frc5024.lib5k.hardware.common.pdp.CurrentLimitManager
 
removeState(T) - Method in class io.github.frc5024.libkontrol.statemachines.StateMachine
Remove a state from the StateMachine
reportFramework(String) - Static method in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.RR_HAL
Report a custom framework via FRCNetComm
reportFRCVersion(String, String) - Static method in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.RR_HAL
Report a custom FRC Version
reportLanguage(String) - Static method in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.RR_HAL
Report a custom programming language via FRCNetComm
reportRobotPosition(Pose2d) - Method in class io.github.frc5024.lib5k.utils.IMGUIFieldReporter
Set the robot's position in IMGUI Simulation
reset() - Method in interface io.github.frc5024.common_drive.controller.BaseController
Deprecated.
Reset the controller
reset() - Method in class io.github.frc5024.common_drive.controller.PDFController
Deprecated.
Reset the controller
reset() - Method in class io.github.frc5024.common_drive.controller.PIFController
Deprecated.
Reset the controller
reset() - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
 
reset() - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.DualPIDTankDriveTrain
 
reset() - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
 
reset() - Method in interface io.github.frc5024.lib5k.control_loops.base.Controller
Reset the controller;
reset() - Method in class io.github.frc5024.lib5k.control_loops.base.ControllerBase
Deprecated.
Reset the controller
reset() - Method in class io.github.frc5024.lib5k.control_loops.base.SettlingController
Deprecated.
 
reset() - Method in class io.github.frc5024.lib5k.control_loops.PID
Deprecated.
Reset the controller
reset() - Method in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Reset the system (effective next cycle)
reset() - Method in class io.github.frc5024.lib5k.control_loops.SlewLimiter
Reset the system (stops accidental movement after a system restart)
reset() - Method in class io.github.frc5024.lib5k.control_loops.TBHController
 
reset() - Method in interface io.github.frc5024.lib5k.hardware.common.sensors.interfaces.CommonEncoder
Reset
reset() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.EncoderSimUtil
Reset the simulation
reset() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.GyroSimUtil
Reset the sensor
reset() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.CANIfierEncoder
 
reset() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedCANCoder
 
reset() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedPigeonIMU
 
reset() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.TalonEncoder
 
reset() - Method in class io.github.frc5024.lib5k.hardware.generic.gyroscopes.ADGyro
 
reset() - Method in class io.github.frc5024.lib5k.hardware.kauai.gyroscopes.NavX
 
reset() - Method in class io.github.frc5024.lib5k.hardware.revrobotics.sensors.SparkMaxEncoder
 
reset() - Method in interface io.github.frc5024.lib5k.utils.interfaces.SafeSystem
Reset everything
reset() - Method in class io.github.frc5024.lib5k.utils.TimeScale
Reset
reset() - Method in class io.github.frc5024.lib5k.utils.Toggle
Reset the current output
reset() - Method in class io.github.frc5024.purepursuit.Follower
Reset the follower
reset() - Method in class io.github.frc5024.purepursuit.PurePursuitController
Reset the controller
reset(double) - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.EncoderElevatorController
Reset the controller
reset(double) - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.RangeFinderElevatorController
Reset the controller
reset(double) - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SimpleFlywheelController
Reset the system
reset(double, double) - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SingleJointedArmController
Reset the controller to a known state
resetEncoders() - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
TO BE OVERRIDDEN BY THE USER.
resetErrorSum() - Method in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Reset the error accumulator
resetInternals() - Method in class io.github.frc5024.lib5k.control_loops.base.ControllerBase
Deprecated.
Override this for controller-specific resets
resetPose(Pose2d) - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
Set a new pose for the robot
resetPose(Pose2d) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
 
restoreFactoryDefaults - Variable in class io.github.frc5024.lib5k.hardware.revrobotics.motors.RevConfig
 
RevConfig - Class in io.github.frc5024.lib5k.hardware.revrobotics.motors
 
RevConfig(CANSparkMaxLowLevel.MotorType) - Constructor for class io.github.frc5024.lib5k.hardware.revrobotics.motors.RevConfig
Creates a default Rev Motor Config
RevConfig(CANSparkMaxLowLevel.MotorType, boolean) - Constructor for class io.github.frc5024.lib5k.hardware.revrobotics.motors.RevConfig
Creates a Rev Motor Config with configurable inversion
RevConfig(CANSparkMaxLowLevel.MotorType, boolean, boolean, int, int, int, boolean) - Constructor for class io.github.frc5024.lib5k.hardware.revrobotics.motors.RevConfig
Creates a Configuable Motor Config
RevConfig(CANSparkMaxLowLevel.MotorType, boolean, int, int, int) - Constructor for class io.github.frc5024.lib5k.hardware.revrobotics.motors.RevConfig
Creates a Rev Motor Config with configurable current limiting settings
RevMotorFactory - Class in io.github.frc5024.lib5k.hardware.revrobotics.motors
A class for making rev Motors
rightEncoder - Variable in class io.github.frc5024.common_drive.queue.Position
Deprecated.
 
rightEncoderMetres - Variable in class io.github.frc5024.common_drive.queue.DriveTrainSensors
Deprecated.
 
rightShifter - Variable in class io.github.frc5024.common_drive.queue.Position
Deprecated.
 
rightSpeed - Variable in class io.github.frc5024.common_drive.queue.Position
Deprecated.
 
rightVoltage - Variable in class io.github.frc5024.common_drive.queue.DriveTrainOutput
Deprecated.
 
rip() - Method in class io.github.frc5024.lib5k.hardware.generic.servos.SmartServo
Make the servo spin forever
robotInit() - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
 
RobotLogger - Class in io.github.frc5024.lib5k.logging
A threaded logger for use by all robot functions
RobotLogger.Level - Enum in io.github.frc5024.lib5k.logging
Log level The kRobot level will immediately push to the console, everything else is queued until the next notifier cycle
RobotMath - Class in io.github.frc5024.lib5k.utils
RobotMath is an extension of MathUtils, with some overloads for robot-specific datatypes (the ewmath library is designed for general use, so excludes these functions)
RobotMath() - Constructor for class io.github.frc5024.lib5k.utils.RobotMath
 
robotPeriodic() - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
 
RobotPresets - Class in io.github.frc5024.lib5k.utils
Robot presets are known measurement taken from various robots.
RobotPresets() - Constructor for class io.github.frc5024.lib5k.utils.RobotPresets
 
RobotPresets.DarthRaider - Class in io.github.frc5024.lib5k.utils
Preset constants for 5024's Darth Raider
RobotPresets.DarthRaider.FlywheelPreset - Class in io.github.frc5024.lib5k.utils
Characteristics of Darth Raider's flywheel
RobotPresets.Imaginary - Class in io.github.frc5024.lib5k.utils
Preset constants for and imaginary, but realistic robot
RobotPresets.Imaginary.ElevatorPreset - Class in io.github.frc5024.lib5k.utils
Characteristics of Imaginary's elevator
RobotPresets.MiniBot - Class in io.github.frc5024.lib5k.utils
Preset constants for 5024's MiniBot
RobotProgram - Class in io.github.frc5024.lib5k.autonomous
RobotProgram is the base class for all robot programs.
RobotProgram(boolean, boolean) - Constructor for class io.github.frc5024.lib5k.autonomous.RobotProgram
Create a robot program
RobotProgram(boolean, boolean, ShuffleboardTab) - Constructor for class io.github.frc5024.lib5k.autonomous.RobotProgram
Create a robot program
robotRadius - Variable in class io.github.frc5024.common_drive.DriveTrainConfig
Deprecated.
 
robotWidth - Variable in class io.github.frc5024.common_drive.DriveTrainConfig
Deprecated.
 
rotation - Variable in class io.github.frc5024.common_drive.queue.DriveTrainSensors
Deprecated.
 
rotation - Variable in class io.github.frc5024.purepursuit.util.WPI_PathPoint.WPI_PathPose
 
RotationMath - Class in io.github.frc5024.lib5k.math
Utils related to rotational math
RotationMath() - Constructor for class io.github.frc5024.lib5k.math.RotationMath
 
rpmLimit - Variable in class io.github.frc5024.lib5k.hardware.revrobotics.motors.RevConfig
 
RR_HAL - Class in io.github.frc5024.lib5k.hardware.ni.roborio.fpga
Tools for messing with the HAL in questionable ways.
RR_HAL() - Constructor for class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.RR_HAL
 
run() - Method in class io.github.frc5024.lib5k.unittest.FakeScheduler
 
run(PowerDistributionPanel) - Method in class io.github.frc5024.lib5k.hardware.common.pdp.CurrentLimit
This is run by the CurrentLimitManager and shouldn't normally be used
runIteration() - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Run a thread iteration
runIteration() - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
TO BE OVERRIDDEN BY THE USER.

S

SafeNotifier - Class in io.github.frc5024.lib5k.hardware.ni.roborio.fpga
SafeNotifier is a wrapper around the system Notifier with some extra error handling built in.
SafeNotifier(String, double, Runnable) - Constructor for class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.SafeNotifier
/** Create a SafeNotifier with a custom period
SafeNotifier(String, Runnable) - Constructor for class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.SafeNotifier
Create a SafeNotifier with a period of 20ms
SafeSystem - Interface in io.github.frc5024.lib5k.utils.interfaces
A system with safety stops
save() - Method in class io.github.frc5024.lib5k.unittest.Grapher
Save this graph to disk
saveAndLogGenerationTime() - Method in class io.github.frc5024.purepursuit.pathgen.Path
Logs how long path gen took
scale(double, InputUtils.ScalingMode) - Static method in class io.github.frc5024.lib5k.utils.InputUtils
Scale a value
SECONDS - io.github.frc5024.lib5k.utils.TimeScale.Mode
 
semiConstCurve(double, double) - Static method in class io.github.frc5024.common_drive.calculation.DifferentialDriveCalculation
Deprecated.
Calculate a percent motor output from speed and rotation inputs using "semi-constant curvature" calculation
SENSOR_GEAR_RATIO - Static variable in class io.github.frc5024.lib5k.utils.RobotPresets.DarthRaider.FlywheelPreset
 
SensorlessArm - Class in ca.retrylife.frc.templates.arms
The SensorlessArm class is designed to control any type of arm that does not have a rotational sensor (like an encoder or potentiometer).
SensorlessArm(SpeedController, DigitalInput, DigitalInput, double, double) - Constructor for class ca.retrylife.frc.templates.arms.SensorlessArm
Create a SensorlessArm
SensorlessArm.SystemState - Enum in ca.retrylife.frc.templates.arms
 
set(boolean) - Method in class io.github.frc5024.lib5k.hardware.generic.pneumatics.LazySolenoid
Set the value of a solenoid, but reduce CAN spam by only sending new data
set(boolean) - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.MockDigitalInput
Set the sensor state
set(double) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
 
set(double) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.VictorSPXCollection
Deprecated.
 
set(double) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.MockSpeedController
 
set(double) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.MixedMotorCollection
Deprecated.
 
set(double) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.SparkCollection
Deprecated.
 
set(double) - Method in class io.github.frc5024.lib5k.hardware.generic.servos.SmartServo
 
set(double) - Method in class io.github.frc5024.lib5k.hardware.revrobotics.motors.ExtendedSparkMax
 
set(BlinkinDriver.LEDSetting) - Method in class io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver
Set the LED driver to a specific setting
set(LinearActuator.ActuatorState) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.LinearActuator
Set the actuator state
setActivePipeline(int) - Method in class io.github.frc5024.lib5k.hardware.limelightvision.BaseLimeLight
Switch to a new image processing pipeline
setActiveSide(ChassisSide) - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Set which side of the drivetrain to treat as the "front"
setAngle(double) - Method in class io.github.frc5024.lib5k.hardware.generic.servos.SmartServo
 
setBrake - Variable in class io.github.frc5024.lib5k.hardware.ctre.motors.CTREConfig
 
setBuffer(double) - Method in interface io.github.frc5024.lib5k.hardware.common.motors.interfaces.IMotorCollection
Only set on new data
setBuffer(double) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
 
setBuffer(double) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.VictorSPXCollection
Deprecated.
 
setBuffer(double) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.MixedMotorCollection
Deprecated.
 
setBuffer(double) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.SparkCollection
Deprecated.
 
setCompensation(boolean) - Method in interface io.github.frc5024.lib5k.hardware.common.motors.interfaces.ICurrentController
Set if voltage compensation should be enabled
setCompensation(boolean) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
Set if voltage compensation should be enabled
setConsoleHook(Consumer<String>) - Method in class io.github.frc5024.libkontrol.statemachines.StateMachine
Deprecated, for removal: This API element is subject to removal in a future version.
setCurrentLimit - Variable in class io.github.frc5024.lib5k.hardware.ctre.motors.CTREConfig
 
setCurrentLimit - Variable in class io.github.frc5024.lib5k.hardware.revrobotics.motors.RevConfig
 
setCurrentLimit(int, int, int, int) - Method in interface io.github.frc5024.lib5k.hardware.common.motors.interfaces.ICurrentController
Configure a current limiting
setCurrentLimit(int, int, int, int) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
 
setDefaultAutonomous(AutonomousSequence) - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
Set the default autonomous sequence
setDefaultState(T, Consumer<StateMetadata<T>>) - Method in class io.github.frc5024.libkontrol.statemachines.StateMachine
Add a state to the StateMachine, and set it as the default.
setDesiredAngle(double) - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SingleJointedArmController
Set the desired arm angle
setDesiredHeight(double) - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.EncoderElevatorController
Set the elevator's desired height
setDesiredPosition(SensorlessArm.SystemState) - Method in class ca.retrylife.frc.templates.arms.SensorlessArm
Set the desired position for the arm
setDesiredVelocity(double) - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SimpleFlywheelController
Set the desired velocity
setEnabled(boolean) - Method in class io.github.frc5024.lib5k.control_loops.TimedSlewLimiter
Enable or disable the system
setEnabled(boolean) - Method in class io.github.frc5024.lib5k.telemetry.FlywheelTuner
Set the system enable
setEncodersInverted(boolean) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
TO BE OVERRIDDEN BY THE USER.
setEpsilon(double) - Method in interface io.github.frc5024.lib5k.control_loops.base.Controller
Set the acceptable error for the system.
setEpsilon(double) - Method in class io.github.frc5024.lib5k.control_loops.base.ControllerBase
Deprecated.
Set acceptable error around goal
setEpsilon(double) - Method in class io.github.frc5024.lib5k.control_loops.ExtendedPIDController
 
setEpsilon(double) - Method in class io.github.frc5024.lib5k.control_loops.TBHController
 
setFrontSide(Chassis.Side) - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
Set which side of the chassis is the "front".
setFrontSide(Chassis.Side) - Method in class io.github.frc5024.lib5k.bases.drivetrain.commands.PathFollowerCommand
Configure path following side
setFrontSide(Chassis.Side) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
 
setGain(double) - Method in class io.github.frc5024.lib5k.control_loops.TBHController
Set the controller gain
setGains(double, double, double) - Method in class io.github.frc5024.lib5k.control_loops.PID
Deprecated.
Change the P, I and D gains on the fly.
setGains(PIDProfile) - Method in class io.github.frc5024.lib5k.control_loops.PID
Deprecated.
Set PID gains with a PIDProfile
setGear(Gear) - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Set what gearing the drivetrain should be using.
setGoal(double) - Method in class io.github.frc5024.lib5k.control_loops.base.ControllerBase
Deprecated.
Set the system goal
setGoalHeading(Rotation2d, Rotation2d) - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
Set a field-relative heading for the robot to face, and immediately start facing it.
setGoalHeading(Rotation2d, Rotation2d) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.OpenLoopTankDriveTrain
 
setGoalPose(Pose2d, Translation2d) - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
Set a goal pose for the robot to be at, and immediately start driving to it.
setGoalPose(Pose2d, Translation2d) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.OpenLoopTankDriveTrain
 
setGoalPose(Translation2d, Translation2d) - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
Set a goal pose for the robot to be at, and immediately start driving to it.
setGoalPose(Translation2d, Translation2d) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.OpenLoopTankDriveTrain
 
setInverted(boolean) - Method in interface io.github.frc5024.lib5k.hardware.common.sensors.interfaces.IGyroscope
Set if angle readings should be flipped
setInverted(boolean) - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.EncoderSimUtil
Set if the encoder is inverted
setInverted(boolean) - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.GyroSimUtil
Set if the sensor is inverted
setInverted(boolean) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
 
setInverted(boolean) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.VictorSPXCollection
Deprecated.
 
setInverted(boolean) - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedPigeonIMU
 
setInverted(boolean) - Method in class io.github.frc5024.lib5k.hardware.generic.gyroscopes.ADGyro
 
setInverted(boolean) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.MockSpeedController
 
setInverted(boolean) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.MixedMotorCollection
Deprecated.
 
setInverted(boolean) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.SparkCollection
Deprecated.
 
setInverted(boolean) - Method in class io.github.frc5024.lib5k.hardware.kauai.gyroscopes.NavX
 
setIRange(double) - Method in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Get the integrator range
setLED(boolean) - Method in class io.github.frc5024.lib5k.hardware.generic.cameras.USBVisionCamera
Enable or disable the LEDRing around the camera
setLED(USBVisionCamera.LEDMode) - Method in class io.github.frc5024.lib5k.hardware.generic.cameras.USBVisionCamera
Set the LEDRing mode
setLEDMode(LimeLightLEDMode) - Method in class io.github.frc5024.lib5k.hardware.limelightvision.BaseLimeLight
Set the LimeLight LED mode
setLookaheadDistance(double) - Method in class io.github.frc5024.purepursuit.Follower
Set the lookahead distance
setLookaheadGain(double) - Method in class io.github.frc5024.purepursuit.Follower
Set the max area around the lookahead to accept pose deviation.
setMasterMotorSafety(boolean) - Method in interface io.github.frc5024.lib5k.hardware.common.motors.interfaces.IMotorGroupSafety
Set the motorsafety mode of the master motor controller
setMasterMotorSafety(boolean) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
 
setMasterMotorSafety(boolean) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.VictorSPXCollection
Deprecated.
 
setMaxSpeedPercent(double) - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
Set the maximum speed percent
setMaxSpeedPercent(double) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
 
setMinRestTime(double) - Method in class io.github.frc5024.lib5k.control_loops.base.SettlingController
Deprecated.
Set the amount of time the system must be stable for in order for "is at goal" to be true
setMotorsInverted(boolean) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
TO BE OVERRIDDEN BY THE USER.
setNeutralMode(NeutralMode) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
 
setOpenLoop(double, double) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
Set an open-loop output
setOpenLoop(DifferentialVoltages) - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
Set an open-loop output
setOperationMode(LimeLightOperationMode) - Method in class io.github.frc5024.lib5k.hardware.limelightvision.BaseLimeLight
Set the camera operation mode
setOutputConstraints(double) - Method in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Set a maximum output value
setOutputConstraints(double, double) - Method in class io.github.frc5024.lib5k.control_loops.PID
Deprecated.
Set constraints on PID output.
setOutputConstraints(double, double) - Method in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Set both a maximum, and minimum output value
setPhaseInverted(boolean) - Method in interface io.github.frc5024.lib5k.hardware.common.sensors.interfaces.CommonEncoder
Set the phase of the encoder so that it is set to be in phase with the motor itself.
setPhaseInverted(boolean) - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.CANIfierEncoder
 
setPhaseInverted(boolean) - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedCANCoder
 
setPhaseInverted(boolean) - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.TalonEncoder
 
setPhaseInverted(boolean) - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
 
setPhaseInverted(boolean) - Method in class io.github.frc5024.lib5k.hardware.revrobotics.sensors.SparkMaxEncoder
 
setPose(Pose2d) - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Force-set the drivetrain's pose
setRampRate(double) - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
TO BE OVERRIDDEN BY THE USER.
setRampRate(double) - Method in interface io.github.frc5024.lib5k.hardware.common.motors.interfaces.IRampRateController
Set the controller ramp rate.
setRampRate(double) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
 
setRampRate(double) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.VictorSPXCollection
Deprecated.
 
setRampRate(double) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.MixedMotorCollection
Deprecated.
 
setRampRate(double) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.SparkCollection
Deprecated.
 
setRate(double) - Method in class io.github.frc5024.lib5k.control_loops.SlewLimiter
Re-set the maximum amount of change allowed by the system
setRate(double) - Method in class io.github.frc5024.lib5k.control_loops.TimedSlewLimiter
Set the ramp rate
setReference(double) - Method in interface io.github.frc5024.lib5k.control_loops.base.Controller
Set the reference value.
setReference(double) - Method in class io.github.frc5024.lib5k.control_loops.ExtendedPIDController
 
setReference(double) - Method in class io.github.frc5024.lib5k.control_loops.TBHController
 
setResolution(int, int, int) - Method in class io.github.frc5024.lib5k.hardware.generic.cameras.AutoCamera
Set the camera resolution and framerate
setRestPeriod(int) - Method in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Set the number of cycles the PID controller should wait before declaiming the system "finished"
setSafetyEnabled(boolean) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedTalonSRX
 
setSetpoint(double) - Method in class io.github.frc5024.lib5k.control_loops.JRADController
Set a voltage setpoint for the controller
setSetpoint(double) - Method in class io.github.frc5024.lib5k.control_loops.PID
Deprecated.
Change the target value for the PID controller to reach.
setSetpoint(double) - Method in class io.github.frc5024.lib5k.control_loops.PIDv2
Deprecated.
Set the PID controller's setpoint (goal position)
setSetpoint(double) - Method in class io.github.frc5024.lib5k.telemetry.FlywheelTuner
Set the controller setpoint var
setSpeedCap(double) - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Set a cap on the output speed by percentage
setState(T) - Method in class io.github.frc5024.libkontrol.statemachines.StateMachine
Set the StateMachine's state
setStreamMode(LimeLightStreamMode) - Method in class io.github.frc5024.lib5k.hardware.limelightvision.BaseLimeLight
Set the streaming mode
SettlingController - Class in io.github.frc5024.lib5k.control_loops.base
Deprecated, for removal: This API element is subject to removal in a future version.
SettlingController() - Constructor for class io.github.frc5024.lib5k.control_loops.base.SettlingController
Deprecated.
Create a Settling Controller
settlingTime - Variable in class io.github.frc5024.lib5k.config.types.JSONPIDGains
 
setVoltage(double) - Method in interface io.github.frc5024.lib5k.hardware.common.motors.interfaces.IVoltageOutputController
Set desired controller output in volts.
setVoltage(double) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
 
setVoltage(double) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.VictorSPXCollection
Deprecated.
 
setVoltage(double) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedTalonFX
 
setVoltage(double) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedTalonSRX
 
setVoltage(double) - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.ExtendedVictorSPX
 
setVoltage(double) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.MixedMotorCollection
Deprecated.
 
setVoltage(double) - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.SparkCollection
Deprecated.
 
setVoltage(double) - Method in class io.github.frc5024.lib5k.hardware.revrobotics.motors.ExtendedSparkMax
 
shifterType - Variable in class io.github.frc5024.common_drive.DriveTrainConfig
Deprecated.
 
ShifterType - Enum in io.github.frc5024.common_drive.types
Type of gear shifter
showCamera(boolean) - Method in class io.github.frc5024.lib5k.hardware.generic.cameras.AutoCamera
Set camera visible
SIMPLE_SHIFTER - io.github.frc5024.common_drive.types.ShifterType
 
SimpleFlywheelController - Class in io.github.frc5024.lib5k.control_loops.statespace.wrappers
This is a wrapper around a state space plant, observer, and LQR.
SimpleFlywheelController(DCBrushedMotor, double, double, double, double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SimpleFlywheelController
Create a SimpleFlywheelController
SimpleFlywheelController(DCBrushedMotor, double, double, double, double, double, double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SimpleFlywheelController
Create a SimpleFlywheelController
SimpleFlywheelController(DCBrushedMotor, double, double, double, double, double, double, double, double, double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SimpleFlywheelController
Create a SimpleFlywheelController
simReady() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.EncoderSimUtil
Get if the simulation is ready
simReady() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.GyroSimUtil
Return if simulation is ready
SINELON_1_AND_2 - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
SINELON_FOREST - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
SINELON_LAVA - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
SINELON_OCEAN - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
SINELON_PARTY - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
SINELON_RAINBOW - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
SingleInstanceJSONConfig<T> - Class in io.github.frc5024.lib5k.config
SingleInstanceJSONConfig is a tool for loading a JSON file into a Java object
SingleInstanceJSONConfig(Class<T>) - Constructor for class io.github.frc5024.lib5k.config.SingleInstanceJSONConfig
Create a SingleInstanceJSONConfig with default settings
SingleInstanceJSONConfig(Class<T>, boolean) - Constructor for class io.github.frc5024.lib5k.config.SingleInstanceJSONConfig
Create a SingleInstanceJSONConfig
SingleInstanceJSONConfig(Class<T>, String, boolean) - Constructor for class io.github.frc5024.lib5k.config.SingleInstanceJSONConfig
Create a SingleInstanceJSONConfig
SingleJointedArmController - Class in io.github.frc5024.lib5k.control_loops.statespace.wrappers
This is a wrapper around a state space plant, observer, motion profiling, and LQR.
SingleJointedArmController(DCBrushedMotor, double, double, double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SingleJointedArmController
Create a SingleJointedArmController
SingleJointedArmController(DCBrushedMotor, double, double, double, double, double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SingleJointedArmController
Create a SingleJointedArmController
SingleJointedArmController(DCBrushedMotor, double, double, double, double, double, double, double, double, double, double, double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SingleJointedArmController
Create a SingleJointedArmController
SKY_BLUE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
SlewLimiter - Class in io.github.frc5024.lib5k.control_loops
A tool for smoothing out joystick information (enforces a maximum rate of change)
SlewLimiter(double) - Constructor for class io.github.frc5024.lib5k.control_loops.SlewLimiter
Built a SlewLimier object
SmartServo - Class in io.github.frc5024.lib5k.hardware.generic.servos
A beta wrapper around the Rev Robotics "smart servo".
SmartServo(int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.servos.SmartServo
Create a SmartServo
smooth(ArrayList<Translation2d>, double, double, double) - Static method in class io.github.frc5024.purepursuit.util.Smoothing
This is an algorithm taken from team 2168 to smooth paths
Smoothing - Class in io.github.frc5024.purepursuit.util
 
SmoothPath - Class in io.github.frc5024.purepursuit.pathgen
A smoothed path
SmoothPath(double, double, double, double, Translation2d...) - Constructor for class io.github.frc5024.purepursuit.pathgen.SmoothPath
Create a Smooth Path
SmoothPath(double, double, double, Translation2d...) - Constructor for class io.github.frc5024.purepursuit.pathgen.SmoothPath
Create a Smooth Path
SparkCollection - Class in io.github.frc5024.lib5k.hardware.generic.motors.motorcollection
Deprecated.
SparkCollection(Spark, Spark...) - Constructor for class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.SparkCollection
Deprecated.
 
SPARKLE_1_ON_2 - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
SPARKLE_2_ON_1 - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
SparkMaxEncoder - Class in io.github.frc5024.lib5k.hardware.revrobotics.sensors
 
SparkMaxEncoder(CANSparkMax, EncoderType, int) - Constructor for class io.github.frc5024.lib5k.hardware.revrobotics.sensors.SparkMaxEncoder
Create a SparkMaxEncoder
SQUARED - io.github.frc5024.lib5k.utils.InputUtils.ScalingMode
 
stallLimit - Variable in class io.github.frc5024.lib5k.hardware.revrobotics.motors.RevConfig
 
STANDARD - io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightStreamMode
 
start() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.GyroSimUtil
Start the simulation
start() - Method in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.SafeNotifier
Start the notifier with a pre-configured period.
start(double) - Method in class io.github.frc5024.lib5k.logging.RobotLogger
Start the periodic logger
startPeriodic(double) - Method in class io.github.frc5024.lib5k.hardware.ni.roborio.fpga.SafeNotifier
 
StateHandler<T> - Class in io.github.frc5024.libkontrol.statemachines
 
StateHandler(T, StateMachine<T>, Consumer<StateMetadata<T>>) - Constructor for class io.github.frc5024.libkontrol.statemachines.StateHandler
Create a StateHandler for a given state
stateMachine - Variable in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
 
StateMachine<T> - Class in io.github.frc5024.libkontrol.statemachines
 
StateMachine(String) - Constructor for class io.github.frc5024.libkontrol.statemachines.StateMachine
Create a StateMachine
StateMetadata<T> - Class in io.github.frc5024.libkontrol.statemachines
A container for metadata about a state.
StateMetadata(StateMachine, T, boolean) - Constructor for class io.github.frc5024.libkontrol.statemachines.StateMetadata
Create StateMetadata
StateSpaceSystem - Interface in io.github.frc5024.lib5k.control_loops.statespace
Common interface for a state-space system
stop() - Method in class ca.retrylife.frc.templates.arms.SensorlessArm
Stop the arm
stop() - Method in class ca.retrylife.frc.templates.turrets.ProfiledTurret
 
stop() - Method in class ca.retrylife.frc.templates.turrets.TurretBase
Stop the turret
stop() - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Stop everything
stop() - Method in class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
 
stop() - Method in class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
 
stop() - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SimpleFlywheelController
Stop the flywheel
stop() - Method in class io.github.frc5024.lib5k.hardware.generic.servos.SmartServo
Stop the servo
stop() - Method in interface io.github.frc5024.lib5k.utils.interfaces.SafeSystem
Stop everything
stopMotor() - Method in class io.github.frc5024.lib5k.hardware.generic.motors.MockSpeedController
 
STROBE_BLUE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
STROBE_GOLD - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
STROBE_WHITE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
SystemCharacteristics - Interface in io.github.frc5024.lib5k.control_loops.models
The characteristics of a system

T

TalonEncoder - Class in io.github.frc5024.lib5k.hardware.ctre.sensors
 
TalonEncoder(BaseTalon, int) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.sensors.TalonEncoder
Create a Talon Encoder
TalonHelper - Class in io.github.frc5024.lib5k.hardware.ctre.util
 
TalonHelper() - Constructor for class io.github.frc5024.lib5k.hardware.ctre.util.TalonHelper
 
TalonSRXCollection - Class in io.github.frc5024.lib5k.hardware.ctre.motors.collections
Deprecated.
TalonSRXCollection(WPI_TalonSRX, WPI_TalonSRX...) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
 
TankDriveTrain - Class in io.github.frc5024.lib5k.bases.drivetrain.implementations
TankDriveTrain is an implementation of AbstractDriveTrain for tank-drive robots.
TankDriveTrain() - Constructor for class io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
Create a new TankDriveTrain
TBHController - Class in io.github.frc5024.lib5k.control_loops
A Take-Back-Half controller designed for controlling flywheels.
TBHController(double) - Constructor for class io.github.frc5024.lib5k.control_loops.TBHController
Create a TBHController
TBHController(double, double) - Constructor for class io.github.frc5024.lib5k.control_loops.TBHController
Create a TBHController
TCP - io.github.frc5024.lib5k.utils.FMSNetworking.SocketType
 
team() - Method in annotation type io.github.frc5024.lib5k.utils.annotations.FieldTested
The team that tested this component
team() - Method in annotation type io.github.frc5024.lib5k.utils.annotations.Tested
The team that tested this component
teleop(boolean) - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
This is run during teleop
teleopInit() - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
 
teleopPeriodic() - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
 
test(boolean) - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
This is run during test mode
Tested - Annotation Type in io.github.frc5024.lib5k.utils.annotations
Indicates that a class or method was successfully used by a team on a robot
TestedInSimulation - Annotation Type in io.github.frc5024.lib5k.utils.annotations
Indicates that a class or method was successfully tested in a simulated environment
testInit() - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
 
testPeriodic() - Method in class io.github.frc5024.lib5k.autonomous.RobotProgram
 
ThrottleSteering - Class in io.github.frc5024.lib5k.utils.types
Represents throttle and steering
ThrottleSteering() - Constructor for class io.github.frc5024.lib5k.utils.types.ThrottleSteering
Create a ThrottleSteering of 0,0
ThrottleSteering(double, double) - Constructor for class io.github.frc5024.lib5k.utils.types.ThrottleSteering
Create new ThrottleSteering
time - Variable in class io.github.frc5024.purepursuit.util.WPI_PathPoint
 
TimedSlewLimiter - Class in io.github.frc5024.lib5k.control_loops
An extension of SlewLimiter that acts a bit more like TalonSRX's rampRate setting, and respects non 20ms periods
TimedSlewLimiter(double) - Constructor for class io.github.frc5024.lib5k.control_loops.TimedSlewLimiter
Create a TimedSlewLimiter
timeoutMS - Variable in class io.github.frc5024.lib5k.hardware.ctre.motors.CTREConfig
 
times(double) - Method in class io.github.frc5024.lib5k.utils.types.DifferentialVoltages
Multiply this DifferentialVoltages by a number of volts.
times(DifferentialVoltages) - Method in class io.github.frc5024.lib5k.utils.types.DifferentialVoltages
Multiply this DifferentialVoltages by another DifferentialVoltages object.
TimeScale - Class in io.github.frc5024.lib5k.utils
TimeScale is a utility for calculating time-based scaling values.
TimeScale() - Constructor for class io.github.frc5024.lib5k.utils.TimeScale
Create a TimeScale for Seconds
TimeScale(TimeScale.Mode) - Constructor for class io.github.frc5024.lib5k.utils.TimeScale
Create a TimeScale
TimeScale.Mode - Enum in io.github.frc5024.lib5k.utils
Timing modes
timestamp_ms - Variable in class io.github.frc5024.common_drive.queue.DriveTrainOutput
Deprecated.
 
timestamp_ms - Variable in class io.github.frc5024.common_drive.queue.DriveTrainSensors
Deprecated.
 
toDCMotor() - Method in class io.github.frc5024.lib5k.control_loops.models.DCBrushedMotor
Converts this to a DC motor, for use with WPILib functions
Toggle - Class in io.github.frc5024.lib5k.utils
Used for toggle-based buttons
Toggle() - Constructor for class io.github.frc5024.lib5k.utils.Toggle
 
toString() - Method in class io.github.frc5024.lib5k.utils.types.DifferentialVoltages
 
toString() - Method in class io.github.frc5024.lib5k.vision.types.AxisAlignedBoundingBox
 
toString() - Method in class io.github.frc5024.purepursuit.pathgen.Path
 
translation - Variable in class io.github.frc5024.purepursuit.util.WPI_PathPoint.WPI_PathPose
 
turningController - Variable in class io.github.frc5024.common_drive.DriveTrainConfig
Deprecated.
 
turnTo(Rotation2d, Rotation2d, boolean) - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Turn to an angle
turnTo(Translation2d, Rotation2d) - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Turn to face a field-relative point
TurnToCommand - Class in io.github.frc5024.lib5k.bases.drivetrain.commands
A command for making drivetrains turn to a specific heading.
TurnToCommand(AbstractDriveTrain, Rotation2d, Rotation2d) - Constructor for class io.github.frc5024.lib5k.bases.drivetrain.commands.TurnToCommand
Create a new TurnToCommand
TurnToCommand(AbstractDriveTrain, Rotation2d, Rotation2d, boolean) - Constructor for class io.github.frc5024.lib5k.bases.drivetrain.commands.TurnToCommand
Create a new TurnToCommand
TurnToCommand(AbstractDriveTrain, Rotation2d, Rotation2d, double) - Constructor for class io.github.frc5024.lib5k.bases.drivetrain.commands.TurnToCommand
Create a new TurnToCommand
TurnToCommand(AbstractDriveTrain, Rotation2d, Rotation2d, double, boolean) - Constructor for class io.github.frc5024.lib5k.bases.drivetrain.commands.TurnToCommand
Create a new TurnToCommand
TurretBase - Class in ca.retrylife.frc.templates.turrets
TurretBase is the base class for all turret templates.
TurretBase(Rotation2d, Rotation2d) - Constructor for class ca.retrylife.frc.templates.turrets.TurretBase
Create a TurretBase with a deadzone
TWINKLE_1_AND_2 - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
TWINKLES_FOREST - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
TWINKLES_LAVA - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
TWINKLES_OCEAN - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
TWINKLES_PARTY - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
TWINKLES_RAINBOW - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 

U

UDP - io.github.frc5024.lib5k.utils.FMSNetworking.SocketType
 
Untested - Annotation Type in io.github.frc5024.lib5k.utils.annotations
Indicates that a class or method has not been tested
update() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.EncoderSimUtil
 
update() - Method in class io.github.frc5024.lib5k.hardware.common.sensors.simulation.GyroSimUtil
Update the simulation data
update() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.CANIfierEncoder
 
update() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.ExtendedCANCoder
 
update() - Method in class io.github.frc5024.lib5k.hardware.ctre.sensors.TalonEncoder
 
update() - Method in class io.github.frc5024.lib5k.hardware.generic.cameras.USBVisionCamera
Update the LEDs Must be called in a periodic loop
update() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.EncoderBase
Deprecated.
 
update() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.GenericEncoder
 
update() - Method in class io.github.frc5024.lib5k.hardware.revrobotics.sensors.SparkMaxEncoder
 
update() - Method in class io.github.frc5024.lib5k.telemetry.FlywheelTuner
Update the output
update() - Method in interface io.github.frc5024.lib5k.utils.interfaces.PeriodicComponent
Method to be called periodically.
update() - Method in class io.github.frc5024.libkontrol.statemachines.StateMachine
Update the machine.
update(double) - Method in class io.github.frc5024.lib5k.control_loops.base.ControllerBase
Deprecated.
Update the system measurement, and get new output
update(double, double) - Method in class io.github.frc5024.lib5k.control_loops.base.ControllerBase
Deprecated.
Update the system measurement and goal, and get new output
update(double, double) - Method in class io.github.frc5024.lib5k.control_loops.base.SettlingController
Deprecated.
 
updateTelemetry() - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.TalonSRXCollection
Deprecated.
 
updateTelemetry() - Method in class io.github.frc5024.lib5k.hardware.ctre.motors.collections.VictorSPXCollection
Deprecated.
 
updateTelemetry() - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.MixedMotorCollection
Deprecated.
 
updateTelemetry() - Method in class io.github.frc5024.lib5k.hardware.generic.motors.motorcollection.SparkCollection
Deprecated.
 
updateTelemetry() - Method in class io.github.frc5024.lib5k.hardware.generic.pneumatics.LazySolenoid
 
updateTelemetry() - Method in interface io.github.frc5024.lib5k.logging.Loggable
Push telemetry data to NetworkTables
USBLogger - Class in io.github.frc5024.lib5k.logging
The USBLogger is a class that is used to save a copy of all logs written to RobotLogger to their own file.
USBLogger() - Constructor for class io.github.frc5024.lib5k.logging.USBLogger
Create a USBLogger
USBLogger(String) - Constructor for class io.github.frc5024.lib5k.logging.USBLogger
Deprecated, for removal: This API element is subject to removal in a future version.
USBVisionCamera - Class in io.github.frc5024.lib5k.hardware.generic.cameras
 
USBVisionCamera(String, int, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.cameras.USBVisionCamera
Create a USBVisionCamera To run the camera, you must call the update method in a periodic loop.
USBVisionCamera(String, int, int, int) - Constructor for class io.github.frc5024.lib5k.hardware.generic.cameras.USBVisionCamera
Create a USBVisionCamera To run the camera, you must call the update method in a periodic loop.
USBVisionCamera.LEDMode - Enum in io.github.frc5024.lib5k.hardware.generic.cameras
 

V

validate() - Method in class io.github.frc5024.lib5k.unittest.ConfigValidator
Validate the config
value - Variable in class io.github.frc5024.common_drive.queue.WriteLock
 
valueOf(String) - Static method in enum ca.retrylife.frc.templates.arms.SensorlessArm.SystemState
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.common_drive.DriveTrainBase.States
Deprecated.
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.common_drive.gearing.Gear
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.common_drive.types.ChassisSide
Deprecated.
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.common_drive.types.MotorMode
Deprecated.
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.common_drive.types.ShifterType
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain.State
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.lib5k.bases.drivetrain.Chassis.Side
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.lib5k.hardware.generic.cameras.USBVisionCamera.LEDMode
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.lib5k.hardware.generic.motors.LinearActuator.ActuatorState
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightLEDMode
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightOperationMode
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightStreamMode
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.lib5k.logging.RobotLogger.Level
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.lib5k.utils.FMSNetworking.SocketType
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.lib5k.utils.InputUtils.ScalingMode
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.lib5k.utils.PoseRelation
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum io.github.frc5024.lib5k.utils.TimeScale.Mode
Returns the enum constant of this type with the specified name.
values() - Static method in enum ca.retrylife.frc.templates.arms.SensorlessArm.SystemState
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.common_drive.DriveTrainBase.States
Deprecated.
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.common_drive.gearing.Gear
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.common_drive.types.ChassisSide
Deprecated.
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.common_drive.types.MotorMode
Deprecated.
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.common_drive.types.ShifterType
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain.State
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.lib5k.bases.drivetrain.Chassis.Side
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.lib5k.hardware.generic.cameras.USBVisionCamera.LEDMode
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.lib5k.hardware.generic.motors.LinearActuator.ActuatorState
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightLEDMode
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightOperationMode
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightStreamMode
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.lib5k.logging.RobotLogger.Level
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.lib5k.utils.FMSNetworking.SocketType
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.lib5k.utils.InputUtils.ScalingMode
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.lib5k.utils.PoseRelation
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum io.github.frc5024.lib5k.utils.TimeScale.Mode
Returns an array containing the constants of this enum type, in the order they are declared.
velocity - Variable in class io.github.frc5024.purepursuit.util.WPI_PathPoint
 
VELOCITY_EPSILON - Static variable in class io.github.frc5024.lib5k.utils.RobotPresets.Imaginary.ElevatorPreset
 
VELOCITY_EPSILON_RPM - Static variable in class io.github.frc5024.lib5k.utils.RobotPresets.DarthRaider.FlywheelPreset
 
VictorSPXCollection - Class in io.github.frc5024.lib5k.hardware.ctre.motors.collections
Deprecated.
VictorSPXCollection(WPI_VictorSPX, WPI_VictorSPX...) - Constructor for class io.github.frc5024.lib5k.hardware.ctre.motors.collections.VictorSPXCollection
Deprecated.
 
VIOLET - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
VISION - io.github.frc5024.lib5k.hardware.limelightvision.settings.LimeLightOperationMode
 

W

WAVES_1_AND_2 - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
WAVES_FOREST - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
WAVES_LAVA - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
WAVES_OCEAN - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
WAVES_PARTY - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
WAVES_RAINBOW - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
waypoints - Variable in class io.github.frc5024.purepursuit.pathgen.Path
 
wheelRadius - Variable in class io.github.frc5024.common_drive.DriveTrainConfig
Deprecated.
 
WHITE - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
WHITE_SHOT - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 
withinEpsilon(double) - Method in class io.github.frc5024.lib5k.control_loops.statespace.wrappers.SimpleFlywheelController
Check if a velocity is within epsilon of goal
withLookahead(double) - Method in class io.github.frc5024.common_drive.commands.PathFollowCommand
Deprecated.
A builder-style method for setting the lookahead.
withLookahead(double) - Method in class io.github.frc5024.lib5k.bases.drivetrain.commands.PathFollowerCommand
A builder-style method for setting the lookahead.
withMaxSpeed(double) - Method in class io.github.frc5024.common_drive.commands.PathFollowCommand
Deprecated.
A builder-style method for setting the max speed
withMaxSpeed(double) - Method in class io.github.frc5024.lib5k.bases.drivetrain.commands.PathFollowerCommand
A builder-style method for setting the max speed
WPI_PathPoint - Class in io.github.frc5024.purepursuit.util
This class is the datastructure used to parse WPILib Path json files into something Lib5K understands.
WPI_PathPoint() - Constructor for class io.github.frc5024.purepursuit.util.WPI_PathPoint
 
WPI_PathPoint.WPI_PathPose - Class in io.github.frc5024.purepursuit.util
This class is the datastructure used to denote pose in a WPILib path json file
WPI_PathPoint.WPI_PathPose.WPI_PathRotation - Class in io.github.frc5024.purepursuit.util
 
WPI_PathPoint.WPI_PathPose.WPI_PathTranslation - Class in io.github.frc5024.purepursuit.util
 
WPI_PathPose() - Constructor for class io.github.frc5024.purepursuit.util.WPI_PathPoint.WPI_PathPose
 
WPI_PathRotation() - Constructor for class io.github.frc5024.purepursuit.util.WPI_PathPoint.WPI_PathPose.WPI_PathRotation
 
WPI_PathTranslation() - Constructor for class io.github.frc5024.purepursuit.util.WPI_PathPoint.WPI_PathPose.WPI_PathTranslation
 
wpiAngleTo5k(double) - Static method in class io.github.frc5024.lib5k.utils.RobotMath
Convert from the [-180-180] angles used by WPILib to the [0-360] angles used by lib5k
write - Variable in class io.github.frc5024.common_drive.queue.WriteLock
 
write(T) - Method in class io.github.frc5024.common_drive.queue.WriteLock
Write a value and enable reading
writeln(String) - Method in class io.github.frc5024.lib5k.logging.USBLogger
Write a line to the USB log
WriteLock<T> - Class in io.github.frc5024.common_drive.queue
A dataclass for storing a value, and if it should be written out or not
WriteLock() - Constructor for class io.github.frc5024.common_drive.queue.WriteLock
Create a WriteLock
WriteLock(T) - Constructor for class io.github.frc5024.common_drive.queue.WriteLock
Create a WriteLock with a default value
writeRow(Object...) - Method in class io.github.frc5024.lib5k.logging.CSVFile
Write a row to the file
writeRow(String...) - Method in class io.github.frc5024.lib5k.logging.CSVFile
Write a row to the file

X

x - Variable in class io.github.frc5024.purepursuit.util.WPI_PathPoint.WPI_PathPose.WPI_PathTranslation
 

Y

y - Variable in class io.github.frc5024.purepursuit.util.WPI_PathPoint.WPI_PathPose.WPI_PathTranslation
 
year() - Method in annotation type io.github.frc5024.lib5k.utils.annotations.FieldTested
The year this component was tested
YELLOW - io.github.frc5024.lib5k.hardware.generic.ledstrips.BlinkinDriver.LEDSetting
 

Z

zero() - Method in class io.github.frc5024.common_drive.DriveTrainBase
Deprecated.
Zero all sensor readings (no-destructive to other subsystems)
zero() - Method in class io.github.frc5024.common_drive.queue.DriveTrainOutput
Deprecated.
Reset this object's contents
zero() - Method in class io.github.frc5024.common_drive.queue.Position
Deprecated.
Reset this position to 0
zero() - Method in class io.github.frc5024.common_drive.queue.WriteLock
Set to defaults
zero() - Method in class io.github.frc5024.lib5k.hardware.generic.sensors.EncoderBase
Deprecated.
Set the current encoder position as "0"
A B C D E F G H I J K L M N O P R S T U V W X Y Z 
All Classes All Packages