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
1,203 changes: 1,203 additions & 0 deletions elastic_layouts/elastic-4048-2026-dev-v1.1.json

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion src/main/java/frc/robot/constants/Constants2026.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ public class Constants2026 extends GameConstants {
public static final int SHOOTER_MOTOR_ID = 54;
public static final int SHOOTER_FOLLOWER_MOTOR_ID = 53;
public static final int INTAKE_DEPLOYMENT_ID = 9;
public static final int TURRET_MOTOR_ID = 9;
public static final int TURRET_MOTOR_ID = 11;

public static final double DRIVE_BASE_WIDTH = 0.635;
public static final double DRIVE_BASE_LENGTH = 0.635;
Expand Down
8 changes: 8 additions & 0 deletions src/main/java/frc/robot/constants/GameConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,14 @@ public enum Mode {
public static final double INITIAL_INTAKE_RETRACTION_SPEED = -10;


//Diags
public static final double HOPPER_DIAGS_ENCODER = 1;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

should we add encoder diag for turret, angler, intakeDeployer?

public static final double INTAKE_ROLLER_DIAGS_ENCODER = 1;
public static final double FEEDER_DIAGS_ENCODER = 1;
public static final double CLIMBER_DIAGS_ENCODER = 1;
public static final double SHOOTER_DIAGS_ENCODER = 1;
public static final double GYRO_DIAGS_ANGLE = 30;

//Timeouts
public static final double SPIN_TIMEOUT = 5;
public static final double TILT_TIMEOUT = 5;
Expand Down
20 changes: 19 additions & 1 deletion src/main/java/frc/robot/subsystems/AnglerSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,11 @@

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Robot;
import frc.robot.constants.Constants;
import frc.robot.constants.Constants2026;
import frc.robot.constants.GameConstants;
import frc.robot.utils.diag.DiagSparkMaxSwitch;
import frc.robot.utils.logging.input.MotorLoggableInputs;
import frc.robot.utils.logging.io.pidmotor.MockSparkMaxPidMotorIo;
import frc.robot.utils.logging.io.pidmotor.RealSparkMaxPidMotorIo;
Expand All @@ -32,6 +36,7 @@ public class AnglerSubsystem extends SubsystemBase {
public AnglerSubsystem(SparkMaxPidMotorIo io) {
this.io = io;
this.pidManager = new TunablePIDManager(LOGGING_NAME, io, createPidConfig());

}

@Override
Expand Down Expand Up @@ -113,7 +118,20 @@ public static SparkMaxPidMotorIo createMockIo() {
}

public static SparkMaxPidMotorIo createRealIo() {
return new RealSparkMaxPidMotorIo(LOGGING_NAME, createMotor(), MotorLoggableInputs.allMetrics());

SparkMaxPidMotor motor = createMotor();

Robot.getDiagnostics()
.addDiagnosable(
new DiagSparkMaxSwitch(
"Angler", "ForwardLimit", motor.getNeoMotor(), DiagSparkMaxSwitch.Direction.FORWARD));

Robot.getDiagnostics()
.addDiagnosable(
new DiagSparkMaxSwitch(
"Angler", "ReverseLimit", motor.getNeoMotor(), DiagSparkMaxSwitch.Direction.REVERSE));

return new RealSparkMaxPidMotorIo(LOGGING_NAME, motor, MotorLoggableInputs.allMetrics());
}

public static SparkMaxPidMotorIo createSimIo(RobotVisualizer visualizer) {
Expand Down
12 changes: 11 additions & 1 deletion src/main/java/frc/robot/subsystems/ClimberSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,10 @@

import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Robot;
import frc.robot.constants.Constants;
import frc.robot.constants.GameConstants;
import frc.robot.utils.diag.DiagSparkMaxEncoder;
import frc.robot.utils.logging.input.DigitalInputLoggableInputs;
import frc.robot.utils.logging.input.MotorLoggableInputs;
import frc.robot.utils.logging.io.motor.DigitalInputIo;
Expand Down Expand Up @@ -50,7 +53,14 @@ public static SparkMaxIo createMockIo() {
}

public static SparkMaxIo createRealIo() {
return new RealSparkMaxIo(LOGGING_NAME, createMotor(), MotorLoggableInputs.allMetrics());
SparkMax motor = createMotor();

Robot.getDiagnostics()
.addDiagnosable(
new DiagSparkMaxEncoder(
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

add limit switches to climber. Top and Bottom.

"Climber", "Encoder", GameConstants.CLIMBER_DIAGS_ENCODER, motor));

return new RealSparkMaxIo(LOGGING_NAME, motor, MotorLoggableInputs.allMetrics());
}

public static SparkMaxIo createSimIo(RobotVisualizer visualizer) {
Expand Down
12 changes: 11 additions & 1 deletion src/main/java/frc/robot/subsystems/FeederSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,11 @@

import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Robot;
import frc.robot.commands.intake.SpinIntake;
import frc.robot.constants.Constants;
import frc.robot.constants.GameConstants;
import frc.robot.utils.diag.DiagSparkMaxEncoder;
import frc.robot.utils.logging.input.DigitalInputLoggableInputs;
import frc.robot.utils.logging.input.MotorLoggableInputs;
import frc.robot.utils.logging.io.motor.DigitalInputIo;
Expand Down Expand Up @@ -51,7 +54,14 @@ public static SparkMaxIo createMockIo() {
}

public static SparkMaxIo createRealIo() {
return new RealSparkMaxIo(LOGGING_NAME, createMotor(), MotorLoggableInputs.allMetrics());
SparkMax motor = createMotor();

Robot.getDiagnostics()
.addDiagnosable(
new DiagSparkMaxEncoder(
"Feeder", "Encoder", GameConstants.FEEDER_DIAGS_ENCODER, motor));

return new RealSparkMaxIo(LOGGING_NAME, motor, MotorLoggableInputs.allMetrics());
}

public static SparkMaxIo createSimIo(RobotVisualizer visualizer) {
Expand Down
8 changes: 8 additions & 0 deletions src/main/java/frc/robot/subsystems/GyroSubsystem.java
Original file line number Diff line number Diff line change
@@ -1,10 +1,14 @@
package frc.robot.subsystems;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Robot;
import frc.robot.constants.GameConstants;
import frc.robot.utils.diag.DiagGyro;
import frc.robot.utils.logging.input.GyroValues;
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.logging.io.gyro.ThreadedGyro;
import frc.robot.utils.simulation.RobotVisualizer;

public class GyroSubsystem extends SubsystemBase {
Expand Down Expand Up @@ -37,7 +41,11 @@ public static GyroIo createMockIo() {

public static GyroIo createRealIo() {
RealGyroIo realGyroIo = new RealGyroIo();
ThreadedGyro gyro = realGyroIo.getThreadedGyro();
realGyroIo.start();
Robot.getDiagnostics()
.addDiagnosable(new DiagGyro("Gyro", "Gyro Angle", GameConstants.GYRO_DIAGS_ANGLE, gyro));

return realGyroIo;
}

Expand Down
13 changes: 12 additions & 1 deletion src/main/java/frc/robot/subsystems/HopperSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,10 @@
import com.revrobotics.spark.config.SparkMaxConfig;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Robot;
import frc.robot.constants.Constants;
import frc.robot.constants.GameConstants;
import frc.robot.utils.diag.DiagSparkMaxEncoder;
import frc.robot.utils.logging.input.MotorLoggableInputs;
import frc.robot.utils.logging.io.motor.MockSparkMaxIo;
import frc.robot.utils.logging.io.motor.RealSparkMaxIo;
Expand Down Expand Up @@ -50,7 +53,15 @@ public static SparkMaxIo createMockIo() {
}

public static SparkMaxIo createRealIo() {
return new RealSparkMaxIo(LOGGING_NAME, createMotor(), MotorLoggableInputs.allMetrics());

SparkMax motor = createMotor();

Robot.getDiagnostics()
.addDiagnosable(
new DiagSparkMaxEncoder(
"Hopper", "Encoder", GameConstants.HOPPER_DIAGS_ENCODER, motor));

return new RealSparkMaxIo(LOGGING_NAME, motor, MotorLoggableInputs.allMetrics());
}

public static SparkMaxIo createSimIo(RobotVisualizer visualizer) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,12 @@
import com.revrobotics.spark.config.SparkMaxConfig;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Robot;
import frc.robot.commands.intakeDeployment.RunDeployer;
import frc.robot.constants.Constants;
import frc.robot.constants.enums.DeploymentState;
import frc.robot.utils.diag.DiagSparkMaxSwitch;
import frc.robot.utils.diag.DiagSparkMaxSwitch.Direction;
import frc.robot.utils.logging.input.MotorLoggableInputs;
import frc.robot.utils.logging.io.motor.MockSparkMaxIo;
import frc.robot.utils.logging.io.motor.RealSparkMaxIo;
Expand Down Expand Up @@ -51,7 +54,20 @@ public static SparkMaxIo createMockIo() {
}

public static SparkMaxIo createRealIo() {
return new RealSparkMaxIo(LOGGING_NAME, createMotor(), MotorLoggableInputs.allMetrics());

SparkMax motor = createMotor();

Robot.getDiagnostics()
.addDiagnosable(
new DiagSparkMaxSwitch(
"Intake Deployer", "ForwardLimit", motor, DiagSparkMaxSwitch.Direction.FORWARD));

Robot.getDiagnostics()
.addDiagnosable(
new DiagSparkMaxSwitch(
"Intake Deployer", "ReverseLimit", motor, DiagSparkMaxSwitch.Direction.REVERSE));

return new RealSparkMaxIo(LOGGING_NAME, motor, MotorLoggableInputs.allMetrics());
}

public static SparkMaxIo createSimIo(RobotVisualizer visualizer) {
Expand Down
13 changes: 12 additions & 1 deletion src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,11 @@

import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Robot;
import frc.robot.commands.intake.SpinIntake;
import frc.robot.constants.Constants;
import frc.robot.constants.GameConstants;
import frc.robot.utils.diag.DiagSparkMaxEncoder;
import frc.robot.utils.logging.input.DigitalInputLoggableInputs;
import frc.robot.utils.logging.input.MotorLoggableInputs;
import frc.robot.utils.logging.io.motor.DigitalInputIo;
Expand Down Expand Up @@ -58,7 +61,15 @@ public static SparkMaxIo createMockIo() {
return new MockSparkMaxIo(LOGGING_NAME, MotorLoggableInputs.allMetrics());
}
public static SparkMaxIo createRealIo() {
return new RealSparkMaxIo(LOGGING_NAME, createMotor(), MotorLoggableInputs.allMetrics());

SparkMax motor = createMotor();

Robot.getDiagnostics()
.addDiagnosable(
new DiagSparkMaxEncoder(
"Intake Roller", "Encoder", GameConstants.INTAKE_ROLLER_DIAGS_ENCODER, motor));

return new RealSparkMaxIo(LOGGING_NAME, motor, MotorLoggableInputs.allMetrics());
}
public static SparkMaxIo createSimIo(RobotVisualizer visualizer) {
SparkMax motor = createMotor();
Expand Down
14 changes: 12 additions & 2 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,11 @@
import com.revrobotics.spark.config.SparkMaxConfig;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Robot;
import frc.robot.constants.Constants;
import frc.robot.constants.Constants2026;
import frc.robot.constants.GameConstants;
import frc.robot.utils.diag.DiagSparkMaxEncoder;
import frc.robot.utils.logging.input.MotorLoggableInputs;
import frc.robot.utils.logging.io.motor.SparkMaxIo;
import frc.robot.utils.logging.io.pidmotor.MockSparkMaxPidMotorIo;
Expand All @@ -38,7 +42,6 @@ public ShooterSubsystem(SparkMaxPidMotorIo io) {
followerConfig = new SparkMaxConfig();
followerConfig.follow(Constants.SHOOTER_MOTOR_ID, true);
followerMotor.configure(followerConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);

}

// setSpeed expects a power value from -1 to 1
Expand All @@ -65,7 +68,14 @@ public static SparkMaxPidMotorIo createMockIo() {
}

public static SparkMaxPidMotorIo createRealIo() {
return new RealSparkMaxPidMotorIo(LOGGING_NAME, createMotor(), MotorLoggableInputs.allMetrics());
SparkMaxPidMotor motor = createMotor();

Robot.getDiagnostics()
.addDiagnosable(
new DiagSparkMaxEncoder(
"Shooter", "Encoder", GameConstants.SHOOTER_DIAGS_ENCODER, motor.getNeoMotor()));

return new RealSparkMaxPidMotorIo(LOGGING_NAME, motor, MotorLoggableInputs.allMetrics());
}

public static SparkMaxPidMotorIo createSimIo(RobotVisualizer visualizer) {
Expand Down
17 changes: 16 additions & 1 deletion src/main/java/frc/robot/subsystems/TurretSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,10 @@

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Robot;
import frc.robot.constants.Constants;
import frc.robot.constants.GameConstants;
import frc.robot.utils.diag.DiagSparkMaxSwitch;
import frc.robot.utils.logging.input.MotorLoggableInputs;
import frc.robot.utils.logging.io.pidmotor.MockSparkMaxPidMotorIo;
import frc.robot.utils.logging.io.pidmotor.RealSparkMaxPidMotorIo;
Expand Down Expand Up @@ -113,7 +115,20 @@ public static SparkMaxPidMotorIo createMockIo() {
}

public static SparkMaxPidMotorIo createRealIo() {
return new RealSparkMaxPidMotorIo(LOGGING_NAME, createMotor(), MotorLoggableInputs.allMetrics());

SparkMaxPidMotor motor = createMotor();

Robot.getDiagnostics()
.addDiagnosable(
new DiagSparkMaxSwitch(
"Turret", "ForwardLimit", motor.getNeoMotor(), DiagSparkMaxSwitch.Direction.FORWARD));

Robot.getDiagnostics()
.addDiagnosable(
new DiagSparkMaxSwitch(
"Turret", "ReverseLimit", motor.getNeoMotor(), DiagSparkMaxSwitch.Direction.REVERSE));

return new RealSparkMaxPidMotorIo(LOGGING_NAME, motor, MotorLoggableInputs.allMetrics());
}

public static SparkMaxPidMotorIo createSimIo(RobotVisualizer visualizer) {
Expand Down