Package swervelib.imu
Class AnalogGyroSwerve
java.lang.Object
swervelib.imu.SwerveIMU
swervelib.imu.AnalogGyroSwerve
Creates a IMU for
AnalogGyro
devices, only uses yaw.-
Field Summary
Modifier and TypeFieldDescriptionprivate final edu.wpi.first.wpilibj.AnalogGyro
Gyroscope object.private boolean
Inversion for the gyroprivate edu.wpi.first.math.geometry.Rotation3d
Offset for the analog gyro. -
Constructor Summary
ConstructorDescriptionAnalogGyroSwerve
(int channel) Analog port in which the gyroscope is connected. -
Method Summary
Modifier and TypeMethodDescriptionvoid
Clear sticky faults on IMU.void
Reset IMU to factory default.Optional<edu.wpi.first.math.geometry.Translation3d>
getAccel()
Fetch the acceleration [x, y, z] from the IMU in meters per second squared.getIMU()
Get the instantiated IMU object.edu.wpi.first.math.geometry.Rotation3d
Fetch theRotation3d
from the IMU without any zeroing.edu.wpi.first.math.geometry.Rotation3d
Fetch theRotation3d
from the IMU.void
setInverted
(boolean invertIMU) Set the gyro to invert its default directionvoid
setOffset
(edu.wpi.first.math.geometry.Rotation3d offset) Set the gyro offset.
-
Field Details
-
gyro
private final edu.wpi.first.wpilibj.AnalogGyro gyroGyroscope object. -
offset
private edu.wpi.first.math.geometry.Rotation3d offsetOffset for the analog gyro. -
invertedIMU
private boolean invertedIMUInversion for the gyro
-
-
Constructor Details
-
AnalogGyroSwerve
public AnalogGyroSwerve(int channel) Analog port in which the gyroscope is connected. Can only be attached to analog ports 0 or 1.- Parameters:
channel
- Analog port 0 or 1.
-
-
Method Details
-
factoryDefault
public void factoryDefault()Reset IMU to factory default.- Specified by:
factoryDefault
in classSwerveIMU
-
clearStickyFaults
public void clearStickyFaults()Clear sticky faults on IMU.- Specified by:
clearStickyFaults
in classSwerveIMU
-
setOffset
public void setOffset(edu.wpi.first.math.geometry.Rotation3d offset) Set the gyro offset. -
setInverted
public void setInverted(boolean invertIMU) Set the gyro to invert its default direction- Specified by:
setInverted
in classSwerveIMU
- Parameters:
invertIMU
- invert gyro direction
-
getRawRotation3d
public edu.wpi.first.math.geometry.Rotation3d getRawRotation3d()Fetch theRotation3d
from the IMU without any zeroing. Robot relative.- Specified by:
getRawRotation3d
in classSwerveIMU
- Returns:
Rotation3d
from the IMU.
-
getRotation3d
public edu.wpi.first.math.geometry.Rotation3d getRotation3d()Fetch theRotation3d
from the IMU. Robot relative.- Specified by:
getRotation3d
in classSwerveIMU
- Returns:
Rotation3d
from the IMU.
-
getAccel
Fetch the acceleration [x, y, z] from the IMU in meters per second squared. If acceleration isn't supported returns empty. -
getIMU
Get the instantiated IMU object.
-