Skip to content
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
43 changes: 43 additions & 0 deletions src/main/java/frc/robot/subsystems/GyroSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
package frc.robot.subsystems;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.utils.logging.io.gyro.GyroIo;
import frc.robot.utils.logging.io.gyro.MockGyroIo;
import frc.robot.utils.logging.io.gyro.RealGyroIo;
import frc.robot.utils.simulation.RobotVisualizer;

public class GyroSubsystem extends SubsystemBase {
private final GyroIo io;

public GyroSubsystem(GyroIo io) {
this.io = io;
}

public void setAngleOffset(double offset) {
io.setAngleOffset(offset);
}

public void resetGyro() {
io.resetGyro();
}

@Override
public void periodic() {
io.periodic();
}

public static GyroIo createMockIo() {
return new MockGyroIo();
}

public static GyroIo createRealIo() {
RealGyroIo realGyroIo = new RealGyroIo();
realGyroIo.start();
return realGyroIo;
}

public static GyroIo createSimIo(RobotVisualizer visualizer) {
// For now, we don't actually simulate the gyro
return new MockGyroIo();
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/RollerSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ public void periodic() {
}

public static SparkMaxIo createMockIo() {
return new MockSparkMaxIo();
return new MockSparkMaxIo(LOGGING_NAME, MotorLoggableInputs.allMetrics());
}

public static SparkMaxIo createRealIo() {
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/TiltSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ public void periodic() {
}

public static SparkMaxIo createMockIo() {
return new MockSparkMaxIo();
return new MockSparkMaxIo(LOGGING_NAME, MotorLoggableInputs.allMetrics());
}

public static SparkMaxIo createRealIo() {
Expand Down
81 changes: 81 additions & 0 deletions src/main/java/frc/robot/utils/logging/input/GyroInputs.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
package frc.robot.utils.logging.input;

import org.littletonrobotics.junction.LogTable;
import org.littletonrobotics.junction.inputs.LoggableInputs;

public class GyroInputs implements LoggableInputs {

private GyroValues values;

public GyroValues getGyroValues() {
return values;
}

@Override
public void toLog(LogTable table) {
table.put("anglesInDeg", values.getAnglesInDeg());
table.put("angleOffset", values.getAngleOffset());
table.put("worldLinearAccelX", values.getWorldLinearAccelX());
table.put("worldLinearAccelY", values.getWorldLinearAccelY());
table.put("worldLinearAccelZ", values.getWorldLinearAccelZ());
table.put("velocityX", values.getVelocityX());
table.put("velocityY", values.getVelocityY());
table.put("velocityZ", values.getVelocityZ());
table.put("displacementX", values.getDisplacementX());
table.put("displacementY", values.getDisplacementY());
table.put("displacementZ", values.getDisplacementZ());
table.put("rawGyroX", values.getRawGyroX());
table.put("rawGyroY", values.getRawGyroY());
table.put("rawGyroZ", values.getRawGyroZ());
table.put("rawAccelX", values.getRawAccelX());
table.put("rawAccelY", values.getRawAccelY());
table.put("rawAccelZ", values.getRawAccelZ());
table.put("rawMagX", values.getRawMagX());
table.put("rawMagY", values.getRawMagY());
table.put("rawMagZ", values.getRawMagZ());
table.put("yaw", values.getYaw());
table.put("pitch", values.getPitch());
table.put("roll", values.getRoll());
table.put("fusedHeading", values.getFusedHeading());
table.put("compassHeading", values.getCompassHeading());
table.put("robotCentricVelocityX", values.getRobotCentricVelocityX());
table.put("robotCentricVelocityY", values.getRobotCentricVelocityY());
table.put("robotCentricVelocityZ", values.getRobotCentricVelocityZ());
}

@Override
public void fromLog(LogTable table) {
values.setAnglesInDeg(table.get("anglesInDeg", values.getAnglesInDeg()));
values.setAngleOffset(table.get("angleOffset", values.getAngleOffset()));
values.setWorldLinearAccelX(table.get("worldLinearAccelX", values.getWorldLinearAccelX()));
values.setWorldLinearAccelY(table.get("worldLinearAccelY", values.getWorldLinearAccelY()));
values.setWorldLinearAccelZ(table.get("worldLinearAccelZ", values.getWorldLinearAccelZ()));
values.setVelocityX(table.get("velocityX", values.getVelocityX()));
values.setVelocityY(table.get("velocityY", values.getVelocityY()));
values.setVelocityZ(table.get("velocityZ", values.getVelocityZ()));
values.setDisplacementX(table.get("displacementX", values.getDisplacementX()));
values.setDisplacementY(table.get("displacementY", values.getDisplacementY()));
values.setDisplacementZ(table.get("displacementZ", values.getDisplacementZ()));
values.setRawGyroX(table.get("rawGyroX", values.getRawGyroX()));
values.setRawGyroY(table.get("rawGyroY", values.getRawGyroY()));
values.setRawGyroZ(table.get("rawGyroZ", values.getRawGyroZ()));
values.setRawAccelX(table.get("rawAccelX", values.getRawAccelX()));
values.setRawAccelY(table.get("rawAccelY", values.getRawAccelY()));
values.setRawAccelZ(table.get("rawAccelZ", values.getRawAccelZ()));
values.setRawMagX(table.get("rawMagX", values.getRawMagX()));
values.setRawMagY(table.get("rawMagY", values.getRawMagY()));
values.setRawMagZ(table.get("rawMagZ", values.getRawMagZ()));
values.setYaw(table.get("yaw", values.getYaw()));
values.setPitch(table.get("pitch", values.getPitch()));
values.setRoll(table.get("roll", values.getRoll()));
values.setCompassHeading(table.get("compassHeading", values.getCompassHeading()));
values.setFusedHeading(table.get("fusedHeading", values.getFusedHeading()));
values.setRobotCentricVelocityX(table.get("robotCentricVelocityX", values.getRobotCentricVelocityX()));
values.setRobotCentricVelocityY(table.get("robotCentricVelocityY", values.getRobotCentricVelocityY()));
values.setRobotCentricVelocityZ(table.get("robotCentricVelocityZ", values.getRobotCentricVelocityZ()));
}

public void fromHardware(GyroValues values) {
this.values = values;
}
}
Loading