Package frc.lib5k.components.gyroscopes
Class NavX
- java.lang.Object
-
- edu.wpi.first.wpilibj.SendableBase
-
- com.kauailabs.navx.frc.AHRS
-
- frc.lib5k.components.gyroscopes.NavX
-
- All Implemented Interfaces:
edu.wpi.first.wpilibj.PIDSource
,edu.wpi.first.wpilibj.Sendable
,java.lang.AutoCloseable
public class NavX extends com.kauailabs.navx.frc.AHRS
A wrapper for the AHRS / NavX gyroscope
-
-
Method Summary
All Methods Static Methods Instance Methods Concrete Methods Modifier and Type Method Description double
getAngle()
double
getHeading()
Returns the heading of the robot.static NavX
getInstance()
Get the Default NavX instancedouble
getRate()
edu.wpi.first.wpilibj.geometry.Rotation2d
getRotation()
Get the NavX heading as a Rotation2d objectdouble
getWrappedAngle()
Get the gyro angle, wrapped by 360 degreesvoid
initDrivebaseSimulation(IDifferentialDrivebase drivebase)
void
setInverted(boolean inverted)
Set if the NavX readings should be inverted-
Methods inherited from class com.kauailabs.navx.frc.AHRS
deregisterCallback, enableBoardlevelYawReset, enableLogging, getAccelFullScaleRangeG, getActualUpdateRate, getAltitude, getAngleAdjustment, getBarometricPressure, getBoardYawAxis, getByteCount, getCompassHeading, getDisplacementX, getDisplacementY, getDisplacementZ, getFirmwareVersion, getFusedHeading, getGyroFullScaleRangeDPS, getLastSensorTimestamp, getPIDSourceType, getPitch, getPressure, getQuaternionW, getQuaternionX, getQuaternionY, getQuaternionZ, getRawAccelX, getRawAccelY, getRawAccelZ, getRawGyroX, getRawGyroY, getRawGyroZ, getRawMagX, getRawMagY, getRawMagZ, getRequestedUpdateRate, getRoll, getTempC, getUpdateCount, getVelocityX, getVelocityY, getVelocityZ, getWorldLinearAccelX, getWorldLinearAccelY, getWorldLinearAccelZ, getYaw, initSendable, isAltitudeValid, isBoardlevelYawResetEnabled, isCalibrating, isConnected, isMagneticDisturbance, isMagnetometerCalibrated, isMoving, isRotating, pidGet, registerCallback, reset, resetDisplacement, setAngleAdjustment, setPIDSourceType, zeroYaw
-
-
-
-
Method Detail
-
getInstance
public static NavX getInstance()
Get the Default NavX instance- Returns:
- NavX instance
-
initDrivebaseSimulation
public void initDrivebaseSimulation(IDifferentialDrivebase drivebase)
-
setInverted
public void setInverted(boolean inverted)
Set if the NavX readings should be inverted- Parameters:
inverted
- Is NavX inverted?
-
getAngle
public double getAngle()
- Overrides:
getAngle
in classcom.kauailabs.navx.frc.AHRS
-
getHeading
public double getHeading()
Returns the heading of the robot.- Returns:
- the robot's heading in degrees, from 180 to 180
-
getRate
public double getRate()
- Overrides:
getRate
in classcom.kauailabs.navx.frc.AHRS
-
getWrappedAngle
public double getWrappedAngle()
Get the gyro angle, wrapped by 360 degrees- Returns:
- Wrapped angle
-
getRotation
public edu.wpi.first.wpilibj.geometry.Rotation2d getRotation()
Get the NavX heading as a Rotation2d object- Returns:
- Heading
-
-