A B C D E F G H I J K L M N O P R S T U V W Z 
All Classes All Packages
All Classes All Packages
All Classes All Packages
A
- AbstractFaultMonitor - Class in com.lightningrobotics.common.fault
 - 
Base
LightningFaultCodes.Codechecking functionality - AbstractFaultMonitor(LightningFaultCodes.Code) - Constructor for class com.lightningrobotics.common.fault.AbstractFaultMonitor
 - 
Creates a new non-fatal abstract fault monitor
 - AbstractFaultMonitor(LightningFaultCodes.Code, String) - Constructor for class com.lightningrobotics.common.fault.AbstractFaultMonitor
 - 
Creates a new non-fatal abstract fault monitor
 - AbstractFaultMonitor(LightningFaultCodes.Code, String, boolean) - Constructor for class com.lightningrobotics.common.fault.AbstractFaultMonitor
 - 
Creates a new abstract fault monitor
 - AbstractTimedSystemTest - Class in com.lightningrobotics.common.testing
 - 
Abstract
SystemTestthat runs for a given period of time. - AbstractTimedSystemTest(String, double, LightningFaultCodes.Code) - Constructor for class com.lightningrobotics.common.testing.AbstractTimedSystemTest
 - 
Creates a new AbstractTimedSystemTest
 - AbstractTimedSystemTest(String, double, LightningFaultCodes.Code, SystemTest.Priority) - Constructor for class com.lightningrobotics.common.testing.AbstractTimedSystemTest
 - 
Creates a new AbstractTimedSystemTest
 - AccelerationLimit() - Constructor for class com.lightningrobotics.common.auto.trajectory.TrajectoryConstraint.AccelerationLimit
 - 
Constructs a MinMax with default values.
 - AccelerationLimit(double, double) - Constructor for class com.lightningrobotics.common.auto.trajectory.TrajectoryConstraint.AccelerationLimit
 - 
Constructs an AccelerationLimit.
 - accelerationMetersPerSecondSq - Variable in class com.lightningrobotics.common.auto.trajectory.TrajectoryState
 - 
The acceleration at that point of the trajectory.
 - addConstraint(TrajectoryConstraint) - Method in class com.lightningrobotics.common.auto.trajectory.TrajectoryConfig
 - 
Adds a user-defined constraint to the trajectory.
 - addConstraints(List<? extends TrajectoryConstraint>) - Method in class com.lightningrobotics.common.auto.trajectory.TrajectoryConfig
 - 
Adds all user-defined constraints from a list to the trajectory.
 - addDataElement(String) - Method in class com.lightningrobotics.common.logging.CommandLogger
 - addDataElement(String, DoubleSupplier) - Static method in class com.lightningrobotics.common.logging.DataLogger
 - addDataElement(String, Supplier<String>) - Static method in class com.lightningrobotics.common.logging.DataLogger
 - addDelayedDataElement(String, DoubleSupplier) - Static method in class com.lightningrobotics.common.logging.DataLogger
 - addElement(String, DoubleSupplier) - Method in class com.lightningrobotics.common.logging.DataLogger
 - addElement(String, Supplier<String>) - Method in class com.lightningrobotics.common.logging.DataLogger
 - addFaultCode(LightningFaultCodes.Code) - Static method in class com.lightningrobotics.common.fault.LightningFaultCodes
 - 
Adds a fault code to the registry
 - addFaultCode(String) - Static method in class com.lightningrobotics.common.fault.LightningFaultCodes
 - 
Adds a fault code to the registry.
 - addFaultCode(String, boolean) - Static method in class com.lightningrobotics.common.fault.LightningFaultCodes
 - 
