mirror of
https://github.com/BroncBotz3481/YAGSL
synced 2026-06-19 06:21:40 +00:00
Added new encoders, updated docs, safety's
This commit is contained in:
@@ -5,6 +5,8 @@ import edu.wpi.first.math.geometry.Quaternion;
|
||||
import edu.wpi.first.math.geometry.Rotation3d;
|
||||
import edu.wpi.first.math.geometry.Translation3d;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
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 java.util.Optional;
|
||||
@@ -41,7 +43,49 @@ public class NavXSwerve extends SwerveIMU
|
||||
SmartDashboard.putData(gyro);
|
||||
} catch (RuntimeException ex)
|
||||
{
|
||||
DriverStation.reportError("Error instantiating navX-MXP: " + ex.getMessage(), true);
|
||||
DriverStation.reportError("Error instantiating navX: " + ex.getMessage(), true);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor for the NavX 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. */
|
||||
gyro = new AHRS(port);
|
||||
factoryDefault();
|
||||
SmartDashboard.putData(gyro);
|
||||
} catch (RuntimeException ex)
|
||||
{
|
||||
DriverStation.reportError("Error instantiating navX: " + ex.getMessage(), true);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor for the NavX 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. */
|
||||
gyro = new AHRS(port);
|
||||
factoryDefault();
|
||||
SmartDashboard.putData(gyro);
|
||||
} catch (RuntimeException ex)
|
||||
{
|
||||
DriverStation.reportError("Error instantiating navX: " + ex.getMessage(), true);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user