Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Reduce GC pressure a bit through Rotation2d.kZero #138

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -49,9 +49,9 @@ public class Drive extends SubsystemBase {
private final double kS = Constants.currentMode == Mode.SIM ? simKs : realKs;
private final double kV = Constants.currentMode == Mode.SIM ? simKv : realKv;
private final DifferentialDrivePoseEstimator poseEstimator =
new DifferentialDrivePoseEstimator(kinematics, new Rotation2d(), 0.0, 0.0, new Pose2d());
new DifferentialDrivePoseEstimator(kinematics, Rotation2d.kZero, 0.0, 0.0, new Pose2d());
private final SysIdRoutine sysId;
private Rotation2d rawGyroRotation = new Rotation2d();
private Rotation2d rawGyroRotation = Rotation2d.kZero;
private double lastLeftPositionMeters = 0.0;
private double lastRightPositionMeters = 0.0;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ public interface GyroIO {
@AutoLog
public static class GyroIOInputs {
public boolean connected = false;
public Rotation2d yawPosition = new Rotation2d();
public Rotation2d yawPosition = Rotation2d.kZero;
public double yawVelocityRadPerSec = 0.0;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,9 +49,9 @@ public class Drive extends SubsystemBase {
private final double kS = Constants.currentMode == Mode.SIM ? simKs : realKs;
private final double kV = Constants.currentMode == Mode.SIM ? simKv : realKv;
private final DifferentialDrivePoseEstimator poseEstimator =
new DifferentialDrivePoseEstimator(kinematics, new Rotation2d(), 0.0, 0.0, new Pose2d());
new DifferentialDrivePoseEstimator(kinematics, Rotation2d.kZero, 0.0, 0.0, new Pose2d());
private final SysIdRoutine sysId;
private Rotation2d rawGyroRotation = new Rotation2d();
private Rotation2d rawGyroRotation = Rotation2d.kZero;
private double lastLeftPositionMeters = 0.0;
private double lastRightPositionMeters = 0.0;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ public interface GyroIO {
@AutoLog
public static class GyroIOInputs {
public boolean connected = false;
public Rotation2d yawPosition = new Rotation2d();
public Rotation2d yawPosition = Rotation2d.kZero;
public double yawVelocityRadPerSec = 0.0;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ private void configureButtonBindings() {
drive,
() -> -controller.getLeftY(),
() -> -controller.getLeftX(),
() -> new Rotation2d()));
() -> Rotation2d.kZero));

// Switch to X pattern when X button is pressed
controller.x().onTrue(Commands.runOnce(drive::stopWithX, drive));
Expand All @@ -142,7 +142,7 @@ private void configureButtonBindings() {
Commands.runOnce(
() ->
drive.setPose(
new Pose2d(drive.getPose().getTranslation(), new Rotation2d())),
new Pose2d(drive.getPose().getTranslation(), Rotation2d.kZero)),
drive)
.ignoringDisable(true));
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ private static Translation2d getLinearVelocityFromJoysticks(double x, double y)

// Return new linear velocity
return new Pose2d(new Translation2d(), linearDirection)
.transformBy(new Transform2d(linearMagnitude, 0.0, new Rotation2d()))
.transformBy(new Transform2d(linearMagnitude, 0.0, Rotation2d.kZero))
.getTranslation();
}

Expand Down Expand Up @@ -292,7 +292,7 @@ public static Command wheelRadiusCharacterization(Drive drive) {

private static class WheelRadiusCharacterizationState {
double[] positions = new double[4];
Rotation2d lastAngle = new Rotation2d();
Rotation2d lastAngle = Rotation2d.kZero;
double gyroDelta = 0.0;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ public class Drive extends SubsystemBase {
new Alert("Disconnected gyro, using kinematics as fallback.", AlertType.kError);

private SwerveDriveKinematics kinematics = new SwerveDriveKinematics(moduleTranslations);
private Rotation2d rawGyroRotation = new Rotation2d();
private Rotation2d rawGyroRotation = Rotation2d.kZero;
private SwerveModulePosition[] lastModulePositions = // For delta tracking
new SwerveModulePosition[] {
new SwerveModulePosition(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ public interface GyroIO {
@AutoLog
public static class GyroIOInputs {
public boolean connected = false;
public Rotation2d yawPosition = new Rotation2d();
public Rotation2d yawPosition = Rotation2d.kZero;
public double yawVelocityRadPerSec = 0.0;
public double[] odometryYawTimestamps = new double[] {};
public Rotation2d[] odometryYawPositions = new Rotation2d[] {};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ public void runSetpoint(SwerveModuleState state) {
/** Runs the module with the specified output while controlling to zero degrees. */
public void runCharacterization(double output) {
io.setDriveOpenLoop(output);
io.setTurnPosition(new Rotation2d());
io.setTurnPosition(Rotation2d.kZero);
}

/** Disables all outputs to motors. */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ public static class ModuleIOInputs {
public double driveCurrentAmps = 0.0;

public boolean turnConnected = false;
public Rotation2d turnPosition = new Rotation2d();
public Rotation2d turnPosition = Rotation2d.kZero;
public double turnVelocityRadPerSec = 0.0;
public double turnAppliedVolts = 0.0;
public double turnCurrentAmps = 0.0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ public ModuleIOSpark(int module) {
case 1 -> frontRightZeroRotation;
case 2 -> backLeftZeroRotation;
case 3 -> backRightZeroRotation;
default -> new Rotation2d();
default -> Rotation2d.kZero;
};
driveSpark =
new SparkFlex(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ private void configureButtonBindings() {
drive,
() -> -controller.getLeftY(),
() -> -controller.getLeftX(),
() -> new Rotation2d()));
() -> Rotation2d.kZero));

// Switch to X pattern when X button is pressed
controller.x().onTrue(Commands.runOnce(drive::stopWithX, drive));
Expand All @@ -143,7 +143,7 @@ private void configureButtonBindings() {
Commands.runOnce(
() ->
drive.setPose(
new Pose2d(drive.getPose().getTranslation(), new Rotation2d())),
new Pose2d(drive.getPose().getTranslation(), Rotation2d.kZero)),
drive)
.ignoringDisable(true));
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ private static Translation2d getLinearVelocityFromJoysticks(double x, double y)

// Return new linear velocity
return new Pose2d(new Translation2d(), linearDirection)
.transformBy(new Transform2d(linearMagnitude, 0.0, new Rotation2d()))
.transformBy(new Transform2d(linearMagnitude, 0.0, Rotation2d.kZero))
.getTranslation();
}

Expand Down Expand Up @@ -290,7 +290,7 @@ public static Command wheelRadiusCharacterization(Drive drive) {

private static class WheelRadiusCharacterizationState {
double[] positions = new double[4];
Rotation2d lastAngle = new Rotation2d();
Rotation2d lastAngle = Rotation2d.kZero;
double gyroDelta = 0.0;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ public class Drive extends SubsystemBase {
new Alert("Disconnected gyro, using kinematics as fallback.", AlertType.kError);

private SwerveDriveKinematics kinematics = new SwerveDriveKinematics(getModuleTranslations());
private Rotation2d rawGyroRotation = new Rotation2d();
private Rotation2d rawGyroRotation = Rotation2d.kZero;
private SwerveModulePosition[] lastModulePositions = // For delta tracking
new SwerveModulePosition[] {
new SwerveModulePosition(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ public interface GyroIO {
@AutoLog
public static class GyroIOInputs {
public boolean connected = false;
public Rotation2d yawPosition = new Rotation2d();
public Rotation2d yawPosition = Rotation2d.kZero;
public double yawVelocityRadPerSec = 0.0;
public double[] odometryYawTimestamps = new double[] {};
public Rotation2d[] odometryYawPositions = new Rotation2d[] {};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ public void runSetpoint(SwerveModuleState state) {
/** Runs the module with the specified output while controlling to zero degrees. */
public void runCharacterization(double output) {
io.setDriveOpenLoop(output);
io.setTurnPosition(new Rotation2d());
io.setTurnPosition(Rotation2d.kZero);
}

/** Disables all outputs to motors. */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@ public static class ModuleIOInputs {

public boolean turnConnected = false;
public boolean turnEncoderConnected = false;
public Rotation2d turnAbsolutePosition = new Rotation2d();
public Rotation2d turnPosition = new Rotation2d();
public Rotation2d turnAbsolutePosition = Rotation2d.kZero;
public Rotation2d turnPosition = Rotation2d.kZero;
public double turnVelocityRadPerSec = 0.0;
public double turnAppliedVolts = 0.0;
public double turnCurrentAmps = 0.0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ public class DemoDrive extends SubsystemBase {
private final DifferentialDrivePoseEstimator poseEstimator =
new DifferentialDrivePoseEstimator(
new DifferentialDriveKinematics(Units.inchesToMeters(26)),
new Rotation2d(),
Rotation2d.kZero,
0.0,
0.0,
new Pose2d());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ public interface VisionIO {
public static class VisionIOInputs {
public boolean connected = false;
public TargetObservation latestTargetObservation =
new TargetObservation(new Rotation2d(), new Rotation2d());
new TargetObservation(Rotation2d.kZero, Rotation2d.kZero);
public PoseObservation[] poseObservations = new PoseObservation[0];
public int[] tagIds = new int[0];
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ public void updateInputs(VisionIOInputs inputs) {
Rotation2d.fromDegrees(result.getBestTarget().getYaw()),
Rotation2d.fromDegrees(result.getBestTarget().getPitch()));
} else {
inputs.latestTargetObservation = new TargetObservation(new Rotation2d(), new Rotation2d());
inputs.latestTargetObservation = new TargetObservation(Rotation2d.kZero, Rotation2d.kZero);
}

// Add pose observation
Expand Down