Adds a fault code to the registry
 - angle - Variable in class com.lightningrobotics.common.geometry.kinematics.swerve.SwerveModuleState
 - angleModulus(double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - 
Wraps an angle to the range -pi to pi radians.
 - arcadeDrive(double, double) - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - atReference() - Method in class com.lightningrobotics.common.controller.DiffDriveController
 - 
Returns true if the pose error is within tolerance of the reference.
 - atSetpoint() - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Returns true if the error is within the tolerance of the setpoint.
 - Autonomous - Class in com.lightningrobotics.common.auto
 - 
Autonomous command configuration class.
 - Autonomous() - Constructor for class com.lightningrobotics.common.auto.Autonomous
 - autonomousInit() - Method in class com.lightningrobotics.common.LightningRobot
 - 
The default implementation handles getting the selected command from Shuffleboard.
 
B
- boundTheta0To2Pi(double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - boundTheta0to360(double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - boundThetaNeg180to180(double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - boundThetaNegPiToPi(double) - Static method in class com.lightningrobotics.common.util.LightningMath
 
C
- calculate(double) - Method in class com.lightningrobotics.common.controller.FeedForwardController
 - 
Calculates the feedforward from the gains and velocity setpoint (acceleration is assumed to be zero).
 - calculate(double) - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Returns the next output of the PID controller.
 - calculate(double, double) - Method in class com.lightningrobotics.common.controller.Controller
 - calculate(double, double) - Method in class com.lightningrobotics.common.controller.FeedForwardController
 - 
Calculates the feedforward from the gains and setpoints.
 - calculate(double, double) - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Returns the next output of the PID controller.
 - calculate(double, double, double) - Method in class com.lightningrobotics.common.controller.FeedForwardController
 - 
Calculates the feedforward from the gains and setpoints.
 - calculate(Pose2d, TrajectoryState) - Method in class com.lightningrobotics.common.controller.DiffDriveController
 - 
Returns the next output of the Ramsete controller.
 - calculate(Pose2d, Pose2d, double, double) - Method in class com.lightningrobotics.common.controller.DiffDriveController
 - 
Returns the next output of the Ramsete controller.
 - Characterize - Class in com.lightningrobotics.common.command.drivetrain
 - Characterize() - Constructor for class com.lightningrobotics.common.command.drivetrain.Characterize
 - check() - Method in class com.lightningrobotics.common.fault.AbstractFaultMonitor
 - 
Checks if the fault should be written, and writes the fault if it should
 - checkBaseFileName() - Static method in class com.lightningrobotics.common.logging.DataLogger
 - checkFault() - Method in class com.lightningrobotics.common.fault.AbstractFaultMonitor
 - 
To be overridden, determines if fault should be written
 - checkFault() - Method in class com.lightningrobotics.common.fault.FaultMonitor
 - checkFault() - Method in class com.lightningrobotics.common.fault.TimedFaultMonitor
 - checkFault() - Method in class com.lightningrobotics.common.fault.UnchangingFaultMonitor
 - checkMonitors() - Static method in class com.lightningrobotics.common.fault.FaultMonitor
 - 
Checks all fault monitors
 - clamp(double, double, double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - 
Returns value clamped between low and high boundaries.
 - clamp(int, int, int) - Static method in class com.lightningrobotics.common.util.LightningMath
 - 
Returns value clamped between low and high boundaries.
 - close() - Method in class com.lightningrobotics.common.controller.PIDFController
 - close() - Method in class com.lightningrobotics.common.logging.CommandLogger
 - close() - Method in class com.lightningrobotics.common.logging.LogWriter
 - code - Variable in class com.lightningrobotics.common.fault.AbstractFaultMonitor
 - Code(String) - Constructor for class com.lightningrobotics.common.fault.LightningFaultCodes.Code
 - 
Create fault code
 - Code(String, boolean) - Constructor for class com.lightningrobotics.common.fault.LightningFaultCodes.Code
 - 
Create fault code
 - com.lightningrobotics.common - package com.lightningrobotics.common
 - com.lightningrobotics.common.auto - package com.lightningrobotics.common.auto
 - com.lightningrobotics.common.auto.trajectory - package com.lightningrobotics.common.auto.trajectory
 - com.lightningrobotics.common.command.core - package com.lightningrobotics.common.command.core
 - com.lightningrobotics.common.command.drivetrain - package com.lightningrobotics.common.command.drivetrain
 - com.lightningrobotics.common.command.drivetrain.differential - package com.lightningrobotics.common.command.drivetrain.differential
 - com.lightningrobotics.common.command.drivetrain.swerve - package com.lightningrobotics.common.command.drivetrain.swerve
 - com.lightningrobotics.common.controller - package com.lightningrobotics.common.controller
 - com.lightningrobotics.common.fault - package com.lightningrobotics.common.fault
 - com.lightningrobotics.common.geometry - package com.lightningrobotics.common.geometry
 - com.lightningrobotics.common.geometry.kinematics - package com.lightningrobotics.common.geometry.kinematics
 - com.lightningrobotics.common.geometry.kinematics.differential - package com.lightningrobotics.common.geometry.kinematics.differential
 - com.lightningrobotics.common.geometry.kinematics.swerve - package com.lightningrobotics.common.geometry.kinematics.swerve
 - com.lightningrobotics.common.logging - package com.lightningrobotics.common.logging
 - com.lightningrobotics.common.subsystem.core - package com.lightningrobotics.common.subsystem.core
 - com.lightningrobotics.common.subsystem.drivetrain - package com.lightningrobotics.common.subsystem.drivetrain
 - com.lightningrobotics.common.subsystem.drivetrain.differential - package com.lightningrobotics.common.subsystem.drivetrain.differential
 - com.lightningrobotics.common.subsystem.drivetrain.swerve - package com.lightningrobotics.common.subsystem.drivetrain.swerve
 - com.lightningrobotics.common.testing - package com.lightningrobotics.common.testing
 - com.lightningrobotics.common.util - package com.lightningrobotics.common.util
 - com.lightningrobotics.common.util.filter - package com.lightningrobotics.common.util.filter
 - com.lightningrobotics.common.util.operator.trigger - package com.lightningrobotics.common.util.operator.trigger
 - command - Variable in class com.lightningrobotics.common.command.core.TimedCommand
 - CommandLogger - Class in com.lightningrobotics.common.logging
 - CommandLogger(String) - Constructor for class com.lightningrobotics.common.logging.CommandLogger
 - compareTo(SwerveModuleState) - Method in class com.lightningrobotics.common.geometry.kinematics.swerve.SwerveModuleState
 - compareTo(SystemTest) - Method in class com.lightningrobotics.common.testing.SystemTest
 - concatenate(Trajectory) - Method in class com.lightningrobotics.common.auto.trajectory.Trajectory
 - 
Concatenates another trajectory to the current trajectory.
 - configureAutonomousCommands() - Method in class com.lightningrobotics.common.LightningContainer
 - 
Configures list of possible commands that can be run during autonomous
 - configureButtonBindings() - Method in class com.lightningrobotics.common.LightningContainer
 - 
Connects commands with buttons on joysticks
 - configureDefaultCommands() - Method in class com.lightningrobotics.common.LightningContainer
 - 
Configures all default commands to run on subsystems when no other command requires that subsystem
 - configureFaultCodes() - Method in class com.lightningrobotics.common.LightningContainer
 - 
Configures all robot-specific fault codes
 - configureFaultMonitors() - Method in class com.lightningrobotics.common.LightningContainer
 - 
Configures listeners for fault codes
 - configureMotors() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - configureMotors() - Method in class com.lightningrobotics.common.subsystem.drivetrain.LightningDrivetrain
 - configureMotors() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain
 - configureSystemTests() - Method in class com.lightningrobotics.common.LightningContainer
 - 
Registers all systems tests for the robot to be run
 - constrain(double, double, double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - constrain(int, int, int) - Static method in class com.lightningrobotics.common.util.LightningMath
 - Controller - Class in com.lightningrobotics.common.controller
 - 
Represents an abstract closed loop controller.
 - Controller() - Constructor for class com.lightningrobotics.common.controller.Controller
 - CrashTracker - Class in com.lightningrobotics.common.logging
 - 
Tracks start-up and caught crash events, logging them to a file which dosn't roll over
 - CrashTracker() - Constructor for class com.lightningrobotics.common.logging.CrashTracker
 - CrashTrackingRunnable - Class in com.lightningrobotics.common.logging
 - 
Runnable class with reports all uncaught throws to CrashTracker
 - CrashTrackingRunnable() - Constructor for class com.lightningrobotics.common.logging.CrashTrackingRunnable
 - CUBED - com.lightningrobotics.common.util.filter.JoystickFilter.Mode
 - curvatureRadPerMeter - Variable in class com.lightningrobotics.common.auto.trajectory.TrajectoryState
 - 
The curvature at that point of the trajectory.
 
D
- dataLogger - Variable in class com.lightningrobotics.common.LightningRobot
 - DataLogger - Class in com.lightningrobotics.common.logging
 - DataLoggerOutOfBand - Class in com.lightningrobotics.common.logging
 - DataLoggerOutOfBand(DoubleSupplier) - Constructor for class com.lightningrobotics.common.logging.DataLoggerOutOfBand
 - DataLoggerOutOfBand(DoubleSupplier, double) - Constructor for class com.lightningrobotics.common.logging.DataLoggerOutOfBand
 - deadZone(double, double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - default_action - Variable in class com.lightningrobotics.common.command.core.StatefulCommand
 - DeleteLogCommand - Class in com.lightningrobotics.common.command.core
 - 
Deletes RoboRio log files
 - DeleteLogCommand(int) - Constructor for class com.lightningrobotics.common.command.core.DeleteLogCommand
 - 
Commmand that deletes a certain number of log files, starting from the oldest
 - deltaThetaInDegrees(double, double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - deltaThetaInRadians(double, double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - didPass() - Method in class com.lightningrobotics.common.testing.SystemTest
 - 
Determines passing conditions for the SystemTest
 - DiffDriveController - Class in com.lightningrobotics.common.controller
 - 
Ramsete is a nonlinear time-varying feedback controller for unicycle models that drives the model to a desired pose along a two-dimensional trajectory.
 - DiffDriveController() - Constructor for class com.lightningrobotics.common.controller.DiffDriveController
 - 
Construct a Ramsete unicycle controller.
 - DiffDriveController(double, double) - Constructor for class com.lightningrobotics.common.controller.DiffDriveController
 - 
Construct a Ramsete unicycle controller.
 - DifferentialDrivetrain - Class in com.lightningrobotics.common.subsystem.drivetrain.differential
 - DifferentialDrivetrain(DifferentialGains, MotorController[], MotorController[], LightningIMU, DoubleSupplier, DoubleSupplier, DoubleSupplier, DoubleSupplier) - Constructor for class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - DifferentialDrivetrainState - Class in com.lightningrobotics.common.geometry.kinematics.differential
 - DifferentialDrivetrainState(double, double) - Constructor for class com.lightningrobotics.common.geometry.kinematics.differential.DifferentialDrivetrainState
 - DifferentialGains - Class in com.lightningrobotics.common.subsystem.drivetrain.differential
 - DifferentialGains() - Constructor for class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialGains
 - DifferentialGains(double, double, double, boolean[], boolean[], PIDFController, FeedForwardController) - Constructor for class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialGains
 - DifferentialKinematics - Class in com.lightningrobotics.common.geometry.kinematics.differential
 - DifferentialKinematics(DifferentialGains) - Constructor for class com.lightningrobotics.common.geometry.kinematics.differential.DifferentialKinematics
 - DifferentialTankDrive - Class in com.lightningrobotics.common.command.drivetrain.differential
 - DifferentialTankDrive(DifferentialDrivetrain, DoubleSupplier, DoubleSupplier) - Constructor for class com.lightningrobotics.common.command.drivetrain.differential.DifferentialTankDrive
 - DifferentialTankDrive(DifferentialDrivetrain, DoubleSupplier, DoubleSupplier, JoystickFilter) - Constructor for class com.lightningrobotics.common.command.drivetrain.differential.DifferentialTankDrive
 - disableContinuousInput() - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Disables continuous input.
 - disabledInit() - Method in class com.lightningrobotics.common.LightningRobot
 - 
The default implementation configures the default commands in the event they have been disabled by
LightningRobot.testInit(). - disabledPeriodic() - Method in class com.lightningrobotics.common.LightningRobot
 - 
Nothing should happen here.
 - DO_FIRST - com.lightningrobotics.common.testing.SystemTest.Priority
 - DONT_CARE - com.lightningrobotics.common.testing.SystemTest.Priority
 - drain() - Method in class com.lightningrobotics.common.logging.CommandLogger
 - drain() - Method in class com.lightningrobotics.common.logging.LogWriter
 - DrivetrainSpeed - Class in com.lightningrobotics.common.geometry.kinematics
 - 
Class represents a speed vector for the robot, relative to the robot.
 - DrivetrainSpeed() - Constructor for class com.lightningrobotics.common.geometry.kinematics.DrivetrainSpeed
 - 
Creates a new, zero drivetrain speed.
 - DrivetrainSpeed(double, double, double) - Constructor for class com.lightningrobotics.common.geometry.kinematics.DrivetrainSpeed
 - 
Creates a new drivetrain speed.
 - DrivetrainState - Class in com.lightningrobotics.common.geometry.kinematics
 - 
Base class for a drivetrain state, such as a collection of
Module States. - DrivetrainState() - Constructor for class com.lightningrobotics.common.geometry.kinematics.DrivetrainState
 - dummyLightOn() - Method in class com.lightningrobotics.common.fault.FaultCode
 
E
- eachCode(BiConsumer<LightningFaultCodes.Code, Boolean>) - Static method in class com.lightningrobotics.common.fault.FaultCode
 - 
Runs the given function on each code.
 - EitherButtonTrigger - Class in com.lightningrobotics.common.util.operator.trigger
 - 
Only performs the action, when either button is pressed.
 - EitherButtonTrigger(JoystickButton, JoystickButton) - Constructor for class com.lightningrobotics.common.util.operator.trigger.EitherButtonTrigger
 - elapsed() - Method in class com.lightningrobotics.common.testing.AbstractTimedSystemTest
 - 
The quantity of time that has passed since the test has started running.
 - enableContinuousInput(double, double) - Method in class com.lightningrobotics.common.controller.Controller
 - enableContinuousInput(double, double) - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Enables continuous input.
 - end(boolean) - Method in class com.lightningrobotics.common.command.core.DeleteLogCommand
 - end(boolean) - Method in class com.lightningrobotics.common.command.core.LogCommand
 - end(boolean) - Method in class com.lightningrobotics.common.command.core.LoggedCommand
 - end(boolean) - Method in class com.lightningrobotics.common.command.core.TimedCommand
 - end(boolean) - Method in class com.lightningrobotics.common.command.drivetrain.differential.DifferentialTankDrive
 - end(boolean) - Method in class com.lightningrobotics.common.command.drivetrain.differential.FollowTrajectory
 - end(boolean) - Method in class com.lightningrobotics.common.command.drivetrain.swerve.SwerveDriveCommand
 - end(boolean) - Method in class com.lightningrobotics.common.testing.SystemTestCommand
 - equals(Object) - Method in class com.lightningrobotics.common.auto.trajectory.Trajectory
 - equals(Object) - Method in class com.lightningrobotics.common.auto.trajectory.TrajectoryState
 - exec() - Method in interface com.lightningrobotics.common.subsystem.core.LightningIMU.IMUFunction
 - execute() - Method in class com.lightningrobotics.common.command.core.DeleteLogCommand
 - execute() - Method in class com.lightningrobotics.common.command.core.LogCommand
 - execute() - Method in class com.lightningrobotics.common.command.core.LoggedCommand
 - execute() - Method in class com.lightningrobotics.common.command.core.StatefulCommand
 - execute() - Method in class com.lightningrobotics.common.command.core.TimedCommand
 - execute() - Method in class com.lightningrobotics.common.command.drivetrain.differential.DifferentialTankDrive
 - execute() - Method in class com.lightningrobotics.common.command.drivetrain.differential.FollowTrajectory
 - execute() - Method in class com.lightningrobotics.common.command.drivetrain.swerve.SwerveDriveCommand
 - execute() - Method in class com.lightningrobotics.common.testing.SystemTestCommand
 
F
- fatal - Variable in class com.lightningrobotics.common.fault.AbstractFaultMonitor
 - FaultCode - Class in com.lightningrobotics.common.fault
 - 
Error codes for robot and means to log them
 - FaultCode() - Constructor for class com.lightningrobotics.common.fault.FaultCode
 - FaultCommand - Class in com.lightningrobotics.common.command.core
 - 
Command to trigger a
LightningFaultCodes.Code - FaultCommand(LightningFaultCodes.Code) - Constructor for class com.lightningrobotics.common.command.core.FaultCommand
 - 
Instantly writes the given
LightningFaultCodes.Code - FaultMonitor - Class in com.lightningrobotics.common.fault
 - 
Basic implementation of an
AbstractFaultMonitorthat also provides a means to register ad check other fault monitors - FaultMonitor(LightningFaultCodes.Code, BooleanSupplier) - Constructor for class com.lightningrobotics.common.fault.FaultMonitor
 - FaultMonitor(LightningFaultCodes.Code, BooleanSupplier, String) - Constructor for class com.lightningrobotics.common.fault.FaultMonitor
 - FaultMonitor(LightningFaultCodes.Code, BooleanSupplier, String, boolean) - Constructor for class com.lightningrobotics.common.fault.FaultMonitor
 - FeedForwardController - Class in com.lightningrobotics.common.controller
 - 
A helper class that computes feedforward outputs for a simple permanent-magnet DC motor.
 - FeedForwardController(double, double) - Constructor for class com.lightningrobotics.common.controller.FeedForwardController
 - 
Creates a new SimpleMotorFeedforward with the specified gains.
 - FeedForwardController(double, double, double) - Constructor for class com.lightningrobotics.common.controller.FeedForwardController
 - 
Creates a new SimpleMotorFeedforward with the specified gains.
 - filter(double) - Method in class com.lightningrobotics.common.util.filter.JoystickFilter
 - filter(double) - Method in class com.lightningrobotics.common.util.filter.KalmanFilter
 - filter(double) - Method in class com.lightningrobotics.common.util.filter.MovingAverageFilter
 - filter(double) - Method in interface com.lightningrobotics.common.util.filter.ValueFilter
 - flush() - Method in class com.lightningrobotics.common.logging.CommandLogger
 - flush() - Static method in class com.lightningrobotics.common.logging.DataLogger
 - flush() - Method in class com.lightningrobotics.common.logging.LogWriter
 - FollowTrajectory - Class in com.lightningrobotics.common.command.drivetrain.differential
 - 
A command that uses a RAMSETE controller (
DiffDriveController) to follow a trajectoryTrajectorywith a differential drive. - FollowTrajectory(Trajectory, Supplier<Pose2d>, DiffDriveController, FeedForwardController, DifferentialKinematics, Supplier<DifferentialDrivetrainState>, PIDFController, PIDFController, BiConsumer<Double, Double>, Subsystem...) - Constructor for class com.lightningrobotics.common.command.drivetrain.differential.FollowTrajectory
 - 
Constructs a new FollowTrajectory that, when executed, will follow the provided trajectory.
 - forward(DrivetrainState) - Method in class com.lightningrobotics.common.geometry.kinematics.differential.DifferentialKinematics
 - forward(DrivetrainState) - Method in interface com.lightningrobotics.common.geometry.kinematics.LightningKinematics
 - forward(DrivetrainState) - Method in class com.lightningrobotics.common.geometry.kinematics.swerve.SwerveKinematics
 - from(List<Pose2d>, TrajectoryConfig) - Static method in class com.lightningrobotics.common.auto.trajectory.Trajectory
 - 
Generates a trajectory from the given waypoints and config.
 - fromFieldCentricSpeed(double, double, double, Rotation2d) - Static method in class com.lightningrobotics.common.geometry.kinematics.DrivetrainSpeed
 - 
Creates a drivetrain speed from a field-centric velocity.
 - FRONT_LEFT - com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain.Modules
 - FRONT_RIGHT - com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain.Modules
 
G
- get() - Method in class com.lightningrobotics.common.logging.LoggerValue
 - get() - Method in class com.lightningrobotics.common.util.filter.KalmanFilter
 - get() - Method in class com.lightningrobotics.common.util.filter.MovingAverageFilter
 - get() - Method in interface com.lightningrobotics.common.util.filter.ValueFilter
 - get() - Method in class com.lightningrobotics.common.util.operator.trigger.EitherButtonTrigger
 - get() - Method in class com.lightningrobotics.common.util.operator.trigger.TwoButtonTrigger
 - get(double) - Method in class com.lightningrobotics.common.util.InterpolationMap
 - getAsDouble() - Method in class com.lightningrobotics.common.logging.DataLoggerOutOfBand
 - getAsDouble() - Method in class com.lightningrobotics.common.logging.LoggerValue
 - getAutonomous() - Static method in class com.lightningrobotics.common.auto.Autonomous
 - 
Gets the command selected on
Shuffleboard. - getAzimuthMotor() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveModule
 - getCallingState() - Method in class com.lightningrobotics.common.command.core.StatefulCommand
 - getCode() - Method in class com.lightningrobotics.common.testing.SystemTest
 - 
The relating
FaultCodecorresponding to the SystemTest - getCodes() - Static method in class com.lightningrobotics.common.fault.LightningFaultCodes
 - 
Get a list of all fault codes
 - getCommand(LightningDrivetrain) - Method in class com.lightningrobotics.common.auto.Path
 - 
Retrieves the path represented as a command
 - getCommands() - Static method in class com.lightningrobotics.common.auto.Autonomous
 - 
Map of autonomous commands where the key (
String) corresponds to the name of the valueCommandthat will be displayed onShuffleboard. - getConstraints() - Method in class com.lightningrobotics.common.auto.trajectory.TrajectoryConfig
 - 
Returns the user-defined constraints of the trajectory.
 - getContainer() - Method in class com.lightningrobotics.common.LightningRobot
 - 
Getter for the configured robot container.
 - getD() - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Get the Differential coefficient.
 - getDeadband() - Method in class com.lightningrobotics.common.util.filter.JoystickFilter
 - getDriveMotor() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveModule
 - getDriveMotorInverts() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveGains
 - getDrivePIDFController() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - getDriveState() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - getDriveState() - Method in class com.lightningrobotics.common.subsystem.drivetrain.LightningDrivetrain
 - getDriveState() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain
 - getDrivetrain() - Method in class com.lightningrobotics.common.LightningContainer
 - 
The
drivetrainobject of the robot - getDriveTrainState() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - getDuration(LightningDrivetrain) - Method in class com.lightningrobotics.common.auto.Path
 - 
The duration of time it will take the robot to complete the path
 - getEndVelocity() - Method in class com.lightningrobotics.common.auto.trajectory.TrajectoryConfig
 - 
Returns the starting velocity of the trajectory.
 - getFaultCode(String) - Static method in class com.lightningrobotics.common.fault.LightningFaultCodes
 - 
Retrieve a specific fault code
 - getFeedForwardController() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - getFeedForwardController() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialGains
 - getGains() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - getGains() - Method in class com.lightningrobotics.common.subsystem.drivetrain.LightningDrivetrain
 - getGains() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain
 - getHeader() - Method in class com.lightningrobotics.common.logging.DataLogger
 - getHeading() - Method in class com.lightningrobotics.common.subsystem.core.LightningIMU
 - 
Get the IMU heading as a
Rotation2d. - getI() - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Get the Integral coefficient.
 - getInitialPose() - Method in class com.lightningrobotics.common.auto.trajectory.Trajectory
 - 
Returns the initial pose of the trajectory.
 - getKinematics() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialGains
 - getKinematics() - Method in class com.lightningrobotics.common.subsystem.drivetrain.LightningGains
 - getLeftInverts() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialGains
 - getLeftSpeed() - Method in class com.lightningrobotics.common.geometry.kinematics.differential.DifferentialDrivetrainState
 - getLength() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveGains
 - getLogAmount() - Method in class com.lightningrobotics.common.command.core.DeleteLogCommand
 - getLogger() - Static method in class com.lightningrobotics.common.logging.DataLogger
 - getLogWriter() - Method in class com.lightningrobotics.common.logging.DataLogger
 - getMaxAcceleration() - Method in class com.lightningrobotics.common.auto.trajectory.TrajectoryConfig
 - 
Returns the maximum acceleration of the trajectory.
 - getMaxAcceleration() - Method in class com.lightningrobotics.common.subsystem.drivetrain.LightningGains
 - getMaxAngularSpeed() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveGains
 - getMaxPower() - Method in class com.lightningrobotics.common.util.filter.JoystickFilter
 - getMaxRealSpeed() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveGains
 - getMaxSpeed() - Method in class com.lightningrobotics.common.subsystem.drivetrain.LightningGains
 - getMaxVelocity() - Method in class com.lightningrobotics.common.auto.trajectory.TrajectoryConfig
 - 
Returns the maximum velocity of the trajectory.
 - getMaxVelocityMetersPerSecond(Pose2d, double, double) - Method in interface com.lightningrobotics.common.auto.trajectory.TrajectoryConstraint
 - 
Returns the max velocity given the current pose and curvature.
 - getMessage() - Method in class com.lightningrobotics.common.testing.SystemTest
 - 
The dashboard message of the SystemTest
 - getMinMaxAccelerationMetersPerSecondSq(Pose2d, double, double) - Method in interface com.lightningrobotics.common.auto.trajectory.TrajectoryConstraint
 - 
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.
 - getMinPower() - Method in class com.lightningrobotics.common.util.filter.JoystickFilter
 - getMode() - Method in class com.lightningrobotics.common.util.filter.JoystickFilter
 - getModel() - Static method in class com.lightningrobotics.common.fault.FaultCode
 - 
Gets a model of the faults and their states as well as the timestamp
 - getModuleAngle() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveModule
 - getModuleID() - Method in enum com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain.Modules
 - getName() - Method in class com.lightningrobotics.common.auto.Path
 - 
Name of path
 - getName() - Method in class com.lightningrobotics.common.fault.LightningFaultCodes.Code
 - 
Name of the fault code
 - getP() - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Get the Proportional coefficient.
 - getPeriod() - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Returns the period of this controller.
 - getPIDFController() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialGains
 - getPose() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - getPose() - Method in class com.lightningrobotics.common.subsystem.drivetrain.LightningDrivetrain
 - getPose() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain
 - getPoseMeters() - Method in class com.lightningrobotics.common.geometry.LightningOdometer
 - 
Returns the position of the robot on the field.
 - getPositionError() - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Returns the difference between the setpoint and the measurement.
 - getPriority() - Method in class com.lightningrobotics.common.testing.SystemTest
 - 
The priority of the SystemTest
 - getReversed() - Method in class com.lightningrobotics.common.auto.Path
 - 
Direction path should be followed
 - getRightInverts() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialGains
 - getRightSpeed() - Method in class com.lightningrobotics.common.geometry.kinematics.differential.DifferentialDrivetrainState
 - getSetpoint() - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Returns the current setpoint of the PIDController.
 - getStartVelocity() - Method in class com.lightningrobotics.common.auto.trajectory.TrajectoryConfig
 - 
Returns the starting velocity of the trajectory.
 - getState() - Method in class com.lightningrobotics.common.command.core.StatefulCommand
 - getState() - Method in class com.lightningrobotics.common.fault.LightningFaultCodes.Code
 - 
The current state of the fault code
 - getState() - Method in class com.lightningrobotics.common.geometry.kinematics.differential.DifferentialDrivetrainState
 - getState() - Method in class com.lightningrobotics.common.geometry.kinematics.DrivetrainState
 - getState() - Method in class com.lightningrobotics.common.geometry.kinematics.swerve.SwerveDrivetrainState
 - getState() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveModule
 - getStates() - Method in class com.lightningrobotics.common.auto.trajectory.Trajectory
 - 
Return the states of the trajectory.
 - getStates() - Method in class com.lightningrobotics.common.geometry.kinematics.swerve.SwerveDrivetrainState
 - getTotalTimeSeconds() - Method in class com.lightningrobotics.common.auto.trajectory.Trajectory
 - 
Returns the overall duration of the trajectory.
 - getTrackWidth() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialGains
 - getTrackWidth() - Method in class com.lightningrobotics.common.subsystem.drivetrain.LightningGains
 - getTrajectory(LightningDrivetrain) - Method in class com.lightningrobotics.common.auto.Path
 - 
Obtains an optimized trajectory the robot should follow so it hits all the waypoints
 - getTurnMotorInverts() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveGains
 - getType() - Method in class com.lightningrobotics.common.subsystem.core.LightningIMU
 - getVelocity() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveModule
 - getVelocityError() - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Returns the velocity error.
 - getWidth() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveGains
 
H
- hasDashboardWaitCommand() - Static method in class com.lightningrobotics.common.auto.Autonomous
 - 
Configures if
Autonomous.register(String, Command)will group command with aWaitCommandif enabled (Autonomous.setHasDashboardWaitCommand(boolean)). - heading() - Method in class com.lightningrobotics.common.subsystem.core.LightningIMU
 - 
A function that can be used to get the heading of the IMU
 - HIGH - com.lightningrobotics.common.testing.SystemTest.Priority
 
I
- init() - Static method in class com.lightningrobotics.common.fault.FaultCode
 - 
Push each fault code to the dashboard
 - initialize() - Method in class com.lightningrobotics.common.command.core.DeleteLogCommand
 - initialize() - Method in class com.lightningrobotics.common.command.core.FaultCommand
 - initialize() - Method in class com.lightningrobotics.common.command.core.LogCommand
 - initialize() - Method in class com.lightningrobotics.common.command.core.LoggedCommand
 - initialize() - Method in class com.lightningrobotics.common.command.core.StatefulCommand
 - initialize() - Method in class com.lightningrobotics.common.command.core.TimedCommand
 - initialize() - Method in class com.lightningrobotics.common.command.core.WaitCommand
 - initialize() - Method in class com.lightningrobotics.common.command.drivetrain.differential.FollowTrajectory
 - initialize() - Method in class com.lightningrobotics.common.testing.AbstractTimedSystemTest
 - initialize() - Method in class com.lightningrobotics.common.testing.SystemTestCommand
 - initializeDashboardCommands() - Method in class com.lightningrobotics.common.LightningContainer
 - 
Puts command buttons on the dashboard
 - initSendable(SendableBuilder) - Method in class com.lightningrobotics.common.controller.PIDFController
 - inputModulus(double, double, double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - 
Returns modulus of input.
 - InterpolationMap - Class in com.lightningrobotics.common.util
 - InterpolationMap() - Constructor for class com.lightningrobotics.common.util.InterpolationMap
 - InterpolationMap(double...) - Constructor for class com.lightningrobotics.common.util.InterpolationMap
 - InterpolationMap(Double[]) - Constructor for class com.lightningrobotics.common.util.InterpolationMap
 - inverse(DrivetrainSpeed) - Method in class com.lightningrobotics.common.geometry.kinematics.differential.DifferentialKinematics
 - inverse(DrivetrainSpeed) - Method in interface com.lightningrobotics.common.geometry.kinematics.LightningKinematics
 - inverse(DrivetrainSpeed) - Method in class com.lightningrobotics.common.geometry.kinematics.swerve.SwerveKinematics
 - isContinuousInputEnabled() - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Returns true if continuous input is enabled.
 - isFinished() - Method in class com.lightningrobotics.common.command.core.DeleteLogCommand
 - isFinished() - Method in class com.lightningrobotics.common.command.core.LogCommand
 - isFinished() - Method in class com.lightningrobotics.common.command.core.StatefulCommand
 - isFinished() - Method in class com.lightningrobotics.common.command.core.TimedCommand
 - isFinished() - Method in class com.lightningrobotics.common.command.core.WaitCommand
 - isFinished() - Method in class com.lightningrobotics.common.command.drivetrain.differential.FollowTrajectory
 - isFinished() - Method in class com.lightningrobotics.common.testing.AbstractTimedSystemTest
 - isFinished() - Method in class com.lightningrobotics.common.testing.SystemTestCommand
 - isReversed() - Method in class com.lightningrobotics.common.auto.trajectory.TrajectoryConfig
 - 
Returns whether the trajectory is reversed or not.
 - isValid() - Method in class com.lightningrobotics.common.logging.LogWriter
 
J
- JoystickFilter - Class in com.lightningrobotics.common.util.filter
 - 
Filter for joystick input to enhance driver controll.
 - JoystickFilter(double, double, double, JoystickFilter.Mode) - Constructor for class com.lightningrobotics.common.util.filter.JoystickFilter
 - JoystickFilter.Mode - Enum in com.lightningrobotics.common.util.filter
 
K
- ka - Variable in class com.lightningrobotics.common.controller.FeedForwardController
 - KalmanFilter - Class in com.lightningrobotics.common.util.filter
 - KalmanFilter() - Constructor for class com.lightningrobotics.common.util.filter.KalmanFilter
 - KalmanFilter(double, double) - Constructor for class com.lightningrobotics.common.util.filter.KalmanFilter
 - ks - Variable in class com.lightningrobotics.common.controller.FeedForwardController
 - kv - Variable in class com.lightningrobotics.common.controller.FeedForwardController
 
L
- lerp(double, double, double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - 
Linearly interpolates between two values.
 - lerp(Pose2d, Pose2d, double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - 
Linearly interpolates between two poses.
 - LightningContainer - Class in com.lightningrobotics.common
 - 
This class is where the bulk of the robot should be declared.
 - LightningContainer() - Constructor for class com.lightningrobotics.common.LightningContainer
 - LightningCore - Class in com.lightningrobotics.common.subsystem.core
 - LightningCore() - Constructor for class com.lightningrobotics.common.subsystem.core.LightningCore
 - LightningDrivetrain - Class in com.lightningrobotics.common.subsystem.drivetrain
 - LightningDrivetrain() - Constructor for class com.lightningrobotics.common.subsystem.drivetrain.LightningDrivetrain
 - LightningFaultCodes - Class in com.lightningrobotics.common.fault
 - 
Class representing a set of fault codes, or enumerated things that can go wrong.
 - LightningFaultCodes() - Constructor for class com.lightningrobotics.common.fault.LightningFaultCodes
 - LightningFaultCodes.Code - Class in com.lightningrobotics.common.fault
 - 
A base class that represents a single fault code
 - LightningGains - Class in com.lightningrobotics.common.subsystem.drivetrain
 - LightningGains() - Constructor for class com.lightningrobotics.common.subsystem.drivetrain.LightningGains
 - LightningGains(double, double) - Constructor for class com.lightningrobotics.common.subsystem.drivetrain.LightningGains
 - LightningIMU - Class in com.lightningrobotics.common.subsystem.core
 - 
Base gyroscope type.
 - LightningIMU.IMUFunction - Interface in com.lightningrobotics.common.subsystem.core
 - 
A generic function on the IMU to support lambda structure
 - LightningIMU.IMUType - Enum in com.lightningrobotics.common.subsystem.core
 - 
Supported IMU types
 - LightningKinematics - Interface in com.lightningrobotics.common.geometry.kinematics
 - 
Base kinematics interface.
 - LightningMath - Class in com.lightningrobotics.common.util
 - LightningOdometer - Class in com.lightningrobotics.common.geometry
 - 
Class for differential drive odometry.
 - LightningOdometer(Rotation2d) - Constructor for class com.lightningrobotics.common.geometry.LightningOdometer
 - 
Constructs a DifferentialDriveOdometry object with the default pose at the origin.
 - LightningOdometer(Rotation2d, Pose2d) - Constructor for class com.lightningrobotics.common.geometry.LightningOdometer
 - 
Constructs a DifferentialDriveOdometry object.
 - LightningRobot - Class in com.lightningrobotics.common
 - 
Base robot class, provides
logging,fault monitoring, and loops with varying periodsbackground,low, andmediumpriority loops. - LightningRobot(LightningContainer) - Constructor for class com.lightningrobotics.common.LightningRobot
 - limit(double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - limit(double, double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - limit(double, double, double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - LINEAR - com.lightningrobotics.common.util.filter.JoystickFilter.Mode
 - load() - Static method in class com.lightningrobotics.common.auto.Autonomous
 - 
Loads all commands configured with
Autonomous.register(String, Command)to "Autonomous" tab onShuffleboard. - logAutoInit() - Static method in class com.lightningrobotics.common.logging.CrashTracker
 - LogCommand - Class in com.lightningrobotics.common.command.core
 - LogCommand(String) - Constructor for class com.lightningrobotics.common.command.core.LogCommand
 - LogCommand(Supplier<String>) - Constructor for class com.lightningrobotics.common.command.core.LogCommand
 - logCompetitionStart() - Static method in class com.lightningrobotics.common.logging.CrashTracker
 - logData() - Static method in class com.lightningrobotics.common.logging.DataLogger
 - logDisabledInit() - Static method in class com.lightningrobotics.common.logging.CrashTracker
 - LoggedCommand - Class in com.lightningrobotics.common.command.core
 - 
A command that writes to
CommandLoggerduring execution. - LoggedCommand() - Constructor for class com.lightningrobotics.common.command.core.LoggedCommand
 - logger - Variable in class com.lightningrobotics.common.command.core.LoggedCommand
 - LoggerValue - Class in com.lightningrobotics.common.logging
 - LoggerValue() - Constructor for class com.lightningrobotics.common.logging.LoggerValue
 - LoggerValue(double) - Constructor for class com.lightningrobotics.common.logging.LoggerValue
 - logRawString(String) - Method in class com.lightningrobotics.common.logging.LogWriter
 - logRobotConstruction() - Static method in class com.lightningrobotics.common.logging.CrashTracker
 - logRobotInit() - Static method in class com.lightningrobotics.common.logging.CrashTracker
 - logRobotStartup() - Static method in class com.lightningrobotics.common.logging.CrashTracker
 - logString(String) - Method in class com.lightningrobotics.common.logging.LogWriter
 - logTeleopInit() - Static method in class com.lightningrobotics.common.logging.CrashTracker
 - logTestInit() - Static method in class com.lightningrobotics.common.logging.CrashTracker
 - logThrowableCrash(Throwable) - Static method in class com.lightningrobotics.common.logging.CrashTracker
 - LogWriter - Class in com.lightningrobotics.common.logging
 - LogWriter(String) - Constructor for class com.lightningrobotics.common.logging.LogWriter
 - LogWriter(String, int) - Constructor for class com.lightningrobotics.common.logging.LogWriter
 - Loop - Interface in com.lightningrobotics.common.util
 - 
Interface for loops, which are routine that run periodically in the robot code (such as periodic gyroscope calibration, etc.)
 - LOW - com.lightningrobotics.common.testing.SystemTest.Priority
 
M
- max(double...) - Static method in class com.lightningrobotics.common.util.LightningMath
 - 
Finds the maximum value of the given inputs.
 - MAX_VOLTAGE - Static variable in class com.lightningrobotics.common.subsystem.drivetrain.LightningGains
 - maxAccelerationMetersPerSecondSq - Variable in class com.lightningrobotics.common.auto.trajectory.TrajectoryConstraint.AccelerationLimit
 - maxAchievableAcceleration(double, double) - Method in class com.lightningrobotics.common.controller.FeedForwardController
 - 
Calculates the maximum achievable acceleration given a maximum voltage supply and a velocity.
 - maxAchievableVelocity(double, double) - Method in class com.lightningrobotics.common.controller.FeedForwardController
 - 
Calculates the maximum achievable velocity given a maximum voltage supply and an acceleration.
 - MED - com.lightningrobotics.common.testing.SystemTest.Priority
 - methodName(Enum<?>) - Method in class com.lightningrobotics.common.command.core.StatefulCommand
 - minAccelerationMetersPerSecondSq - Variable in class com.lightningrobotics.common.auto.trajectory.TrajectoryConstraint.AccelerationLimit
 - minAchievableAcceleration(double, double) - Method in class com.lightningrobotics.common.controller.FeedForwardController
 - 
Calculates the minimum achievable acceleration given a maximum voltage supply and a velocity.
 - minAchievableVelocity(double, double) - Method in class com.lightningrobotics.common.controller.FeedForwardController
 - 
Calculates the minimum achievable velocity given a maximum voltage supply and an acceleration.
 - MovingAverageFilter - Class in com.lightningrobotics.common.util.filter
 - MovingAverageFilter(int) - Constructor for class com.lightningrobotics.common.util.filter.MovingAverageFilter
 - msg - Variable in class com.lightningrobotics.common.fault.AbstractFaultMonitor
 
N
- navX() - Static method in class com.lightningrobotics.common.subsystem.core.LightningIMU
 - 
Creates a new
NavX. - NAVX - com.lightningrobotics.common.subsystem.core.LightningIMU.IMUType
 - none() - Static method in class com.lightningrobotics.common.subsystem.core.LightningIMU
 - 
Creates a static IMU
 - NONE - com.lightningrobotics.common.subsystem.core.LightningIMU.IMUType
 
O
- omega - Variable in class com.lightningrobotics.common.geometry.kinematics.DrivetrainSpeed
 - 
Rotational velocity
 - onLoop() - Method in class com.lightningrobotics.common.logging.DataLogger
 - onLoop() - Method in class com.lightningrobotics.common.logging.LogWriter
 - onLoop() - Method in interface com.lightningrobotics.common.util.Loop
 - onStart() - Method in class com.lightningrobotics.common.logging.DataLogger
 - onStart() - Method in class com.lightningrobotics.common.logging.LogWriter
 - onStart() - Method in interface com.lightningrobotics.common.util.Loop
 - onStop() - Method in class com.lightningrobotics.common.logging.DataLogger
 - onStop() - Method in class com.lightningrobotics.common.logging.LogWriter
 - onStop() - Method in interface com.lightningrobotics.common.util.Loop
 - optimize(SwerveModuleState, Rotation2d) - Static method in class com.lightningrobotics.common.geometry.kinematics.swerve.SwerveModuleState
 
P
- Path - Class in com.lightningrobotics.common.auto
 - 
Object class representing a path a
LightningDrivetraincan follow. - Path(String, boolean) - Constructor for class com.lightningrobotics.common.auto.Path
 - 
Constructor creates path object
 - Path(String, List<Pose2d>) - Constructor for class com.lightningrobotics.common.auto.Path
 - 
Constructor creates path object
 - Path(String, List<Pose2d>, boolean) - Constructor for class com.lightningrobotics.common.auto.Path
 - 
Constructor creates path object
 - Path(List<Pose2d>) - Constructor for class com.lightningrobotics.common.auto.Path
 - 
Constructor creates path object
 - Path(List<Pose2d>, boolean) - Constructor for class com.lightningrobotics.common.auto.Path
 - periodic() - Method in class com.lightningrobotics.common.subsystem.core.LightningIMU
 - periodic() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - periodic() - Method in class com.lightningrobotics.common.subsystem.drivetrain.PIDFDashboardTuner
 - PIDFController - Class in com.lightningrobotics.common.controller
 - 
Implements a PID control loop.
 - PIDFController(double, double, double) - Constructor for class com.lightningrobotics.common.controller.PIDFController
 - 
Allocates a PIDController with the given constants for kp, ki, and kd and a default period of 0.02 seconds.
 - PIDFController(double, double, double, double) - Constructor for class com.lightningrobotics.common.controller.PIDFController
 - 
Allocates a PIDController with the given constants for kp, ki, and kd.
 - PIDFDashboardTuner - Class in com.lightningrobotics.common.subsystem.drivetrain
 - PIDFDashboardTuner(String, PIDFController) - Constructor for class com.lightningrobotics.common.subsystem.drivetrain.PIDFDashboardTuner
 - PIDFDashboardTuner(String, PIDFController, String) - Constructor for class com.lightningrobotics.common.subsystem.drivetrain.PIDFDashboardTuner
 - pigeon(int) - Static method in class com.lightningrobotics.common.subsystem.core.LightningIMU
 - 
Creates a new
Pigeonwith the given ID. - PIGEON - com.lightningrobotics.common.subsystem.core.LightningIMU.IMUType
 - poseMeters - Variable in class com.lightningrobotics.common.auto.trajectory.TrajectoryState
 - 
The pose at that point of the trajectory.
 - preventNewDataElements() - Static method in class com.lightningrobotics.common.logging.DataLogger
 
R
- REAR_LEFT - com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain.Modules
 - REAR_RIGHT - com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain.Modules
 - register(AbstractFaultMonitor) - Static method in class com.lightningrobotics.common.fault.FaultMonitor
 - 
Adds a new fault monitor to be checked with
FaultMonitor.checkMonitors() - register(SystemTest) - Static method in class com.lightningrobotics.common.testing.SystemTest
 - 
Registers the given system test to be run when the
LightningRobotis enabled in test mode. - register(String, Command) - Static method in class com.lightningrobotics.common.auto.Autonomous
 - 
Add command to list of autonomous commands.
 - relativeTo(Pose2d) - Method in class com.lightningrobotics.common.auto.trajectory.Trajectory
 - 
Transforms all poses in the trajectory so that they are relative to the given pose.
 - releaseDefaultCommands() - Method in class com.lightningrobotics.common.LightningContainer
 - 
Cancles all default commands
 - reset() - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Resets the previous error and the integral term.
 - reset() - Method in class com.lightningrobotics.common.logging.CommandLogger
 - reset() - Method in class com.lightningrobotics.common.subsystem.core.LightningIMU
 - 
Reset IMU heading to 0
 - reset() - Method in class com.lightningrobotics.common.testing.SystemTestCommand
 - 
Resets the status of all system tests to incomplete.
 - reset() - Method in class com.lightningrobotics.common.util.filter.KalmanFilter
 - reset() - Method in class com.lightningrobotics.common.util.filter.MovingAverageFilter
 - reset() - Method in interface com.lightningrobotics.common.util.filter.ValueFilter
 - reset_file() - Method in class com.lightningrobotics.common.logging.DataLogger
 - resetPose() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - resetPosition(Pose2d, Rotation2d) - Method in class com.lightningrobotics.common.geometry.LightningOdometer
 - 
Resets the robot's position on the field.
 - robotBackgroundPeriodic() - Method in class com.lightningrobotics.common.LightningRobot
 - 
A slower loop, running once every 10 seconds Note as currently implemented it still needs to complete in our loop time or it delay higher priority opterations.
 - robotInit() - Method in class com.lightningrobotics.common.LightningRobot
 - 
This function is run when the robot is first started up and should be used for any initialization code.
 - robotLowPriorityPeriodic() - Method in class com.lightningrobotics.common.LightningRobot
 - 
A slow loop, running once a second Note as currently implemented it still needs to complete in our loop time or it delay higher priority opterations.
 - robotMediumPriorityPeriodic() - Method in class com.lightningrobotics.common.LightningRobot
 - 
A loop, running 10 times a second Note as currently implemented it still needs to complete in our loop time or it delay higher priority opterations.
 - robotPeriodic() - Method in class com.lightningrobotics.common.LightningRobot
 - 
This function is called every robot packet, no matter the mode.
 - rpmToMetersPerSecond(double, double, double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - 
Converts motor rotational speed to linear speed
 - run() - Method in class com.lightningrobotics.common.logging.CrashTrackingRunnable
 - runCrashTracked() - Method in class com.lightningrobotics.common.logging.CrashTrackingRunnable
 
S
- sample(double) - Method in class com.lightningrobotics.common.auto.trajectory.Trajectory
 - 
Sample the trajectory at a point in time.
 - scale(double, double, double, double, double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - scale(int, int, int, int, int) - Static method in class com.lightningrobotics.common.util.LightningMath
 - set(double) - Method in class com.lightningrobotics.common.logging.LoggerValue
 - set(String, double) - Method in class com.lightningrobotics.common.logging.CommandLogger
 - set(String, String) - Method in class com.lightningrobotics.common.logging.CommandLogger
 - setBaseFileName(String) - Static method in class com.lightningrobotics.common.logging.DataLogger
 - setD(double) - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Sets the Differential coefficient of the PID controller gain.
 - setDeadband(double) - Method in class com.lightningrobotics.common.util.filter.JoystickFilter
 - setDefaultAction(Runnable) - Method in class com.lightningrobotics.common.command.core.StatefulCommand
 - setDriveMotorInverts(boolean[]) - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveGains
 - setDriveSpeed(DrivetrainSpeed) - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - setDriveSpeed(DrivetrainSpeed) - Method in class com.lightningrobotics.common.subsystem.drivetrain.LightningDrivetrain
 - setDriveSpeed(DrivetrainSpeed) - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain
 - setEnabled(boolean) - Method in class com.lightningrobotics.common.controller.DiffDriveController
 - 
Enables and disables the controller for troubleshooting purposes.
 - setEndVelocity(double) - Method in class com.lightningrobotics.common.auto.trajectory.TrajectoryConfig
 - 
Sets the end velocity of the trajectory.
 - setFileName(String) - Method in class com.lightningrobotics.common.logging.LogWriter
 - setHasDashboardWaitCommand(boolean) - Static method in class com.lightningrobotics.common.auto.Autonomous
 - 
Configures if
Autonomous.register(String, Command)will group command with aWaitCommand. - setI(double) - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Sets the Integral coefficient of the PID controller gain.
 - setIntegratorRange(double, double) - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Sets the minimum and maximum values for the integrator.
 - setKinematics(LightningKinematics) - Method in class com.lightningrobotics.common.subsystem.drivetrain.LightningGains
 - setLeftInverts(boolean[]) - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialGains
 - setLeftOutput(double) - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - setLength(double) - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveGains
 - setMaxAcceleration(double) - Method in class com.lightningrobotics.common.subsystem.drivetrain.LightningGains
 - setMaxAngularSpeed(double) - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveGains
 - setMaxPower(double) - Method in class com.lightningrobotics.common.util.filter.JoystickFilter
 - setMaxRealSpeed(double) - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveGains
 - setMaxSpeed(double) - Method in class com.lightningrobotics.common.subsystem.drivetrain.LightningGains
 - setMinPower(double) - Method in class com.lightningrobotics.common.util.filter.JoystickFilter
 - setMode(JoystickFilter.Mode) - Method in class com.lightningrobotics.common.util.filter.JoystickFilter
 - setName(String) - Method in class com.lightningrobotics.common.fault.LightningFaultCodes.Code
 - 
Sets the name of a fault code
 - setNetworkTableEntry(LightningFaultCodes.Code, NetworkTableEntry) - Static method in class com.lightningrobotics.common.fault.FaultCode
 - 
Links a
LightningFaultCodes.Codewith aNetworkTableEntry - setP(double) - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Sets the Proportional coefficient of the PID controller gain.
 - setPID(double, double, double) - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Sets the PID Controller gain parameters.
 - setPose(Pose2d) - Method in class com.lightningrobotics.common.geometry.LightningOdometer
 - setRampDelta(double) - Method in class com.lightningrobotics.common.util.filter.JoystickFilter
 - setRawAzimuthPower(double) - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveModule
 - setRawDrivePower(double) - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveModule
 - setReversed(boolean) - Method in class com.lightningrobotics.common.auto.trajectory.TrajectoryConfig
 - 
Sets the reversed flag of the trajectory.
 - setRightInverts(boolean[]) - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialGains
 - setRightOutput(double) - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - setSetpoint(double) - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Sets the setpoint for the PIDController.
 - setStartVelocity(double) - Method in class com.lightningrobotics.common.auto.trajectory.TrajectoryConfig
 - 
Sets the start velocity of the trajectory.
 - setState(boolean) - Method in class com.lightningrobotics.common.fault.LightningFaultCodes.Code
 - 
Sets the state of the fault code
 - setState(SwerveModuleState) - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveModule
 - setState(Enum<?>) - Method in class com.lightningrobotics.common.command.core.StatefulCommand
 - setStates(SwerveModuleState[]) - Method in class com.lightningrobotics.common.geometry.kinematics.swerve.SwerveDrivetrainState
 - setTolerance(double) - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Sets the error which is considered tolerable for use with atSetpoint().
 - setTolerance(double, double) - Method in class com.lightningrobotics.common.controller.PIDFController
 - 
Sets the error which is considered tolerable for use with atSetpoint().
 - setTolerance(Pose2d) - Method in class com.lightningrobotics.common.controller.DiffDriveController
 - 
Sets the pose error which is considered tolerable for use with atReference().
 - setTrackWidth(int) - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialGains
 - setTurnMotorInverts(boolean[]) - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveGains
 - setVoltage(double, double) - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - setWidth(double) - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveGains
 - SQUARED - com.lightningrobotics.common.util.filter.JoystickFilter.Mode
 - StatefulCommand - Class in com.lightningrobotics.common.command.core
 - 
A command that iterates through a list of states subclass-defined states.
 - StatefulCommand(Enum<?>) - Constructor for class com.lightningrobotics.common.command.core.StatefulCommand
 - stop() - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - stop() - Method in class com.lightningrobotics.common.subsystem.drivetrain.LightningDrivetrain
 - stop() - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain
 - SwerveDriveCommand - Class in com.lightningrobotics.common.command.drivetrain.swerve
 - SwerveDriveCommand(SwerveDrivetrain, LightningIMU, XboxController) - Constructor for class com.lightningrobotics.common.command.drivetrain.swerve.SwerveDriveCommand
 - SwerveDriveCommand(SwerveDrivetrain, LightningIMU, XboxController, boolean) - Constructor for class com.lightningrobotics.common.command.drivetrain.swerve.SwerveDriveCommand
 - SwerveDriveCommand(SwerveDrivetrain, LightningIMU, XboxController, boolean, JoystickFilter) - Constructor for class com.lightningrobotics.common.command.drivetrain.swerve.SwerveDriveCommand
 - SwerveDrivetrain - Class in com.lightningrobotics.common.subsystem.drivetrain.swerve
 - SwerveDrivetrain(SwerveGains, SwerveModule...) - Constructor for class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain
 - SwerveDrivetrain.Modules - Enum in com.lightningrobotics.common.subsystem.drivetrain.swerve
 - SwerveDrivetrainState - Class in com.lightningrobotics.common.geometry.kinematics.swerve
 - SwerveDrivetrainState(SwerveModuleState[]) - Constructor for class com.lightningrobotics.common.geometry.kinematics.swerve.SwerveDrivetrainState
 - SwerveGains - Class in com.lightningrobotics.common.subsystem.drivetrain.swerve
 - SwerveGains() - Constructor for class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveGains
 - SwerveGains(double, double, double, double, double, double, boolean[], boolean[]) - Constructor for class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveGains
 - SwerveKinematics - Class in com.lightningrobotics.common.geometry.kinematics.swerve
 - SwerveKinematics(SwerveGains) - Constructor for class com.lightningrobotics.common.geometry.kinematics.swerve.SwerveKinematics
 - SwerveModule - Class in com.lightningrobotics.common.subsystem.drivetrain.swerve
 - 
Represents a single swerve module with both drive and azimuth control.
 - SwerveModule(SwerveGains, MotorController, MotorController, Supplier<Rotation2d>, DoubleSupplier, PIDFController, PIDFController) - Constructor for class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveModule
 - SwerveModuleState - Class in com.lightningrobotics.common.geometry.kinematics.swerve
 - SwerveModuleState(double, Rotation2d) - Constructor for class com.lightningrobotics.common.geometry.kinematics.swerve.SwerveModuleState
 - SystemTest - Class in com.lightningrobotics.common.testing
 - 
Base testing class.
 - SystemTest(String, LightningFaultCodes.Code) - Constructor for class com.lightningrobotics.common.testing.SystemTest
 - 
Creates a new SystemTest
 - SystemTest(String, LightningFaultCodes.Code, SystemTest.Priority) - Constructor for class com.lightningrobotics.common.testing.SystemTest
 - 
Creates a new SystemTest
 - SystemTest.Priority - Enum in com.lightningrobotics.common.testing
 - 
Importance of the SystemTest.
 - SystemTestCommand - Class in com.lightningrobotics.common.testing
 - 
Runs all
SystemTeststhat have been queued withSystemTest.register(SystemTest). - SystemTestCommand() - Constructor for class com.lightningrobotics.common.testing.SystemTestCommand
 - 
Creates new SystemTestCommand.
 
T
- tankDrive(double, double) - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - teleopInit() - Method in class com.lightningrobotics.common.LightningRobot
 - 
The default implementation handles canceling the autonomous command.
 - testInit() - Method in class com.lightningrobotics.common.LightningRobot
 - 
The default implementation cancles all commands and releases the default commands from the subsystems, and schedules a
SystemTestCommand. - testPeriodic() - Method in class com.lightningrobotics.common.LightningRobot
 - ticksToDistance(double, double, double, double) - Static method in class com.lightningrobotics.common.util.LightningMath
 - 
Converts encoder ticks to a distance (units of input)
 - TimedCommand - Class in com.lightningrobotics.common.command.core
 - 
Command to run a command for a set time.
 - TimedCommand(Command, double) - Constructor for class com.lightningrobotics.common.command.core.TimedCommand
 - TimedFaultMonitor - Class in com.lightningrobotics.common.fault
 - 
A fault monitor that checks if a condition has existed for a given period of time
 - TimedFaultMonitor(LightningFaultCodes.Code, BooleanSupplier, double, String) - Constructor for class com.lightningrobotics.common.fault.TimedFaultMonitor
 - timeout - Variable in class com.lightningrobotics.common.command.core.TimedCommand
 - timeParameterizeTrajectory(List<PoseWithCurvature>, List<TrajectoryConstraint>, double, double, double, double, boolean) - Static method in class com.lightningrobotics.common.auto.trajectory.TrajectoryInterpolater
 - 
Parameterize the trajectory by time.
 - timer - Variable in class com.lightningrobotics.common.command.core.TimedCommand
 - timeSeconds - Variable in class com.lightningrobotics.common.auto.trajectory.TrajectoryState
 - 
The time elapsed since the beginning of the trajectory.
 - toJSONString() - Static method in class com.lightningrobotics.common.fault.FaultCode
 - 
Gets all the faults as a JSON String
 - toString() - Method in class com.lightningrobotics.common.geometry.kinematics.DrivetrainSpeed
 - toString() - Method in class com.lightningrobotics.common.geometry.kinematics.swerve.SwerveModuleState
 - Trajectory - Class in com.lightningrobotics.common.auto.trajectory
 - 
Represents a time-parameterized trajectory.
 - Trajectory() - Constructor for class com.lightningrobotics.common.auto.trajectory.Trajectory
 - 
Constructs an empty trajectory.
 - Trajectory(List<TrajectoryState>) - Constructor for class com.lightningrobotics.common.auto.trajectory.Trajectory
 - 
Constructs a trajectory from a vector of states.
 - TrajectoryConfig - Class in com.lightningrobotics.common.auto.trajectory
 - 
Represents the configuration for generating a trajectory.
 - TrajectoryConfig(LightningDrivetrain) - Constructor for class com.lightningrobotics.common.auto.trajectory.TrajectoryConfig
 - 
Constructs the trajectory configuration class.
 - TrajectoryConfig(LightningDrivetrain, boolean) - Constructor for class com.lightningrobotics.common.auto.trajectory.TrajectoryConfig
 - 
Constructs the trajectory configuration class.
 - TrajectoryConstraint - Interface in com.lightningrobotics.common.auto.trajectory
 - 
An interface for defining user-defined velocity and acceleration constraints while generating trajectories.
 - TrajectoryConstraint.AccelerationLimit - Class in com.lightningrobotics.common.auto.trajectory
 - 
Represents a minimum and maximum acceleration.
 - TrajectoryGenerationException(String) - Constructor for exception com.lightningrobotics.common.auto.trajectory.TrajectoryInterpolater.TrajectoryGenerationException
 - TrajectoryInterpolater - Class in com.lightningrobotics.common.auto.trajectory
 - 
Class used to parameterize a trajectory by time.
 - TrajectoryInterpolater.TrajectoryGenerationException - Exception in com.lightningrobotics.common.auto.trajectory
 - TrajectoryState - Class in com.lightningrobotics.common.auto.trajectory
 - 
Represents a time-parameterized trajectory.
 - TrajectoryState() - Constructor for class com.lightningrobotics.common.auto.trajectory.TrajectoryState
 - TrajectoryState(double, double, double, Pose2d, double) - Constructor for class com.lightningrobotics.common.auto.trajectory.TrajectoryState
 - 
Constructs a TrajectoryState with the specified parameters.
 - transformBy(Transform2d) - Method in class com.lightningrobotics.common.auto.trajectory.Trajectory
 - 
Transforms all poses in the trajectory by the given transform.
 - trigger() - Method in class com.lightningrobotics.common.fault.AbstractFaultMonitor
 - 
Writes the fault.
 - TwoButtonTrigger - Class in com.lightningrobotics.common.util.operator.trigger
 - 
Only performs the action, when both buttons are pressed.
 - TwoButtonTrigger(JoystickButton, JoystickButton) - Constructor for class com.lightningrobotics.common.util.operator.trigger.TwoButtonTrigger
 
U
- UnchangingFaultMonitor - Class in com.lightningrobotics.common.fault
 - 
A fault monitor that ensures a given value remains unchanged for a duration of time
 - UnchangingFaultMonitor(LightningFaultCodes.Code, DoubleSupplier, double, double, String) - Constructor for class com.lightningrobotics.common.fault.UnchangingFaultMonitor
 - update() - Static method in class com.lightningrobotics.common.fault.FaultCode
 - 
Updates the
NetworkTableEntryfor eachLightningFaultCodes.Code. - update(Rotation2d, double, double) - Method in class com.lightningrobotics.common.geometry.LightningOdometer
 - 
Updates the robot position on the field using distance measurements from encoders.
 
V
- ValueFilter - Interface in com.lightningrobotics.common.util.filter
 - valueOf(String) - Static method in enum com.lightningrobotics.common.subsystem.core.LightningIMU.IMUType
 - 
Returns the enum constant of this type with the specified name.
 - valueOf(String) - Static method in enum com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain.Modules
 - 
Returns the enum constant of this type with the specified name.
 - valueOf(String) - Static method in enum com.lightningrobotics.common.testing.SystemTest.Priority
 - 
Returns the enum constant of this type with the specified name.
 - valueOf(String) - Static method in enum com.lightningrobotics.common.util.filter.JoystickFilter.Mode
 - 
Returns the enum constant of this type with the specified name.
 - values() - Static method in enum com.lightningrobotics.common.subsystem.core.LightningIMU.IMUType
 - 
Returns an array containing the constants of this enum type, in the order they are declared.
 - values() - Static method in enum com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain.Modules
 - 
Returns an array containing the constants of this enum type, in the order they are declared.
 - values() - Static method in enum com.lightningrobotics.common.testing.SystemTest.Priority
 - 
Returns an array containing the constants of this enum type, in the order they are declared.
 - values() - Static method in enum com.lightningrobotics.common.util.filter.JoystickFilter.Mode
 - 
Returns an array containing the constants of this enum type, in the order they are declared.
 - velocity - Variable in class com.lightningrobotics.common.geometry.kinematics.swerve.SwerveModuleState
 - velocityMetersPerSecond - Variable in class com.lightningrobotics.common.auto.trajectory.TrajectoryState
 - 
The speed at that point of the trajectory.
 - vx - Variable in class com.lightningrobotics.common.geometry.kinematics.DrivetrainSpeed
 - 
Velocity in X direction
 - vy - Variable in class com.lightningrobotics.common.geometry.kinematics.DrivetrainSpeed
 - 
Velocity in Y direction
 
W
- WaitCommand - Class in com.lightningrobotics.common.command.core
 - 
Command that waits for a dashboard-determined amount of time to elapse before returning.
 - WaitCommand() - Constructor for class com.lightningrobotics.common.command.core.WaitCommand
 - 
Creates a new DashboardWaitCommand called
AutoWaitSecondsunderAutonomousshuffleboard tab. - WaitCommand(String) - Constructor for class com.lightningrobotics.common.command.core.WaitCommand
 - 
Creates a new DashboardWaitCommand under
Autonomousshuffleboard tab. - WaitCommand(String, String) - Constructor for class com.lightningrobotics.common.command.core.WaitCommand
 - 
Creates a new DashboardWaitCommand.
 - withEachAzimuthMotor(Consumer<MotorController>) - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain
 - withEachDriveMotor(Consumer<MotorController>) - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain
 - withEachLeftMotor(Consumer<MotorController>) - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - withEachModule(Consumer<SwerveModule>) - Method in class com.lightningrobotics.common.subsystem.drivetrain.swerve.SwerveDrivetrain
 - withEachMotor(BiConsumer<MotorController, MotorController>) - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - withEachMotor(Consumer<MotorController>) - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - withEachMotorIndexed(BiConsumer<MotorController, Integer>) - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - withEachRightMotor(Consumer<MotorController>) - Method in class com.lightningrobotics.common.subsystem.drivetrain.differential.DifferentialDrivetrain
 - write() - Method in class com.lightningrobotics.common.logging.CommandLogger
 - write(LightningFaultCodes.Code) - Static method in class com.lightningrobotics.common.fault.FaultCode
 - 
Writes the given fault code
 - write(LightningFaultCodes.Code, String) - Static method in class com.lightningrobotics.common.fault.FaultCode
 - 
Writes the fault code, effectively logging that it has been detected in a log file and the system error stream.
 - writeValues() - Method in class com.lightningrobotics.common.logging.CommandLogger
 
Z
- zero() - Method in class com.lightningrobotics.common.subsystem.core.LightningIMU
 - 
Function to reset IMU heading
 
All Classes All Packages