Upgrading to 2025.1.0

This commit is contained in:
thenetworkgrinch
2024-12-09 23:26:04 +00:00
parent 9fe6551d88
commit 4bc6978a20
35 changed files with 1902 additions and 1122 deletions

View File

@@ -1,14 +1,12 @@
package swervelib.imu;
import com.kauailabs.navx.frc.AHRS;
import com.studica.frc.AHRS;
import com.studica.frc.AHRS.NavXComType;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.wpilibj.I2C;
import edu.wpi.first.wpilibj.SPI;
import edu.wpi.first.wpilibj.SerialPort;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj.Alert;
import edu.wpi.first.wpilibj.Alert.AlertType;
import java.util.Optional;
import swervelib.telemetry.Alert;
/**
* Communicates with the NavX({@link AHRS}) as the IMU.
@@ -38,9 +36,9 @@ public class NavXSwerve extends SwerveIMU
*
* @param port Serial Port to connect to.
*/
public NavXSwerve(SerialPort.Port port)
public NavXSwerve(NavXComType port)
{
navXError = new Alert("IMU", "Error instantiating NavX.", Alert.AlertType.ERROR_TRACE);
navXError = new Alert("IMU", "Error instantiating NavX.", AlertType.kError);
try
{
/* Communicate w/navX-MXP via the MXP SPI Bus. */
@@ -48,7 +46,6 @@ public class NavXSwerve extends SwerveIMU
/* See http://navx-mxp.kauailabs.com/guidance/selecting-an-interface/ for details. */
imu = new AHRS(port);
factoryDefault();
SmartDashboard.putData(imu);
} catch (RuntimeException ex)
{
navXError.setText("Error instantiating NavX: " + ex.getMessage());
@@ -56,49 +53,6 @@ public class NavXSwerve extends SwerveIMU
}
}
/**
* Constructor for the NavX({@link AHRS}) swerve.
*
* @param port SPI Port to connect to.
*/
public NavXSwerve(SPI.Port port)
{
try
{
/* Communicate w/navX-MXP via the MXP SPI Bus. */
/* Alternatively: I2C.Port.kMXP, SerialPort.Port.kMXP or SerialPort.Port.kUSB */
/* See http://navx-mxp.kauailabs.com/guidance/selecting-an-interface/ for details. */
imu = new AHRS(port);
factoryDefault();
SmartDashboard.putData(imu);
} catch (RuntimeException ex)
{
navXError.setText("Error instantiating NavX: " + ex.getMessage());
navXError.set(true);
}
}
/**
* Constructor for the NavX({@link AHRS}) swerve.
*
* @param port I2C Port to connect to.
*/
public NavXSwerve(I2C.Port port)
{
try
{
/* Communicate w/navX-MXP via the MXP SPI Bus. */
/* Alternatively: I2C.Port.kMXP, SerialPort.Port.kMXP or SerialPort.Port.kUSB */
/* See http://navx-mxp.kauailabs.com/guidance/selecting-an-interface/ for details. */
imu = new AHRS(port);
factoryDefault();
SmartDashboard.putData(imu);
} catch (RuntimeException ex)
{
navXError.setText("Error instantiating NavX: " + ex.getMessage());
navXError.set(true);
}
}
/**
* Reset offset to current gyro reading. Does not call NavX({@link AHRS#reset()}) because it has been reported to be
@@ -137,6 +91,7 @@ public class NavXSwerve extends SwerveIMU
public void setInverted(boolean invertIMU)
{
invertedIMU = invertIMU;
setOffset(getRawRotation3d());
}
/**