Merge branch 'New-Intake' into DenverAutos

This commit is contained in:
mimigamin
2026-03-31 16:45:32 -06:00
17 changed files with 782 additions and 218 deletions
+1
View File
@@ -185,3 +185,4 @@ compile_commands.json
# Eclipse generated file for annotation processors # Eclipse generated file for annotation processors
.factorypath .factorypath
src/main/java/frc4388/utility/compute/JankCoder copy.java
+5
View File
@@ -15,6 +15,8 @@ import org.littletonrobotics.junction.networktables.NT4Publisher;
import org.littletonrobotics.junction.wpilog.WPILOGReader; import org.littletonrobotics.junction.wpilog.WPILOGReader;
import org.littletonrobotics.junction.wpilog.WPILOGWriter; import org.littletonrobotics.junction.wpilog.WPILOGWriter;
import com.ctre.phoenix6.SignalLogger;
import edu.wpi.first.wpilibj.GenericHID.RumbleType; import edu.wpi.first.wpilibj.GenericHID.RumbleType;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler; import edu.wpi.first.wpilibj2.command.CommandScheduler;
@@ -50,6 +52,9 @@ public class Robot extends LoggedRobot {
// Start logging with AdvantageKit // Start logging with AdvantageKit
startLogging(); startLogging();
com.revrobotics.util.StatusLogger.disableAutoLogging();
SignalLogger.enableAutoLogging(false);
// Instantiate our RobotContainer. This will perform all our button bindings, and put our // Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard. // autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer(); m_robotContainer = new RobotContainer();
+60 -28
View File
@@ -109,7 +109,7 @@ public class RobotContainer {
private Command IntakeExtended = new SequentialCommandGroup( private Command IntakeExtended = new SequentialCommandGroup(
new InstantCommand(() -> m_robotIntake.setMode(IntakeMode.Extended), m_robotIntake) new InstantCommand(() -> m_robotIntake.setMode(IntakeMode.ExtendedREMOVEME), m_robotIntake)
); );
// private Command LidarIntake = new SequentialCommandGroup( // private Command LidarIntake = new SequentialCommandGroup(
@@ -134,7 +134,7 @@ public class RobotContainer {
private Command RobotRev = new SequentialCommandGroup( private Command RobotRev = new SequentialCommandGroup(
new InstantCommand(() -> m_robotShooter.spinUpShooting(), m_robotShooter), new InstantCommand(() -> m_robotShooter.spinUpShooting(), m_robotShooter),
IntakeExtended, IntakeExtended,
new InstantCommand(() -> m_robotIntake.setMode(IntakeMode.RollerStop), m_robotIntake) new InstantCommand(() -> m_robotIntake.setMode(IntakeMode.Idle), m_robotIntake)
); );
private Command RobotShootDriving = new SequentialCommandGroup( private Command RobotShootDriving = new SequentialCommandGroup(
@@ -146,7 +146,7 @@ public class RobotContainer {
); );
private Command IntakeRetracted = new SequentialCommandGroup( private Command IntakeRetracted = new SequentialCommandGroup(
new InstantCommand(() -> m_robotIntake.setMode(IntakeMode.Retracted), m_robotIntake) new InstantCommand(() -> m_robotIntake.setMode(IntakeMode.RetractedREMOVEME), m_robotIntake)
); );
private Command RobotShoot = new SequentialCommandGroup( private Command RobotShoot = new SequentialCommandGroup(
@@ -164,7 +164,7 @@ public class RobotContainer {
public RobotContainer() { public RobotContainer() {
configureSINGLEBindings(); configureButtonBindings();
// Called on first robot enable // Called on first robot enable
DeferredBlock.addBlock(() -> { DeferredBlock.addBlock(() -> {
@@ -357,22 +357,22 @@ public class RobotContainer {
m_robotShooter.spinUpIdle(); m_robotShooter.spinUpIdle();
})); }));
new JoystickButton(getDeadbandedOperatorController(), XboxController.RIGHT_BUMPER_BUTTON) // new JoystickButton(getDeadbandedOperatorController(), XboxController.RIGHT_BUMPER_BUTTON)
.onTrue(new InstantCommand(() -> { // .onTrue(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Retracted); // m_robotIntake.setMode(IntakeMode.RetractedREMOVEME);
})); // }));
new JoystickButton(getDeadbandedOperatorController(), XboxController.A_BUTTON) // new JoystickButton(getDeadbandedOperatorController(), XboxController.A_BUTTON)
.onTrue(new InstantCommand(() -> { // .onTrue(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Extended); // m_robotIntake.setMode(IntakeMode.ExtendedREMOVEME);
})); // }));
new JoystickButton(getDeadbandedOperatorController(), XboxController.X_BUTTON) new JoystickButton(getDeadbandedOperatorController(), XboxController.X_BUTTON)
.onTrue(new InstantCommand(() -> { .onTrue(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Extending); m_robotIntake.setMode(IntakeMode.ExtendingRolling);
})) }))
.onFalse(new InstantCommand(() -> { .onFalse(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Idle); m_robotIntake.setMode(IntakeMode.ExtendingIdle);
})); }));
new JoystickButton(getDeadbandedOperatorController(), XboxController.Y_BUTTON) new JoystickButton(getDeadbandedOperatorController(), XboxController.Y_BUTTON)
@@ -383,6 +383,38 @@ public class RobotContainer {
m_robotIntake.setMode(IntakeMode.Idle); m_robotIntake.setMode(IntakeMode.Idle);
})); }));
new Trigger(() -> getDeadbandedOperatorController().getPOV() == 90)
.onTrue(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.ExtendingIdle);
}))
.onFalse(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Idle);
}));
new Trigger(() -> getDeadbandedOperatorController().getPOV() == 270)
.onTrue(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Retracting);
}))
.onFalse(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Idle);
}));
new Trigger(() -> getDeadbandedOperatorController().getPOV() == 0)
.onTrue(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Bouncing);
}))
.onFalse(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Idle);
}));
// .onFalse(new InstantCommand(() -> {
// m_robotIntake.setMode(IntakeMode.Idle);
// }));
new JoystickButton(getDeadbandedOperatorController(), XboxController.START_BUTTON) new JoystickButton(getDeadbandedOperatorController(), XboxController.START_BUTTON)
.whileTrue( .whileTrue(
new PathPlannerAuto("Right_AutoClimb") new PathPlannerAuto("Right_AutoClimb")
@@ -505,21 +537,21 @@ public class RobotContainer {
m_robotShooter.spinUpIdle(); m_robotShooter.spinUpIdle();
})); }));
new JoystickButton(getDeadbandedDriverController(), XboxController.X_BUTTON) // new JoystickButton(getDeadbandedDriverController(), XboxController.X_BUTTON)
.onTrue(new InstantCommand(() -> { // .onTrue(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Extending); // m_robotIntake.setMode(IntakeMode.ExtendedIdle);
})) // }))
.onFalse(new InstantCommand(() -> { // .onFalse(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Idle); // m_robotIntake.setMode(IntakeMode.Idle);
})); // }));
new JoystickButton(getDeadbandedDriverController(), XboxController.Y_BUTTON) // new JoystickButton(getDeadbandedDriverController(), XboxController.Y_BUTTON)
.onTrue(new InstantCommand(() -> { // .onTrue(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Retracting); // m_robotIntake.setMode(IntakeMode.Retracting);
})) // }))
.onFalse(new InstantCommand(() -> { // .onFalse(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Idle); // m_robotIntake.setMode(IntakeMode.Idle);
})); // }));
} }
+10 -8
View File
@@ -13,6 +13,7 @@ import org.photonvision.PhotonCamera;
import com.ctre.phoenix6.hardware.CANcoder; import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.swerve.SwerveDrivetrain; import com.ctre.phoenix6.swerve.SwerveDrivetrain;
import com.revrobotics.spark.SparkMax;
import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.DigitalInput;
import frc4388.robot.constants.Constants; import frc4388.robot.constants.Constants;
@@ -33,9 +34,11 @@ import frc4388.robot.subsystems.swerve.SwerveIO;
import frc4388.robot.subsystems.swerve.SwerveReal; import frc4388.robot.subsystems.swerve.SwerveReal;
import frc4388.robot.subsystems.vision.VisionIO; import frc4388.robot.subsystems.vision.VisionIO;
import frc4388.robot.subsystems.vision.VisionReal; import frc4388.robot.subsystems.vision.VisionReal;
import frc4388.utility.compute.JankCoder;
import frc4388.utility.status.FaultCANCoder; import frc4388.utility.status.FaultCANCoder;
import frc4388.utility.status.FaultPhotonCamera; import frc4388.utility.status.FaultPhotonCamera;
import frc4388.utility.status.FaultPidgeon2; import frc4388.utility.status.FaultPidgeon2;
import frc4388.utility.status.FaultSparkMax;
import frc4388.utility.status.FaultTalonFX; import frc4388.utility.status.FaultTalonFX;
/** /**
@@ -97,18 +100,17 @@ public class RobotMap {
TalonFX indexer = new TalonFX(ShooterConstants.INDEXER_ID.id, Constants.CANIVORE_CANBUS); TalonFX indexer = new TalonFX(ShooterConstants.INDEXER_ID.id, Constants.CANIVORE_CANBUS);
//Configure Intake 20,21 //Configure Intake 20,21
TalonFX arm = new TalonFX(IntakeConstants.ARM_ID.id, Constants.CANIVORE_CANBUS); SparkMax arm = new SparkMax(IntakeConstants.ARM_ID.id, com.revrobotics.spark.SparkLowLevel.MotorType.kBrushless);
TalonFX roller = new TalonFX(IntakeConstants.ROLLER_ID.id, Constants.CANIVORE_CANBUS); SparkMax roller = new SparkMax(IntakeConstants.ROLLER_ID.id, com.revrobotics.spark.SparkLowLevel.MotorType.kBrushless);
DigitalInput armLimitSwitch = new DigitalInput(IntakeConstants.ARM_LIMIT_SWITCH_CHANNEL); // DigitalInput armLimitSwitch = new DigitalInput(IntakeConstants.ARM_LIMIT_SWITCH_CHANNEL);
// DigitalInput basinLimitSwitch = new DigitalInput(ElevatorConstants.BASIN_LIMIT_SWITCH); // DigitalInput basinLimitSwitch = new DigitalInput(ElevatorConstants.BASIN_LIMIT_SWITCH);
// DigitalInput endeffectorLimitSwitch = new DigitalInput(ElevatorConstants.ENDEFFECTOR_LIMIT_SWITCH); // DigitalInput endeffectorLimitSwitch = new DigitalInput(ElevatorConstants.ENDEFFECTOR_LIMIT_SWITCH);
// DigitalInput IRIntakeBeam = new DigitalInput(ElevatorConstants.INTAKE_LIMIT_SWITCH); // DigitalInput IRIntakeBeam = new DigitalInput(ElevatorConstants.INTAKE_LIMIT_SWITCH);
// shooterIO = new ShooterIO() {};
shooterIO = new ShooterReal(shooter1, shooter2, indexer); shooterIO = new ShooterReal(shooter1, shooter2, indexer);
JankCoder armEncoder = new JankCoder(0, IntakeConstants.ARM_ENCODER_OFFSET);
intakeIO = new IntakeReal(armLimitSwitch, arm, roller); intakeIO = new IntakeReal(arm, roller, armEncoder);
// Fault // Fault
FaultPidgeon2.addDevice(swerveDrivetrainReal.getPigeon2(), "Gyro"); FaultPidgeon2.addDevice(swerveDrivetrainReal.getPigeon2(), "Gyro");
@@ -117,8 +119,8 @@ public class RobotMap {
FaultTalonFX.addDevice(shooter1, "Shooter1"); FaultTalonFX.addDevice(shooter1, "Shooter1");
FaultTalonFX.addDevice(shooter2, "Shooter2"); FaultTalonFX.addDevice(shooter2, "Shooter2");
FaultTalonFX.addDevice(indexer, "Indexer"); FaultTalonFX.addDevice(indexer, "Indexer");
FaultTalonFX.addDevice(arm, "Arm"); FaultSparkMax.addDevice(arm, "Arm");
FaultTalonFX.addDevice(roller, "Roller"); FaultSparkMax.addDevice(roller, "Roller");
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getDriveMotor(), "Module 0 Drive"); FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getDriveMotor(), "Module 0 Drive");
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getSteerMotor(), "Module 0 Steer"); FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getSteerMotor(), "Module 0 Steer");
@@ -7,12 +7,12 @@ public final class BuildConstants {
public static final String MAVEN_GROUP = ""; public static final String MAVEN_GROUP = "";
public static final String MAVEN_NAME = "2026KPopRobotHunters"; public static final String MAVEN_NAME = "2026KPopRobotHunters";
public static final String VERSION = "unspecified"; public static final String VERSION = "unspecified";
public static final int GIT_REVISION = 186; public static final int GIT_REVISION = 191;
public static final String GIT_SHA = "a774f156c681df6426dc5d344b84692080bb8a06"; public static final String GIT_SHA = "9021f480beaf35912eb54a845ec87522fef5337a";
public static final String GIT_DATE = "2026-03-26 18:40:37 MDT"; public static final String GIT_DATE = "2026-03-30 18:57:14 MDT";
public static final String GIT_BRANCH = "DenverAutos"; public static final String GIT_BRANCH = "New-Intake";
public static final String BUILD_DATE = "2026-03-30 19:07:09 MDT"; public static final String BUILD_DATE = "2026-03-30 19:50:05 MDT";
public static final long BUILD_UNIX_TIME = 1774919229417L; public static final long BUILD_UNIX_TIME = 1774921805228L;
public static final int DIRTY = 1; public static final int DIRTY = 1;
private BuildConstants(){} private BuildConstants(){}
@@ -1,10 +1,15 @@
package frc4388.robot.subsystems.intake; package frc4388.robot.subsystems.intake;
import static edu.wpi.first.units.Units.Amps;
import static edu.wpi.first.units.Units.Rotations; import static edu.wpi.first.units.Units.Rotations;
import static edu.wpi.first.units.Units.RotationsPerSecond;
import java.util.function.Supplier; import java.util.function.Supplier;
import org.littletonrobotics.junction.Logger; import org.littletonrobotics.junction.Logger;
import com.ctre.phoenix6.Utils;
import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.SubsystemBase;
@@ -23,18 +28,31 @@ public class Intake extends SubsystemBase {
} }
public enum IntakeMode { public enum IntakeMode {
Extended, ExtendedREMOVEME,
Retracted, RetractedREMOVEME,
Extending,
ExtendingIdle,
ExtendingRolling,
Retracting, Retracting,
Idle, Idle,
RollerStop Bouncing
} }
private IntakeMode mode = IntakeMode.Idle; private IntakeMode mode = IntakeMode.Idle;
public void setMode(IntakeMode mode) { public void setMode(IntakeMode mode) {
this.mode = mode; this.mode = mode;
switch (mode) {
case Bouncing:
// When bounce is enabled: set the bounce timer
this.state.currentBounceTime = Utils.getSystemTimeSeconds() + IntakeConstants.INTAKE_BOUNCE_HALF_PERIOD.get();
break;
default:
break;
}
} }
public IntakeMode getMode() { public IntakeMode getMode() {
@@ -78,27 +96,66 @@ public class Intake extends SubsystemBase {
io.updateInputs(state); io.updateInputs(state);
// getCurrentTime
switch (mode) { switch (mode) {
case Extended: case ExtendedREMOVEME:
io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_LIMIT_EXTENDED.get())); // io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_LIMIT_EXTENDED.get()));
io.setRollerOutput(state, IntakeConstants.ROLLER_PERCENT_OUTPUT.get()); // io.setRollerOutput(state, IntakeConstants.ROLLER_PERCENT_OUTPUT.get());
break; break;
case Retracted: case RetractedREMOVEME:
io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_LIMIT_RETRACTED.get())); // io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_LIMIT_RETRACTED.get()));
// io.setRollerOutput(state, 0);
break;
case ExtendingIdle:
io.armOutput(IntakeConstants.ARM_EXTEND_PERCENT_OUTPUT.get());
io.setRollerOutput(state, 0); io.setRollerOutput(state, 0);
break; break;
case Extending:
case ExtendingRolling:
io.armOutput(IntakeConstants.ARM_EXTEND_PERCENT_OUTPUT.get()); io.armOutput(IntakeConstants.ARM_EXTEND_PERCENT_OUTPUT.get());
io.setRollerOutput(state, IntakeConstants.ROLLER_PERCENT_OUTPUT.get()); io.setRollerOutput(state, IntakeConstants.ROLLER_PERCENT_OUTPUT.get());
break; break;
case Retracting: case Retracting:
io.armOutput(IntakeConstants.ARM_RETRACT_PERCENT_OUTPUT.get()); io.armOutput(IntakeConstants.ARM_RETRACT_PERCENT_OUTPUT.get());
io.setRollerOutput(state, 0);
if(state.intakeEncoder.in(Rotations) > IntakeConstants.ARM_REVERSE_ROLLER_RANGE.get()) {
io.setRollerOutput(state, IntakeConstants.ROLLER_RETRACT_PERCENT_OUTPUT.get());
} else {
io.setRollerOutput(state, 0);
}
break;
case Bouncing:
// io.setRollerOutput(state, 0);
if(
state.armMotorCurrent.in(Amps) > IntakeConstants.INTAKE_BOUNCE_CURRENT_LIMIT.get()
// Math.abs(state.armMotorVelocity.in(RotationsPerSecond)) < IntakeConstants.INTAKE_BOUNCE_VELOCITY_LIMIT.get()
) {
System.out.println("RESET BOUNCE");
this.state.currentBounceTime = Utils.getSystemTimeSeconds() + IntakeConstants.INTAKE_BOUNCE_HALF_PERIOD.get();
}
// Get the time delta from the last bounce time update
double currentTime = Utils.getSystemTimeSeconds() - state.currentBounceTime;
// Get the percentage through the bounce period (0 output means one half period has passed)
double percentOutput = (currentTime / IntakeConstants.INTAKE_BOUNCE_HALF_PERIOD.get()) * IntakeConstants.INTAKE_BOUNCE_OUTPUT.get();
// Clamp the output of the motor to some value
percentOutput = -Math.max(Math.min(percentOutput, IntakeConstants.INTAKE_BOUNCE_MAX_OUTPUT.get()), -IntakeConstants.INTAKE_BOUNCE_MAX_OUTPUT.get());
io.armOutput(percentOutput);
if(percentOutput < 0) {
io.setRollerOutput(state, IntakeConstants.ROLLER_RETRACT_PERCENT_OUTPUT.get());
} else {
io.setRollerOutput(state, 0);
}
break; break;
case Idle: case Idle:
io.stopArm(); io.armOutput(0);
break;
case RollerStop:
io.setRollerOutput(state, 0); io.setRollerOutput(state, 0);
break; break;
} }
@@ -1,10 +1,10 @@
package frc4388.robot.subsystems.intake; package frc4388.robot.subsystems.intake;
import com.ctre.phoenix6.configs.CurrentLimitsConfigs; import com.revrobotics.spark.FeedbackSensor;
import com.ctre.phoenix6.configs.MotorOutputConfigs; import com.revrobotics.spark.config.SparkMaxConfig;
import com.ctre.phoenix6.configs.Slot0Configs; import com.revrobotics.spark.config.LimitSwitchConfig.Behavior;
import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.revrobotics.spark.config.LimitSwitchConfig.Type;
import com.ctre.phoenix6.signals.NeutralModeValue; import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
import frc4388.utility.configurable.ConfigurableDouble; import frc4388.utility.configurable.ConfigurableDouble;
import frc4388.utility.status.CanDevice; import frc4388.utility.status.CanDevice;
@@ -14,6 +14,15 @@ public class IntakeConstants {
public static final double ARM_MOTOR_GEAR_RATIO = 125; public static final double ARM_MOTOR_GEAR_RATIO = 125;
public static final double ROLLER_MOTOR_GEAR_RATIO = 3; public static final double ROLLER_MOTOR_GEAR_RATIO = 3;
public static final ConfigurableDouble ARM_ENCODER_OFFSET = new ConfigurableDouble("Arm Encoder Offset", 0);
public static final ConfigurableDouble INTAKE_BOUNCE_HALF_PERIOD = new ConfigurableDouble("Bounce Half Period", 5.);
public static final ConfigurableDouble INTAKE_BOUNCE_OUTPUT = new ConfigurableDouble("Bounce Output", 0.1);
public static final ConfigurableDouble INTAKE_BOUNCE_MAX_OUTPUT = new ConfigurableDouble("Bounce Max Output", 0.2);
public static final ConfigurableDouble INTAKE_BOUNCE_CURRENT_LIMIT = new ConfigurableDouble("Intake Bounce Current Limit", 16);
public static final ConfigurableDouble INTAKE_BOUNCE_VELOCITY_LIMIT = new ConfigurableDouble("Intake Bounce Velocity Limit", 4);
@@ -21,7 +30,7 @@ public class IntakeConstants {
public static final CanDevice ARM_ID = new CanDevice("ARM", 20); public static final CanDevice ARM_ID = new CanDevice("ARM", 20);
public static final CanDevice ROLLER_ID = new CanDevice("INTAKE_ROLLER", 21); public static final CanDevice ROLLER_ID = new CanDevice("INTAKE_ROLLER", 21);
public static final int ARM_LIMIT_SWITCH_CHANNEL = 9; public static final int ARM_ENCODER_ID = 0;
// Limits // Limits
@@ -33,27 +42,32 @@ public class IntakeConstants {
// public static final Angle ARM_LIMIT_LOWER = Degrees.of(90); // public static final Angle ARM_LIMIT_LOWER = Degrees.of(90);
// public static final Angle ARM_LIMIT_UPPER = Degrees.of(-90); // public static final Angle ARM_LIMIT_UPPER = Degrees.of(-90);
public static final ConfigurableDouble ARM_LIMIT_RETRACTED = new ConfigurableDouble("Arm angle retracted", 0.1); public static final ConfigurableDouble ARM_LIMIT_RETRACTED = new ConfigurableDouble("Arm angle retracted", 0.);
public static final ConfigurableDouble ARM_LIMIT_EXTENDED = new ConfigurableDouble("Arm angle extended", 0.33); public static final ConfigurableDouble ARM_LIMIT_EXTENDED = new ConfigurableDouble("Arm angle extended", 1.5);
public static final ConfigurableDouble ARM_EXTEND_PERCENT_OUTPUT = new ConfigurableDouble("Arm extend % output", 0.4); public static final ConfigurableDouble ARM_EXTEND_PERCENT_OUTPUT = new ConfigurableDouble("Arm extend % output", 0.2);
public static final ConfigurableDouble ARM_RETRACT_PERCENT_OUTPUT = new ConfigurableDouble("Arm retract % output", -0.4); public static final ConfigurableDouble ARM_RETRACT_PERCENT_OUTPUT = new ConfigurableDouble("Arm retract % output", -0.2);
public static final ConfigurableDouble ROLLER_PERCENT_OUTPUT = new ConfigurableDouble("Roller Percent Output", .70);
public static final ConfigurableDouble ARM_REVERSE_ROLLER_RANGE = new ConfigurableDouble("Arm reverse roller range", 1.17);
public static final ConfigurableDouble ROLLER_PERCENT_OUTPUT = new ConfigurableDouble("Roller Percent Output", .80);
public static final ConfigurableDouble ROLLER_RETRACT_PERCENT_OUTPUT = new ConfigurableDouble("Roller Retract Output", .40);
// public static final ConfigurableDouble ROLL = new ConfigurableDouble("Arm angle extended", 0.25); // public static final ConfigurableDouble ROLL = new ConfigurableDouble("Arm angle extended", 0.25);
// public static final AngularVelocity ROLLER_MAX_VELOCITY = RotationsPerSecond.of(4.0); // public static final AngularVelocity ROLLER_MAX_VELOCITY = RotationsPerSecond.of(4.0);
// public static final AngularVelocity ROLLER_STOP = RotationsPerSecond.of(0.0); // public static final AngularVelocity ROLLER_STOP = RotationsPerSecond.of(0.0);
public static final Slot0Configs ARM_PID = new Slot0Configs() // public static final Slot0Configs ARM_PID = new Slot0Configs()
.withKP(0.08) // .withKP(0.08)
.withKI(0.0) // .withKI(0.0)
.withKD(0.05); // .withKD(0.05);
public static ConfigurableDouble arm_kP = new ConfigurableDouble("ARM KP", 0.08); // public static ConfigurableDouble arm_kP = new ConfigurableDouble("ARM KP", 0.08);
public static ConfigurableDouble arm_kI = new ConfigurableDouble("ARM KI", 0); // public static ConfigurableDouble arm_kI = new ConfigurableDouble("ARM KI", 0);
public static ConfigurableDouble arm_kD = new ConfigurableDouble("ARM KD", 0.05); // public static ConfigurableDouble arm_kD = new ConfigurableDouble("ARM KD", 0.05);
@@ -63,25 +77,46 @@ public class IntakeConstants {
// public static final Angle PITCH_LIMIT_LOWER = Degrees.of(0); // public static final Angle PITCH_LIMIT_LOWER = Degrees.of(0);
// Motor configs // Motor configs
public static final TalonFXConfiguration ARM_MOTOR_CONFIG = new TalonFXConfiguration()
.withCurrentLimits(
new CurrentLimitsConfigs()
.withStatorCurrentLimit(15) // TODO: tune???
.withStatorCurrentLimitEnable(true)
).withMotorOutput(
new MotorOutputConfigs()
.withNeutralMode(NeutralModeValue.Brake) // Must be break because this has to be accurate
.withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means
);
public static final TalonFXConfiguration ROLLER_MOTOR_CONFIG = new TalonFXConfiguration() public static final SparkMaxConfig ARM_MOTOR_CONFIG = new SparkMaxConfig();
.withCurrentLimits( public static final SparkMaxConfig ROLELR_MOTOR_CONFIG = new SparkMaxConfig();
new CurrentLimitsConfigs()
.withStatorCurrentLimit(40) // TODO: tune??? static {
.withStatorCurrentLimitEnable(true) ARM_MOTOR_CONFIG.limitSwitch
).withMotorOutput( .limitSwitchPositionSensor(FeedbackSensor.kPrimaryEncoder)
new MotorOutputConfigs()
.withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny .forwardLimitSwitchType(Type.kNormallyOpen)
.withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means .forwardLimitSwitchTriggerBehavior(Behavior.kKeepMovingMotor)
);
.reverseLimitSwitchType(Type.kNormallyClosed)
.reverseLimitSwitchPosition(0)
.reverseLimitSwitchTriggerBehavior(Behavior.kStopMovingMotorAndSetPosition);
ARM_MOTOR_CONFIG.idleMode(IdleMode.kBrake);
ROLELR_MOTOR_CONFIG.idleMode(IdleMode.kCoast);
}
// public static final TalonFXConfiguration ARM_MOTOR_CONFIG = new TalonFXConfiguration()
// .withCurrentLimits(
// new CurrentLimitsConfigs()
// .withStatorCurrentLimit(15) // TODO: tune???
// .withStatorCurrentLimitEnable(true)
// ).withMotorOutput(
// new MotorOutputConfigs()
// .withNeutralMode(NeutralModeValue.Brake) // Must be break because this has to be accurate
// .withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means
// );
// public static final TalonFXConfiguration ROLLER_MOTOR_CONFIG = new TalonFXConfiguration()
// .withCurrentLimits(
// new CurrentLimitsConfigs()
// .withStatorCurrentLimit(40) // TODO: tune???
// .withStatorCurrentLimitEnable(true)
// ).withMotorOutput(
// new MotorOutputConfigs()
// .withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny
// .withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means
// );
} }
@@ -15,13 +15,22 @@ import edu.wpi.first.units.measure.Current;
public interface IntakeIO { public interface IntakeIO {
@AutoLog @AutoLog
public class IntakeState { public class IntakeState {
boolean retractedLimit = false; double currentBounceTime = 0;
boolean retractedLimitSwitch = false;
boolean extendedSoftLimit = false;
boolean retractedSoftLimit = false;
boolean encoderConnected = false;
Angle intakeEncoder = Rotations.of(0);
Angle armAngle = Rotations.of(0); Angle armAngle = Rotations.of(0);
Angle armTargetAngle = Rotations.of(0); Angle armTargetAngle = Rotations.of(0);
Current armMotorCurrent = Amps.of(0); Current armMotorCurrent = Amps.of(0);
AngularVelocity armMotorVelocity = RotationsPerSecond.of(0); AngularVelocity armMotorVelocity = RotationsPerSecond.of(0);
AngularAcceleration armMotorAcceleration = RotationsPerSecondPerSecond.of(0); // AngularAcceleration armMotorAcceleration = RotationsPerSecondPerSecond.of(0);
// Angle shooterPitch = Rotations.of(0); // Angle shooterPitch = Rotations.of(0);
// Angle shooterTargetPitch = Rotations.of(0); // Angle shooterTargetPitch = Rotations.of(0);
@@ -1,11 +1,18 @@
package frc4388.robot.subsystems.intake; package frc4388.robot.subsystems.intake;
import static edu.wpi.first.units.Units.Amps;
import static edu.wpi.first.units.Units.Rotation;
import static edu.wpi.first.units.Units.Rotations; import static edu.wpi.first.units.Units.Rotations;
import static edu.wpi.first.units.Units.RotationsPerSecond;
import static edu.wpi.first.units.Units.RotationsPerSecondPerSecond;
import com.ctre.phoenix6.controls.DutyCycleOut; import com.ctre.phoenix6.controls.DutyCycleOut;
import com.ctre.phoenix6.controls.PositionDutyCycle; import com.ctre.phoenix6.controls.PositionDutyCycle;
import com.ctre.phoenix6.controls.PositionVoltage; import com.ctre.phoenix6.controls.PositionVoltage;
import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.hardware.TalonFX;
import com.revrobotics.PersistMode;
import com.revrobotics.ResetMode;
import com.revrobotics.spark.SparkMax;
import edu.wpi.first.math.trajectory.TrapezoidProfile; import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.math.util.Units; import edu.wpi.first.math.util.Units;
@@ -13,44 +20,28 @@ import edu.wpi.first.units.measure.Acceleration;
import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.units.measure.Velocity; import edu.wpi.first.units.measure.Velocity;
import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.DutyCycleEncoder;
import frc4388.utility.compute.JankCoder;
public class IntakeReal implements IntakeIO { public class IntakeReal implements IntakeIO {
TalonFX m_armMotor; SparkMax m_armMotor;
TalonFX m_rollerMotor; SparkMax m_rollerMotor;
DigitalInput m_armLimitSwitch; JankCoder m_encoder;
PositionDutyCycle armPosition = new PositionDutyCycle(0);
DutyCycleOut armPercentOutput = new DutyCycleOut(0);
public IntakeReal( public IntakeReal(
DigitalInput armLimitSwitch, SparkMax armMotor,
TalonFX armMotor, SparkMax rollerMotor,
TalonFX rollerMotor JankCoder jankCoder
) { ) {
// m_angleMotor = angleMotor; // m_angleMotor = angleMotor;
// m_pitchMotor = pitchMotor; // m_pitchMotor = pitchMotor;
m_armMotor = armMotor; m_armMotor = armMotor;
m_rollerMotor = rollerMotor; m_rollerMotor = rollerMotor;
m_armLimitSwitch = armLimitSwitch; m_encoder = jankCoder;
// Apply the configs m_armMotor.configure(IntakeConstants.ARM_MOTOR_CONFIG, ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters);
m_armMotor.getConfigurator().apply(IntakeConstants.ARM_PID); m_rollerMotor.configure(IntakeConstants.ROLELR_MOTOR_CONFIG, ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters);
m_armMotor.getConfigurator().apply(IntakeConstants.ARM_MOTOR_CONFIG);
m_rollerMotor.getConfigurator().apply(IntakeConstants.ROLLER_MOTOR_CONFIG);
armPosition.Slot = 0;
// rollerVelocity.Slot = 0;
}
private Angle clampAng(Angle x, Angle min, Angle max){
if(x.gt(max)) {
return max;
}else if(x.lt(min)) {
return min;
}else{
return x;
}
} }
@@ -59,11 +50,6 @@ public class IntakeReal implements IntakeIO {
public void setRollerOutput(IntakeState state, double rollerOutput) { public void setRollerOutput(IntakeState state, double rollerOutput) {
state.rollerTargetOutput = rollerOutput; state.rollerTargetOutput = rollerOutput;
if(rollerOutput == 0) {
m_rollerMotor.set(0);
return;
}
m_rollerMotor.set(rollerOutput); m_rollerMotor.set(rollerOutput);
} }
@@ -80,78 +66,76 @@ public class IntakeReal implements IntakeIO {
Angle motorAngle = angle.times(IntakeConstants.ARM_MOTOR_GEAR_RATIO); Angle motorAngle = angle.times(IntakeConstants.ARM_MOTOR_GEAR_RATIO);
// PositionDutyCycle posRequest = new PositionDutyCycle(motorTargetAngle); // PositionDutyCycle posRequest = new PositionDutyCycle(motorTargetAngle);
m_armMotor.setControl( // m_armMotor.setControl(
armPosition // armPosition
.withPosition(motorAngle) // .withPosition(motorAngle)
.withLimitReverseMotion(!m_armLimitSwitch.get()) // .withLimitReverseMotion(!m_armLimitSwitch.get())
); // );
} }
@Override
public void testSetArmAngle(IntakeState state, Angle angle){
state.armTargetAngle = angle;
Angle motorAngle = angle.times(IntakeConstants.ARM_MOTOR_GEAR_RATIO);
final TrapezoidProfile m_profile = new TrapezoidProfile(
new TrapezoidProfile.Constraints(80, 160)
);
// Final target of motorAngle rot, 0 rps
// Convert the Angle to a numeric degree value before creating the profile state
TrapezoidProfile.State m_goal = new TrapezoidProfile.State(motorAngle.in(Rotations), 0);
TrapezoidProfile.State m_setpoint = new TrapezoidProfile.State();
// create a position closed-loop request, voltage output, slot 0 configs
final PositionVoltage m_request = new PositionVoltage(0).withSlot(0);
// calculate the next profile setpoint
m_setpoint = m_profile.calculate(0.020, m_setpoint, m_goal);
// send the request to the device
m_request.Position = m_setpoint.position;
m_request.Velocity = m_setpoint.velocity;
m_armMotor.setControl(m_request);
}
@Override @Override
public void stopArm(){ public void stopArm(){
m_armMotor.set(0); m_armMotor.set(0);
// m_rollerMotor.set(0); // m_rollerMotor.set(0);
} }
private boolean retractedLimit() {
return m_encoder.get() <= IntakeConstants.ARM_LIMIT_RETRACTED.get();
}
private boolean extendedLimit() {
return m_encoder.get() >= IntakeConstants.ARM_LIMIT_EXTENDED.get();
}
@Override @Override
public void armOutput(double percentOutput){ public void armOutput(double percentOutput){
m_armMotor.setControl(
armPercentOutput.withOutput(percentOutput) // if(retractedLimit()) {
.withLimitReverseMotion(!m_armLimitSwitch.get()) // percentOutput = Math.max(percentOutput, 0);
); // }
if (extendedLimit()) {
percentOutput = Math.min(percentOutput, 0);
}
m_armMotor.set(percentOutput);
} }
@Override @Override
public void updateInputs(IntakeState state) { public void updateInputs(IntakeState state) {
state.armAngle = m_armMotor.getPosition().getValue().div(IntakeConstants.ARM_MOTOR_GEAR_RATIO); m_encoder.update();
state.armMotorCurrent = m_armMotor.getStatorCurrent().getValue();
state.armAngle = Rotations.of(m_armMotor.getEncoder().getPosition()).div(IntakeConstants.ARM_MOTOR_GEAR_RATIO);
state.armMotorVelocity = RotationsPerSecond.of(m_armMotor.getEncoder().getVelocity()).div(IntakeConstants.ARM_MOTOR_GEAR_RATIO);
// state.armMotorAcceleration = RotationsPerSecondPerSecond.of(m_armMotor.getEncoder().ge);
state.armMotorCurrent = Amps.of(m_armMotor.getOutputCurrent());
state.rollerOutput = m_rollerMotor.get(); state.rollerOutput = m_rollerMotor.get();
state.rollerMotorCurrent = m_rollerMotor.getStatorCurrent().getValue(); state.rollerMotorCurrent = Amps.of(m_rollerMotor.getOutputCurrent());
state.retractedLimit = !m_armLimitSwitch.get();
state.armMotorVelocity = m_armMotor.getVelocity().getValue(); state.retractedSoftLimit = retractedLimit();
state.armMotorAcceleration = m_armMotor.getAcceleration().getValue(); state.extendedSoftLimit = extendedLimit();
if(state.retractedLimit) { state.intakeEncoder = m_encoder.getRotations();
// Set the arm motor to be zero if the limit switch is pressed state.encoderConnected = m_encoder.isConnected();
m_armMotor.setPosition(0., 0);
state.retractedLimitSwitch = m_armMotor.getReverseLimitSwitch().isPressed();
if(state.retractedLimitSwitch) {
m_encoder.resetRotations();
} }
} }
@Override @Override
public void updateGains() { public void updateGains() {
m_encoder.loadRotations();
IntakeConstants.ARM_PID.kP = IntakeConstants.arm_kP.get(); // IntakeConstants.ARM_PID.kP = IntakeConstants.arm_kP.get();
IntakeConstants.ARM_PID.kI = IntakeConstants.arm_kI.get(); // IntakeConstants.ARM_PID.kI = IntakeConstants.arm_kI.get();
IntakeConstants.ARM_PID.kD = IntakeConstants.arm_kD.get(); // IntakeConstants.ARM_PID.kD = IntakeConstants.arm_kD.get();
m_armMotor.getConfigurator().apply(IntakeConstants.ARM_PID); // m_armMotor.getConfigurator().apply(IntakeConstants.ARM_PID);
} }
} }
@@ -0,0 +1,100 @@
package frc4388.utility.compute;
import static edu.wpi.first.units.Units.Rotations;
import java.io.FileInputStream;
import java.io.FileOutputStream;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.wpilibj.DutyCycleEncoder;
public class JankCoder {
DutyCycleEncoder m_encoder;
boolean loaded_rotations = false;
double lastRotation = 0;
double offset = 0;
public JankCoder(int dio_channel) {
m_encoder = new DutyCycleEncoder(dio_channel);
loadRotations();
}
public JankCoder(int dio_channel, double _offset) {
m_encoder = new DutyCycleEncoder(dio_channel);
loadRotations();
}
public void update() {
if(!m_encoder.isConnected()) {
return;
}
if(!loaded_rotations) {
loadRotations();
} else {
double curRot = m_encoder.get();
if(lastRotation - curRot > 0.5) {
offset += 1;
saveRotations();
} else if (curRot - lastRotation > 0.5) {
offset -= 1;
saveRotations();
}
lastRotation = curRot;
}
}
public double get() {
return (double) offset + m_encoder.get();
}
public Angle getRotations() {
return Rotations.of(get());
}
public int getRotationCount() {
return (int) offset;
}
public void resetRotation() {
setRotation(0);
}
public void setRotation(double rotation) {
offset = rotation - m_encoder.get();
saveRotations();
}
private void saveRotations() {
try (FileOutputStream stream = new FileOutputStream("/home/lvuser/encoder" + m_encoder.getSourceChannel())) {
stream.write(DataUtils.doubleToByteArray(offset));
} catch (Exception e) {
// e.printStackTrace();
System.out.println("ENCODER: Unable to write to trim file `" + m_encoder.getSourceChannel() + "`!?!");
}
}
private boolean loadRotations() {
lastRotation = m_encoder.get();
this.loaded_rotations = true;
try (FileInputStream stream = new FileInputStream("/home/lvuser/encoder" + m_encoder.getSourceChannel())) {
offset = DataUtils.byteArrayToDouble(stream.readNBytes(4));
// clampModify();
// modified = false;
// if (fileValue != currentValue) {
// // System.out.println("TRIMS: Loaded trim `" + trimName + "` has a value that is higher than or less than the bounds set for the trim, clamping...");
// // modified = true;
// }
return true;
} catch (Exception e) {
// e.printStackTrace();
System.out.println("ENCODER: Unable to read encoder `" + m_encoder.getSourceChannel() + "`, using current value...");
return false;
}
}
}
@@ -0,0 +1,105 @@
package frc4388.utility.compute;
import static edu.wpi.first.units.Units.Rotations;
import java.io.FileInputStream;
import java.io.FileOutputStream;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.wpilibj.DutyCycleEncoder;
import frc4388.utility.configurable.ConfigurableDouble;
public class JankCoder {
DutyCycleEncoder m_encoder;
boolean loaded_rotations = false;
int rotations = 0;
double lastRotation = 0;
final ConfigurableDouble offset;
public JankCoder(int dio_channel, ConfigurableDouble offset) {
this.offset = offset;
m_encoder = new DutyCycleEncoder(dio_channel);
loadRotations();
}
public void update() {
// if(!m_encoder.isConnected()) {
// return;
// }
if(!loaded_rotations) {
loadRotations();
} else {
double curRot = m_encoder.get();
if(lastRotation - curRot > 0.5) {
rotations += 1;
saveRotations();
} else if (curRot - lastRotation > 0.5) {
rotations -= 1;
saveRotations();
}
lastRotation = curRot;
}
}
public double get() {
return (double) rotations + m_encoder.get() + offset.get();
}
public Angle getRotations() {
return Rotations.of(get());
}
public int getRotationCount() {
return rotations;
}
public void resetRotations() {
offset.set(-m_encoder.get());
setRotations(0);
}
public void setRotations(int rotation) {
rotations = rotation;
saveRotations();
}
public boolean isConnected() {
return m_encoder.isConnected();
}
public void saveRotations() {
try (FileOutputStream stream = new FileOutputStream("/home/lvuser/encoder" + m_encoder.getSourceChannel())) {
stream.write(DataUtils.intToByteArray(rotations));
} catch (Exception e) {
// e.printStackTrace();
System.out.println("ENCODER: Unable to write to trim file `" + m_encoder.getSourceChannel() + "`!?!");
}
}
public boolean loadRotations() {
lastRotation = m_encoder.get();
this.loaded_rotations = true;
try (FileInputStream stream = new FileInputStream("/home/lvuser/encoder" + m_encoder.getSourceChannel())) {
int fileValue = DataUtils.byteArrayToInt(stream.readNBytes(4));
rotations = fileValue;
// clampModify();
// modified = false;
// if (fileValue != currentValue) {
// // System.out.println("TRIMS: Loaded trim `" + trimName + "` has a value that is higher than or less than the bounds set for the trim, clamping...");
// // modified = true;
// }
return true;
} catch (Exception e) {
// e.printStackTrace();
System.out.println("ENCODER: Unable to read encoder `" + m_encoder.getSourceChannel() + "`, using current value...");
return false;
}
}
}
@@ -20,4 +20,8 @@ public class ConfigurableDouble {
public double get() { public double get() {
return SmartDashboard.getNumber(name, defualtValue); return SmartDashboard.getNumber(name, defualtValue);
} }
public void set(double value) {
SmartDashboard.putNumber(name, value);
}
} }
@@ -0,0 +1,97 @@
package frc4388.utility.status;
import com.revrobotics.spark.SparkBase.Faults;
import com.revrobotics.spark.SparkBase.Warnings;
import com.revrobotics.spark.SparkMax;
import frc4388.utility.status.Status.ReportLevel;
public class FaultSparkMax implements Queryable {
private String name;
private SparkMax motor;
public static void addDevice(SparkMax motor, String name) {
FaultSparkMax p = new FaultSparkMax();
p.name = name;
p.motor = motor;
FaultReporter.register(p);
}
@Override
public String getName() {
return name;
}
@Override
public Status diagnosticStatus() {
Status s = new Status();
s.addReport(ReportLevel.INFO, "Firmware Version: " + motor.getFirmwareString());
s.addReport(ReportLevel.INFO, "Voltage: " + motor.getBusVoltage());
s.addReport(ReportLevel.INFO, "Current: " + motor.getOutputCurrent());
s.addReport(ReportLevel.INFO, "Device temp (C): " + motor.getMotorTemperature());
s.addReport(ReportLevel.INFO, "Position: " + motor.getEncoder().getPosition());
s.addReport(ReportLevel.INFO, "Velocity: " + motor.getEncoder().getVelocity());
s.addReport(ReportLevel.INFO, "Forward hard limit: " + motor.getForwardLimitSwitch().isPressed());
s.addReport(ReportLevel.INFO, "Reverse hard limit: " + motor.getReverseLimitSwitch().isPressed());
s.addReport(ReportLevel.INFO, "Forward soft limit: " + motor.getForwardSoftLimit().isReached());
s.addReport(ReportLevel.INFO, "Reverse soft limit: " + motor.getReverseSoftLimit().isReached());
// faults
Faults faults = motor.getFaults();
if(faults.can) {
s.addReport(ReportLevel.ERROR, "CAN Fault (Joe Johnson)");
}
if(faults.escEeprom) {
s.addReport(ReportLevel.ERROR, "Escape Eeprom. Cannot write to internal memory (oh god I don't want to think about what this means)");
}
if(faults.firmware) {
s.addReport(ReportLevel.ERROR, "Firmware Fault");
}
if(faults.gateDriver) {
s.addReport(ReportLevel.ERROR, "Gate Driver Fault");
}
if(faults.motorType) {
s.addReport(ReportLevel.ERROR, "Motor type Fault");
}
if(faults.other) {
s.addReport(ReportLevel.ERROR, "Fault type is 'other'. Hope for the best!");
}
if(faults.sensor) {
s.addReport(ReportLevel.ERROR, "Sensor fault");
}
if(faults.temperature) {
s.addReport(ReportLevel.ERROR, "Temperature fault");
}
Warnings warnings = motor.getWarnings();
if(warnings.brownout) {
s.addReport(ReportLevel.WARNING, "Brownout detected");
}
if (warnings.escEeprom) {
s.addReport(ReportLevel.WARNING, "Escape Eeprom. Cannot write to internal memory. (Why is only a warning)");
}
if (warnings.extEeprom) {
s.addReport(ReportLevel.WARNING, "Exit Eeprom. Cannot write to internal memory. (Why is only a warning)");
}
if (warnings.hasReset) {
s.addReport(ReportLevel.WARNING, "Has Reset");
}
if (warnings.other) {
s.addReport(ReportLevel.WARNING, "Other. Warning message sold seperately");
}
if (warnings.overcurrent) {
s.addReport(ReportLevel.WARNING, "Overcurrent");
}
if (warnings.sensor) {
s.addReport(ReportLevel.WARNING, "Sensor problem");
}
if (warnings.stall) {
s.addReport(ReportLevel.WARNING, "Motor stall detected");
}
return s;
}
}
+3 -3
View File
@@ -1,7 +1,7 @@
{ {
"fileName": "AdvantageKit.json", "fileName": "AdvantageKit.json",
"name": "AdvantageKit", "name": "AdvantageKit",
"version": "26.0.0", "version": "26.0.2",
"uuid": "d820cc26-74e3-11ec-90d6-0242ac120003", "uuid": "d820cc26-74e3-11ec-90d6-0242ac120003",
"frcYear": "2026", "frcYear": "2026",
"mavenUrls": [ "mavenUrls": [
@@ -12,14 +12,14 @@
{ {
"groupId": "org.littletonrobotics.akit", "groupId": "org.littletonrobotics.akit",
"artifactId": "akit-java", "artifactId": "akit-java",
"version": "26.0.0" "version": "26.0.2"
} }
], ],
"jniDependencies": [ "jniDependencies": [
{ {
"groupId": "org.littletonrobotics.akit", "groupId": "org.littletonrobotics.akit",
"artifactId": "akit-wpilibio", "artifactId": "akit-wpilibio",
"version": "26.0.0", "version": "26.0.2",
"skipInvalidPlatforms": false, "skipInvalidPlatforms": false,
"isJar": false, "isJar": false,
"validPlatforms": [ "validPlatforms": [
@@ -1,7 +1,7 @@
{ {
"fileName": "Phoenix6-26.1.0.json", "fileName": "Phoenix6-26.1.3.json",
"name": "CTRE-Phoenix (v6)", "name": "CTRE-Phoenix (v6)",
"version": "26.1.0", "version": "26.1.3",
"frcYear": "2026", "frcYear": "2026",
"uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
"mavenUrls": [ "mavenUrls": [
@@ -19,14 +19,14 @@
{ {
"groupId": "com.ctre.phoenix6", "groupId": "com.ctre.phoenix6",
"artifactId": "wpiapi-java", "artifactId": "wpiapi-java",
"version": "26.1.0" "version": "26.1.3"
} }
], ],
"jniDependencies": [ "jniDependencies": [
{ {
"groupId": "com.ctre.phoenix6", "groupId": "com.ctre.phoenix6",
"artifactId": "api-cpp", "artifactId": "api-cpp",
"version": "26.1.0", "version": "26.1.3",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -40,7 +40,7 @@
{ {
"groupId": "com.ctre.phoenix6", "groupId": "com.ctre.phoenix6",
"artifactId": "tools", "artifactId": "tools",
"version": "26.1.0", "version": "26.1.3",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -54,7 +54,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "api-cpp-sim", "artifactId": "api-cpp-sim",
"version": "26.1.0", "version": "26.1.3",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -68,7 +68,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "tools-sim", "artifactId": "tools-sim",
"version": "26.1.0", "version": "26.1.3",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -82,7 +82,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonSRX", "artifactId": "simTalonSRX",
"version": "26.1.0", "version": "26.1.3",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -96,7 +96,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simVictorSPX", "artifactId": "simVictorSPX",
"version": "26.1.0", "version": "26.1.3",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -110,7 +110,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simPigeonIMU", "artifactId": "simPigeonIMU",
"version": "26.1.0", "version": "26.1.3",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -124,7 +124,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFX", "artifactId": "simProTalonFX",
"version": "26.1.0", "version": "26.1.3",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -138,7 +138,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFXS", "artifactId": "simProTalonFXS",
"version": "26.1.0", "version": "26.1.3",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -152,7 +152,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANcoder", "artifactId": "simProCANcoder",
"version": "26.1.0", "version": "26.1.3",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -166,7 +166,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProPigeon2", "artifactId": "simProPigeon2",
"version": "26.1.0", "version": "26.1.3",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -180,7 +180,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANrange", "artifactId": "simProCANrange",
"version": "26.1.0", "version": "26.1.3",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -194,7 +194,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANdi", "artifactId": "simProCANdi",
"version": "26.1.0", "version": "26.1.3",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -208,7 +208,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANdle", "artifactId": "simProCANdle",
"version": "26.1.0", "version": "26.1.3",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -224,7 +224,7 @@
{ {
"groupId": "com.ctre.phoenix6", "groupId": "com.ctre.phoenix6",
"artifactId": "wpiapi-cpp", "artifactId": "wpiapi-cpp",
"version": "26.1.0", "version": "26.1.3",
"libName": "CTRE_Phoenix6_WPI", "libName": "CTRE_Phoenix6_WPI",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -240,7 +240,7 @@
{ {
"groupId": "com.ctre.phoenix6", "groupId": "com.ctre.phoenix6",
"artifactId": "tools", "artifactId": "tools",
"version": "26.1.0", "version": "26.1.3",
"libName": "CTRE_PhoenixTools", "libName": "CTRE_PhoenixTools",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -256,7 +256,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "wpiapi-cpp-sim", "artifactId": "wpiapi-cpp-sim",
"version": "26.1.0", "version": "26.1.3",
"libName": "CTRE_Phoenix6_WPISim", "libName": "CTRE_Phoenix6_WPISim",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -272,7 +272,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "tools-sim", "artifactId": "tools-sim",
"version": "26.1.0", "version": "26.1.3",
"libName": "CTRE_PhoenixTools_Sim", "libName": "CTRE_PhoenixTools_Sim",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -288,7 +288,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonSRX", "artifactId": "simTalonSRX",
"version": "26.1.0", "version": "26.1.3",
"libName": "CTRE_SimTalonSRX", "libName": "CTRE_SimTalonSRX",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -304,7 +304,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simVictorSPX", "artifactId": "simVictorSPX",
"version": "26.1.0", "version": "26.1.3",
"libName": "CTRE_SimVictorSPX", "libName": "CTRE_SimVictorSPX",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -320,7 +320,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simPigeonIMU", "artifactId": "simPigeonIMU",
"version": "26.1.0", "version": "26.1.3",
"libName": "CTRE_SimPigeonIMU", "libName": "CTRE_SimPigeonIMU",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -336,7 +336,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFX", "artifactId": "simProTalonFX",
"version": "26.1.0", "version": "26.1.3",
"libName": "CTRE_SimProTalonFX", "libName": "CTRE_SimProTalonFX",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -352,7 +352,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFXS", "artifactId": "simProTalonFXS",
"version": "26.1.0", "version": "26.1.3",
"libName": "CTRE_SimProTalonFXS", "libName": "CTRE_SimProTalonFXS",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -368,7 +368,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANcoder", "artifactId": "simProCANcoder",
"version": "26.1.0", "version": "26.1.3",
"libName": "CTRE_SimProCANcoder", "libName": "CTRE_SimProCANcoder",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -384,7 +384,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProPigeon2", "artifactId": "simProPigeon2",
"version": "26.1.0", "version": "26.1.3",
"libName": "CTRE_SimProPigeon2", "libName": "CTRE_SimProPigeon2",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -400,7 +400,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANrange", "artifactId": "simProCANrange",
"version": "26.1.0", "version": "26.1.3",
"libName": "CTRE_SimProCANrange", "libName": "CTRE_SimProCANrange",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -416,7 +416,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANdi", "artifactId": "simProCANdi",
"version": "26.1.0", "version": "26.1.3",
"libName": "CTRE_SimProCANdi", "libName": "CTRE_SimProCANdi",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -432,7 +432,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANdle", "artifactId": "simProCANdle",
"version": "26.1.0", "version": "26.1.3",
"libName": "CTRE_SimProCANdle", "libName": "CTRE_SimProCANdle",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
+133
View File
@@ -0,0 +1,133 @@
{
"fileName": "REVLib.json",
"name": "REVLib",
"version": "2026.0.5",
"frcYear": "2026",
"uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
"mavenUrls": [
"https://maven.revrobotics.com/"
],
"jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2026.json",
"javaDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-java",
"version": "2026.0.5"
}
],
"jniDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2026.0.5",
"skipInvalidPlatforms": true,
"isJar": false,
"validPlatforms": [
"windowsx86-64",
"linuxarm64",
"linuxx86-64",
"linuxathena",
"linuxarm32",
"osxuniversal"
]
},
{
"groupId": "com.revrobotics.frc",
"artifactId": "RevLibBackendDriver",
"version": "2026.0.5",
"skipInvalidPlatforms": true,
"isJar": false,
"validPlatforms": [
"windowsx86-64",
"linuxarm64",
"linuxx86-64",
"linuxathena",
"linuxarm32",
"osxuniversal"
]
},
{
"groupId": "com.revrobotics.frc",
"artifactId": "RevLibWpiBackendDriver",
"version": "2026.0.5",
"skipInvalidPlatforms": true,
"isJar": false,
"validPlatforms": [
"windowsx86-64",
"linuxarm64",
"linuxx86-64",
"linuxathena",
"linuxarm32",
"osxuniversal"
]
}
],
"cppDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-cpp",
"version": "2026.0.5",
"libName": "REVLib",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxarm64",
"linuxx86-64",
"linuxathena",
"linuxarm32",
"osxuniversal"
]
},
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2026.0.5",
"libName": "REVLibDriver",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxarm64",
"linuxx86-64",
"linuxathena",
"linuxarm32",
"osxuniversal"
]
},
{
"groupId": "com.revrobotics.frc",
"artifactId": "RevLibBackendDriver",
"version": "2026.0.5",
"libName": "BackendDriver",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxarm64",
"linuxx86-64",
"linuxathena",
"linuxarm32",
"osxuniversal"
]
},
{
"groupId": "com.revrobotics.frc",
"artifactId": "RevLibWpiBackendDriver",
"version": "2026.0.5",
"libName": "REVLibWpi",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxarm64",
"linuxx86-64",
"linuxathena",
"linuxarm32",
"osxuniversal"
]
}
]
}
+6 -6
View File
@@ -1,7 +1,7 @@
{ {
"fileName": "photonlib.json", "fileName": "photonlib.json",
"name": "photonlib", "name": "photonlib",
"version": "v2025.3.1", "version": "v2026.3.2",
"uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004", "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004",
"frcYear": "2026", "frcYear": "2026",
"mavenUrls": [ "mavenUrls": [
@@ -13,7 +13,7 @@
{ {
"groupId": "org.photonvision", "groupId": "org.photonvision",
"artifactId": "photontargeting-cpp", "artifactId": "photontargeting-cpp",
"version": "v2025.3.1", "version": "v2026.3.2",
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"isJar": false, "isJar": false,
"validPlatforms": [ "validPlatforms": [
@@ -28,7 +28,7 @@
{ {
"groupId": "org.photonvision", "groupId": "org.photonvision",
"artifactId": "photonlib-cpp", "artifactId": "photonlib-cpp",
"version": "v2025.3.1", "version": "v2026.3.2",
"libName": "photonlib", "libName": "photonlib",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -43,7 +43,7 @@
{ {
"groupId": "org.photonvision", "groupId": "org.photonvision",
"artifactId": "photontargeting-cpp", "artifactId": "photontargeting-cpp",
"version": "v2025.3.1", "version": "v2026.3.2",
"libName": "photontargeting", "libName": "photontargeting",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -60,12 +60,12 @@
{ {
"groupId": "org.photonvision", "groupId": "org.photonvision",
"artifactId": "photonlib-java", "artifactId": "photonlib-java",
"version": "v2025.3.1" "version": "v2026.3.2"
}, },
{ {
"groupId": "org.photonvision", "groupId": "org.photonvision",
"artifactId": "photontargeting-java", "artifactId": "photontargeting-java",
"version": "v2025.3.1" "version": "v2026.3.2"
} }
] ]
} }