Files
YAGSL/swervelib/imu/Pigeon2Swerve.java

190 lines
4.7 KiB
Java
Raw Normal View History

2023-02-13 17:21:24 -06:00
package swervelib.imu;
2023-02-13 14:37:05 -06:00
2024-12-09 23:26:04 +00:00
import static edu.wpi.first.units.Units.DegreesPerSecond;
2024-01-15 14:37:13 -06:00
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.Rotation3d;
import edu.wpi.first.math.geometry.Translation3d;
2024-12-09 23:26:04 +00:00
import edu.wpi.first.units.measure.LinearAcceleration;
2024-12-17 18:49:55 +00:00
import edu.wpi.first.units.measure.MutAngularVelocity;
2023-02-13 14:37:05 -06:00
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import java.util.Optional;
2024-12-09 23:26:04 +00:00
import java.util.function.Supplier;
2023-02-13 14:37:05 -06:00
/**
2024-11-06 00:10:07 +00:00
* SwerveIMU interface for the {@link Pigeon2}
2023-02-13 14:37:05 -06:00
*/
public class Pigeon2Swerve extends SwerveIMU
{
2024-02-02 18:55:29 -06:00
/**
* Wait time for status frames to show up.
*/
2025-02-22 06:15:56 +00:00
public static double STATUS_TIMEOUT_SECONDS = 0.04;
2023-02-13 14:37:05 -06:00
/**
2024-11-06 00:10:07 +00:00
* {@link Pigeon2} IMU device.
2023-02-13 14:37:05 -06:00
*/
2025-02-22 06:15:56 +00:00
private final Pigeon2 imu;
2024-12-17 18:49:55 +00:00
/**
2025-02-22 06:15:56 +00:00
* Mutable {@link MutAngularVelocity} for readings.
2024-12-17 18:49:55 +00:00
*/
2025-02-22 06:15:56 +00:00
private final MutAngularVelocity yawVel = new MutAngularVelocity(0,
0,
DegreesPerSecond);
2023-03-08 23:34:33 -06:00
/**
2025-02-22 06:15:56 +00:00
* X Acceleration supplier
2023-03-08 23:34:33 -06:00
*/
2025-02-22 06:15:56 +00:00
private final Supplier<StatusSignal<LinearAcceleration>> xAcc;
2024-01-22 15:11:18 -06:00
/**
2025-02-22 06:15:56 +00:00
* Y Accelleration supplier.
2024-01-22 15:11:18 -06:00
*/
2025-02-22 06:15:56 +00:00
private final Supplier<StatusSignal<LinearAcceleration>> yAcc;
2024-10-14 13:22:11 -05:00
/**
2025-02-22 06:15:56 +00:00
* Z Acceleration supplier.
2024-10-14 13:22:11 -05:00
*/
2025-02-22 06:15:56 +00:00
private final Supplier<StatusSignal<LinearAcceleration>> zAcc;
2024-12-09 23:26:04 +00:00
/**
2025-02-22 06:15:56 +00:00
* Offset for the {@link Pigeon2}.
2024-12-09 23:26:04 +00:00
*/
2025-02-22 06:15:56 +00:00
private Rotation3d offset = new Rotation3d();
2024-12-09 23:26:04 +00:00
/**
2025-02-22 06:15:56 +00:00
* Inversion for the gyro
2024-12-09 23:26:04 +00:00
*/
2025-02-22 06:15:56 +00:00
private boolean invertedIMU = false;
2024-12-09 23:26:04 +00:00
/**
2025-02-22 06:15:56 +00:00
* {@link Pigeon2} configurator.
2024-12-09 23:26:04 +00:00
*/
2025-02-22 06:15:56 +00:00
private Pigeon2Configurator cfg;
2024-12-09 23:26:04 +00:00
2023-02-13 14:37:05 -06:00
/**
2024-11-06 00:10:07 +00:00
* Generate the SwerveIMU for {@link Pigeon2}.
2023-02-13 14:37:05 -06:00
*
2024-11-06 00:10:07 +00:00
* @param canid CAN ID for the {@link Pigeon2}
* @param canbus CAN Bus name the {@link Pigeon2} resides on.
2023-02-13 14:37:05 -06:00
*/
public Pigeon2Swerve(int canid, String canbus)
{
2024-01-15 14:37:13 -06:00
imu = new Pigeon2(canid, canbus);
2024-10-14 13:22:11 -05:00
this.cfg = imu.getConfigurator();
2024-12-09 23:26:04 +00:00
xAcc = imu::getAccelerationX;
yAcc = imu::getAccelerationY;
zAcc = imu::getAccelerationZ;
2023-02-13 14:37:05 -06:00
SmartDashboard.putData(imu);
}
/**
2024-11-06 00:10:07 +00:00
* Generate the SwerveIMU for {@link Pigeon2}.
2023-02-13 14:37:05 -06:00
*
2024-11-06 00:10:07 +00:00
* @param canid CAN ID for the {@link Pigeon2}
2023-02-13 14:37:05 -06:00
*/
public Pigeon2Swerve(int canid)
{
this(canid, "");
}
2025-02-22 06:15:56 +00:00
@Override
public void close() {
imu.close();
}
2023-02-13 14:37:05 -06:00
/**
2024-11-06 00:10:07 +00:00
* Reset {@link Pigeon2} to factory default.
2023-02-13 14:37:05 -06:00
*/
@Override
public void factoryDefault()
{
2024-01-15 14:37:13 -06:00
Pigeon2Configuration config = new Pigeon2Configuration();
// Compass utilization causes readings to jump dramatically in some cases.
cfg.apply(config.Pigeon2Features.withEnableCompass(false));
2023-02-13 14:37:05 -06:00
}
/**
2024-11-06 00:10:07 +00:00
* Clear sticky faults on {@link Pigeon2}.
2023-02-13 14:37:05 -06:00
*/
@Override
public void clearStickyFaults()
{
imu.clearStickyFaults();
}
/**
2023-03-08 23:34:33 -06:00
* Set the gyro offset.
2023-02-13 14:37:05 -06:00
*
2023-03-08 23:34:33 -06:00
* @param offset gyro offset as a {@link Rotation3d}.
2023-02-13 14:37:05 -06:00
*/
2023-03-08 23:34:33 -06:00
public void setOffset(Rotation3d offset)
2023-02-13 14:37:05 -06:00
{
this.offset = offset;
2023-02-13 14:37:05 -06:00
}
2024-01-22 15:11:18 -06:00
/**
* Set the gyro to invert its default direction
*
* @param invertIMU invert gyro direction
*/
public void setInverted(boolean invertIMU)
{
invertedIMU = invertIMU;
}
2023-02-13 14:37:05 -06:00
/**
2023-03-08 23:34:33 -06:00
* Fetch the {@link Rotation3d} from the IMU without any zeroing. Robot relative.
2023-02-13 14:37:05 -06:00
*
2023-03-08 23:34:33 -06:00
* @return {@link Rotation3d} from the IMU.
2023-02-13 14:37:05 -06:00
*/
@Override
2023-03-08 23:34:33 -06:00
public Rotation3d getRawRotation3d()
2023-02-13 14:37:05 -06:00
{
2024-02-12 18:59:40 -06:00
Rotation3d reading = imu.getRotation3d();
2024-01-22 15:11:18 -06:00
return invertedIMU ? reading.unaryMinus() : reading;
2023-02-13 14:37:05 -06:00
}
/**
* Fetch the {@link Rotation3d} from the IMU. Robot relative.
*
* @return {@link Rotation3d} from the IMU.
*/
@Override
public Rotation3d getRotation3d()
{
2025-03-19 03:45:47 +00:00
return getRawRotation3d().rotateBy(offset.unaryMinus());
}
2024-12-09 23:26:04 +00:00
/**
* 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()
{
2025-02-22 06:15:56 +00:00
return Optional.of(new Translation3d(xAcc.get().getValueAsDouble(),
yAcc.get().getValueAsDouble(),
zAcc.get().getValueAsDouble()));
}
2024-12-17 18:49:55 +00:00
@Override
public MutAngularVelocity getYawAngularVelocity()
2024-08-24 17:40:19 -05:00
{
2025-02-22 06:15:56 +00:00
return yawVel.mut_replace(imu.getAngularVelocityZWorld().refresh().getValue());
2024-08-24 17:27:03 -05:00
}
2023-02-13 14:37:05 -06:00
/**
2024-11-06 00:10:07 +00:00
* Get the instantiated {@link Pigeon2} object.
2023-02-13 14:37:05 -06:00
*
* @return IMU object.
*/
@Override
public Object getIMU()
{
return imu;
}
}