Updated to 2024.4.6.1

This commit is contained in:
thenetworkgrinch
2024-01-22 15:11:18 -06:00
parent 7c76cffc78
commit a20a6b83af
120 changed files with 923 additions and 603 deletions

View File

@@ -19,7 +19,11 @@ public class ADIS16448Swerve extends SwerveIMU
/**
* Offset for the ADIS16448.
*/
private Rotation3d offset = new Rotation3d();
private Rotation3d offset = new Rotation3d();
/**
* Inversion for the gyro
*/
private boolean invertedIMU = false;
/**
* Construct the ADIS16448 imu and reset default configurations. Publish the gyro to the SmartDashboard.
@@ -60,6 +64,16 @@ public class ADIS16448Swerve extends SwerveIMU
this.offset = offset;
}
/**
* Set the gyro to invert its default direction
*
* @param invertIMU invert gyro direction
*/
public void setInverted(boolean invertIMU)
{
invertedIMU = invertIMU;
}
/**
* Fetch the {@link Rotation3d} from the IMU without any zeroing. Robot relative.
*
@@ -67,9 +81,10 @@ public class ADIS16448Swerve extends SwerveIMU
*/
public Rotation3d getRawRotation3d()
{
return new Rotation3d(Math.toRadians(-imu.getGyroAngleX()),
Math.toRadians(-imu.getGyroAngleY()),
Math.toRadians(-imu.getGyroAngleZ()));
Rotation3d reading = new Rotation3d(Math.toRadians(-imu.getGyroAngleX()),
Math.toRadians(-imu.getGyroAngleY()),
Math.toRadians(-imu.getGyroAngleZ()));
return invertedIMU ? reading.unaryMinus() : reading;
}
/**