mirror of
https://github.com/BroncBotz3481/YAGSL
synced 2026-06-19 06:21:40 +00:00
137 lines
3.3 KiB
Java
137 lines
3.3 KiB
Java
package swervelib.imu;
|
|
|
|
import com.ctre.phoenix6.StatusSignal;
|
|
import com.ctre.phoenix6.configs.Pigeon2Configuration;
|
|
import com.ctre.phoenix6.configs.Pigeon2Configurator;
|
|
import com.ctre.phoenix6.hardware.Pigeon2;
|
|
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.smartdashboard.SmartDashboard;
|
|
import java.util.Optional;
|
|
|
|
/**
|
|
* SwerveIMU interface for the Pigeon2
|
|
*/
|
|
public class Pigeon2Swerve extends SwerveIMU
|
|
{
|
|
|
|
/**
|
|
* Pigeon2 IMU device.
|
|
*/
|
|
Pigeon2 imu;
|
|
/**
|
|
* Offset for the Pigeon 2.
|
|
*/
|
|
private Rotation3d offset = new Rotation3d();
|
|
|
|
/**
|
|
* Generate the SwerveIMU for pigeon.
|
|
*
|
|
* @param canid CAN ID for the pigeon
|
|
* @param canbus CAN Bus name the pigeon resides on.
|
|
*/
|
|
public Pigeon2Swerve(int canid, String canbus)
|
|
{
|
|
imu = new Pigeon2(canid, canbus);
|
|
SmartDashboard.putData(imu);
|
|
}
|
|
|
|
/**
|
|
* Generate the SwerveIMU for pigeon.
|
|
*
|
|
* @param canid CAN ID for the pigeon
|
|
*/
|
|
public Pigeon2Swerve(int canid)
|
|
{
|
|
this(canid, "");
|
|
}
|
|
|
|
/**
|
|
* Reset IMU to factory default.
|
|
*/
|
|
@Override
|
|
public void factoryDefault()
|
|
{
|
|
Pigeon2Configurator cfg = imu.getConfigurator();
|
|
Pigeon2Configuration config = new Pigeon2Configuration();
|
|
|
|
// Compass utilization causes readings to jump dramatically in some cases.
|
|
cfg.apply(config.Pigeon2Features.withEnableCompass(false));
|
|
}
|
|
|
|
/**
|
|
* Clear sticky faults on IMU.
|
|
*/
|
|
@Override
|
|
public void clearStickyFaults()
|
|
{
|
|
imu.clearStickyFaults();
|
|
}
|
|
|
|
/**
|
|
* Set the gyro offset.
|
|
*
|
|
* @param offset gyro offset as a {@link Rotation3d}.
|
|
*/
|
|
public void setOffset(Rotation3d offset)
|
|
{
|
|
this.offset = offset;
|
|
}
|
|
|
|
/**
|
|
* Fetch the {@link Rotation3d} from the IMU without any zeroing. Robot relative.
|
|
*
|
|
* @return {@link Rotation3d} from the IMU.
|
|
*/
|
|
@Override
|
|
public Rotation3d getRawRotation3d()
|
|
{
|
|
// TODO: Switch to suppliers.
|
|
StatusSignal<Double> w = imu.getQuatW();
|
|
StatusSignal<Double> x = imu.getQuatX();
|
|
StatusSignal<Double> y = imu.getQuatY();
|
|
StatusSignal<Double> z = imu.getQuatZ();
|
|
return new Rotation3d(new Quaternion(w.refresh().getValue(), x.refresh().getValue(), y.refresh().getValue(), z.refresh().getValue()));
|
|
}
|
|
|
|
/**
|
|
* Fetch the {@link Rotation3d} from the IMU. Robot relative.
|
|
*
|
|
* @return {@link Rotation3d} from the IMU.
|
|
*/
|
|
@Override
|
|
public Rotation3d getRotation3d()
|
|
{
|
|
return getRawRotation3d().minus(offset);
|
|
}
|
|
|
|
/**
|
|
* Fetch the acceleration [x, y, z] from the IMU in meters per second squared. If acceleration isn't supported returns
|
|
* empty.
|
|
*
|
|
* @return {@link Translation3d} of the acceleration as an {@link Optional}.
|
|
*/
|
|
@Override
|
|
public Optional<Translation3d> getAccel()
|
|
{
|
|
// TODO: Switch to suppliers.
|
|
StatusSignal<Double> xAcc = imu.getAccelerationX();
|
|
StatusSignal<Double> yAcc = imu.getAccelerationX();
|
|
StatusSignal<Double> zAcc = imu.getAccelerationX();
|
|
|
|
return Optional.of(new Translation3d(xAcc.refresh().getValue(), yAcc.refresh().getValue(), zAcc.refresh().getValue()).times(9.81 / 16384.0));
|
|
}
|
|
|
|
/**
|
|
* Get the instantiated IMU object.
|
|
*
|
|
* @return IMU object.
|
|
*/
|
|
@Override
|
|
public Object getIMU()
|
|
{
|
|
return imu;
|
|
}
|
|
}
|