mirror of
https://github.com/Team4388/2026KPopRobotHunters.git
synced 2026-06-08 16:28:05 -06:00
LEDs
This commit is contained in:
@@ -129,7 +129,7 @@ public class Robot extends LoggedRobot {
|
||||
|
||||
@Override
|
||||
public void teleopInit() {
|
||||
m_robotContainer.stop();
|
||||
// m_robotContainer.stop();
|
||||
// This makes sure that the autonomous stops running when
|
||||
// teleop starts running. If you want the autonomous to
|
||||
// continue until interrupted by another command, remove
|
||||
|
||||
@@ -30,6 +30,7 @@ import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
// Autos
|
||||
import frc4388.utility.controller.VirtualController;
|
||||
import frc4388.utility.controller.XboxController;
|
||||
import frc4388.utility.structs.LEDPatterns;
|
||||
import frc4388.robot.commands.MoveForTimeCommand;
|
||||
import frc4388.robot.commands.alignment.RotTo45;
|
||||
import frc4388.robot.commands.MoveUntilSuply;
|
||||
@@ -40,6 +41,7 @@ import frc4388.robot.commands.MoveUntilSuply;
|
||||
import frc4388.robot.commands.wait.waitSupplier;
|
||||
import frc4388.robot.constants.Constants;
|
||||
import frc4388.robot.constants.Constants.AutoConstants;
|
||||
import frc4388.robot.constants.Constants.LEDConstants;
|
||||
import frc4388.robot.constants.Constants.OIConstants;
|
||||
import frc4388.robot.constants.Constants.SimConstants.Mode;
|
||||
|
||||
@@ -63,10 +65,10 @@ public class RobotContainer {
|
||||
public final RobotMap m_robotMap = new RobotMap(Mode.REAL);
|
||||
|
||||
/* Subsystems */
|
||||
public final LED m_robotLED = new LED();
|
||||
public final LED m_robotLED = new LED(LEDConstants.LED_SPARK_ID);
|
||||
public final Vision m_vision = new Vision();
|
||||
// public final Elevator m_robotElevator = new Elevator(m_robotMap.elevatorIO, m_robotLED);
|
||||
public final SwerveDrive m_robotSwerveDrive = new SwerveDrive(m_robotMap.swerveDrivetrain, m_vision);
|
||||
// public final SwerveDrive m_robotSwerveDrive = new SwerveDrive(m_robotMap.swerveDrivetrain, m_vision);
|
||||
// public final SwerveDrive m_robotSwerveDrive = new SwerveDrive(m_robotMap.swerveDrivetrain);
|
||||
|
||||
// public final LiDAR reefLidar = new LiDAR(m_robotMap.reefLidar, "Reef");
|
||||
@@ -81,11 +83,11 @@ public class RobotContainer {
|
||||
// public List<Subsystem> subsystems = new ArrayList<>();
|
||||
|
||||
// ! Teleop Commands
|
||||
public void stop() {
|
||||
new InstantCommand(()->{}, m_robotSwerveDrive).schedule();
|
||||
m_robotSwerveDrive.stopModules();
|
||||
Constants.AutoConstants.Y_OFFSET_TRIM.set(0);
|
||||
}
|
||||
// public void stop() {
|
||||
// new InstantCommand(()->{}, m_robotSwerveDrive).schedule();
|
||||
// m_robotSwerveDrive.stopModules();
|
||||
// Constants.AutoConstants.Y_OFFSET_TRIM.set(0);
|
||||
// }
|
||||
|
||||
// ! /* Autos */
|
||||
private SendableChooser<String> autoChooser;
|
||||
@@ -96,9 +98,9 @@ public class RobotContainer {
|
||||
|
||||
configureButtonBindings();
|
||||
|
||||
DeferredBlock.addBlock(() -> { // Called on first robot enable
|
||||
m_robotSwerveDrive.resetGyro();
|
||||
}, false);
|
||||
// DeferredBlock.addBlock(() -> { // Called on first robot enable
|
||||
// m_robotSwerveDrive.resetGyro();
|
||||
// }, false);
|
||||
DeferredBlock.addBlock(() -> { // Called on every robot enable
|
||||
TimesNegativeOne.update();
|
||||
}, true);
|
||||
@@ -106,27 +108,27 @@ public class RobotContainer {
|
||||
|
||||
DriverStation.silenceJoystickConnectionWarning(true);
|
||||
|
||||
m_robotSwerveDrive.setDefaultCommand(new RunCommand(() -> {
|
||||
// m_robotSwerveDrive.setDefaultCommand(new RunCommand(() -> {
|
||||
|
||||
// IF the driver is holding the aim button, aim the robot towards the hub
|
||||
if(m_driverXbox.getRightTriggerAxis() > 0.5) {
|
||||
// Aim
|
||||
Translation2d shootTarget = new Translation2d();
|
||||
// new Rotation2()
|
||||
Rotation2d ang = m_robotSwerveDrive.getPose2d().getTranslation().minus(shootTarget).getAngle();
|
||||
m_robotSwerveDrive.driveFieldAngle(
|
||||
getDeadbandedDriverController().getLeft(),
|
||||
ang);
|
||||
} else {
|
||||
// Drive normally
|
||||
m_robotSwerveDrive.driveWithInput(
|
||||
getDeadbandedDriverController().getLeft(),
|
||||
getDeadbandedDriverController().getRight(),true);
|
||||
}
|
||||
// // IF the driver is holding the aim button, aim the robot towards the hub
|
||||
// if(m_driverXbox.getRightTriggerAxis() > 0.5) {
|
||||
// // Aim
|
||||
// Translation2d shootTarget = new Translation2d();
|
||||
// // new Rotation2()
|
||||
// Rotation2d ang = m_robotSwerveDrive.getPose2d().getTranslation().minus(shootTarget).getAngle();
|
||||
// m_robotSwerveDrive.driveFieldAngle(
|
||||
// getDeadbandedDriverController().getLeft(),
|
||||
// ang);
|
||||
// } else {
|
||||
// // Drive normally
|
||||
// m_robotSwerveDrive.driveWithInput(
|
||||
// getDeadbandedDriverController().getLeft(),
|
||||
// getDeadbandedDriverController().getRight(),true);
|
||||
// }
|
||||
|
||||
}, m_robotSwerveDrive)
|
||||
.withName("SwerveDrive DefaultCommand"));
|
||||
m_robotSwerveDrive.setToSlow();
|
||||
// }, m_robotSwerveDrive)
|
||||
// .withName("SwerveDrive DefaultCommand"));
|
||||
// m_robotSwerveDrive.setToSlow();
|
||||
|
||||
}
|
||||
|
||||
@@ -142,28 +144,38 @@ public class RobotContainer {
|
||||
private void configureButtonBindings() {
|
||||
|
||||
|
||||
// new JoystickButton(getDeadbandedDriverController(), XboxController.A_BUTTON)
|
||||
// .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyro()));
|
||||
|
||||
|
||||
new JoystickButton(getDeadbandedDriverController(), XboxController.A_BUTTON)
|
||||
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyro()));
|
||||
.onTrue(new InstantCommand(() -> m_robotLED.setMode(LEDPatterns.C1C2_GRADIENT)));
|
||||
|
||||
|
||||
// new JoystickButton(getDeadbandedDriverController(), XboxController.X_BUTTON)
|
||||
// .onTrue(new RotTo45(m_robotSwerveDrive));
|
||||
|
||||
|
||||
new JoystickButton(getDeadbandedDriverController(), XboxController.B_BUTTON)
|
||||
.onTrue(new InstantCommand(() -> {m_robotSwerveDrive.softStop();}, m_robotSwerveDrive));
|
||||
.onTrue(new InstantCommand(() -> m_robotLED.setMode(LEDPatterns.OCEAN_RAINBOW)));
|
||||
|
||||
new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON)
|
||||
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUp()));
|
||||
|
||||
new JoystickButton(getDeadbandedDriverController(), XboxController.LEFT_BUMPER_BUTTON)
|
||||
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftDown()));
|
||||
new JoystickButton(getDeadbandedDriverController(), XboxController.Y_BUTTON)
|
||||
.onTrue(new InstantCommand(() -> m_robotLED.setMode(LEDPatterns.RAINBOW_RAINBOW)));
|
||||
|
||||
new JoystickButton(getDeadbandedDriverController(), XboxController.START_BUTTON)
|
||||
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.activateLuigiMode()));
|
||||
|
||||
new JoystickButton(getDeadbandedDriverController(), XboxController.BACK_BUTTON)
|
||||
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.deactivateLuigiMode()));
|
||||
.onTrue(new InstantCommand(() -> m_robotLED.setTo5V()));
|
||||
|
||||
|
||||
// new JoystickButton(getDeadbandedDriverController(), XboxController.B_BUTTON)
|
||||
// .onTrue(new InstantCommand(() -> {m_robotSwerveDrive.softStop();}, m_robotSwerveDrive));
|
||||
|
||||
// new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON)
|
||||
// .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUp()));
|
||||
|
||||
// new JoystickButton(getDeadbandedDriverController(), XboxController.LEFT_BUMPER_BUTTON)
|
||||
// .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftDown()));
|
||||
|
||||
// new JoystickButton(getDeadbandedDriverController(), XboxController.START_BUTTON)
|
||||
// .onTrue(new InstantCommand(() -> m_robotSwerveDrive.activateLuigiMode()));
|
||||
|
||||
|
||||
// new JoystickButton(getDeadbandedDriverController(), XboxController.BACK_BUTTON)
|
||||
// .onTrue(new InstantCommand(() -> m_robotSwerveDrive.deactivateLuigiMode()));
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -214,17 +226,17 @@ public class RobotContainer {
|
||||
}
|
||||
|
||||
autoChooser.onChange((filename) -> {
|
||||
autoChooserUpdated = true;
|
||||
if (filename.equals("Taxi")) {
|
||||
autoCommand = new SequentialCommandGroup(
|
||||
new MoveForTimeCommand(m_robotSwerveDrive,
|
||||
new Translation2d(0, -1),
|
||||
new Translation2d(), 1000, true
|
||||
), new InstantCommand(()-> {m_robotSwerveDrive.softStop();} , m_robotSwerveDrive));
|
||||
} else {
|
||||
autoCommand = new PathPlannerAuto(filename);
|
||||
}
|
||||
System.out.println("Robot Auto Changed " + filename);
|
||||
// autoChooserUpdated = true;
|
||||
// if (filename.equals("Taxi")) {
|
||||
// autoCommand = new SequentialCommandGroup(
|
||||
// new MoveForTimeCommand(m_robotSwerveDrive,
|
||||
// new Translation2d(0, -1),
|
||||
// new Translation2d(), 1000, true
|
||||
// ), new InstantCommand(()-> {m_robotSwerveDrive.softStop();} , m_robotSwerveDrive));
|
||||
// } else {
|
||||
// autoCommand = new PathPlannerAuto(filename);
|
||||
// }
|
||||
// System.out.println("Robot Auto Changed " + filename);
|
||||
});
|
||||
// SmartDashboard.putData(autoChooser);
|
||||
|
||||
|
||||
@@ -53,7 +53,7 @@ public class RobotMap {
|
||||
// public final Spark LEDController = new Spark(LEDConstants.LED_SPARK_ID);
|
||||
|
||||
/* Swreve Drive Subsystem */
|
||||
public final SwerveIO swerveDrivetrain;
|
||||
// public final SwerveIO swerveDrivetrain;
|
||||
|
||||
// /* Elevator Subsystem */
|
||||
// public final ElevatorIO elevatorIO;
|
||||
@@ -76,13 +76,13 @@ public class RobotMap {
|
||||
// reverseLidar = new LidarReal(LiDARConstants.REVERSE_LIDAR_DIO_CHANNEL);
|
||||
|
||||
// Configure swerve drive train
|
||||
SwerveDrivetrain<TalonFX, TalonFX, CANcoder> swerveDrivetrainReal = new SwerveDrivetrain<TalonFX, TalonFX, CANcoder> (TalonFX::new, TalonFX::new, CANcoder::new,
|
||||
SwerveDriveConstants.DrivetrainConstants,
|
||||
SwerveDriveConstants.FRONT_LEFT, SwerveDriveConstants.FRONT_RIGHT,
|
||||
SwerveDriveConstants.BACK_LEFT, SwerveDriveConstants.BACK_RIGHT
|
||||
);
|
||||
// SwerveDrivetrain<TalonFX, TalonFX, CANcoder> swerveDrivetrainReal = new SwerveDrivetrain<TalonFX, TalonFX, CANcoder> (TalonFX::new, TalonFX::new, CANcoder::new,
|
||||
// SwerveDriveConstants.DrivetrainConstants,
|
||||
// SwerveDriveConstants.FRONT_LEFT, SwerveDriveConstants.FRONT_RIGHT,
|
||||
// SwerveDriveConstants.BACK_LEFT, SwerveDriveConstants.BACK_RIGHT
|
||||
// );
|
||||
|
||||
swerveDrivetrain = new SwerveReal(swerveDrivetrainReal);
|
||||
// swerveDrivetrain = new SwerveReal(swerveDrivetrainReal);
|
||||
|
||||
// Configure elevator
|
||||
|
||||
@@ -99,23 +99,23 @@ public class RobotMap {
|
||||
|
||||
|
||||
// Fault
|
||||
FaultPidgeon2.addDevice(swerveDrivetrainReal.getPigeon2(), "Gyro");
|
||||
// FaultPidgeon2.addDevice(swerveDrivetrainReal.getPigeon2(), "Gyro");
|
||||
|
||||
// FaultTalonFX.addDevice(elevator, "Elevator");
|
||||
// FaultTalonFX.addDevice(endeffector, "Endeffector");
|
||||
// // FaultTalonFX.addDevice(elevator, "Elevator");
|
||||
// // FaultTalonFX.addDevice(endeffector, "Endeffector");
|
||||
|
||||
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getDriveMotor(), "Module 0 Drive");
|
||||
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getSteerMotor(), "Module 0 Steer");
|
||||
FaultCANCoder.addDevice(swerveDrivetrainReal.getModule(0).getEncoder(), "Module 0 CANCoder");
|
||||
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(1).getDriveMotor(), "Module 1 Drive");
|
||||
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(1).getSteerMotor(), "Module 1 Steer");
|
||||
FaultCANCoder.addDevice(swerveDrivetrainReal.getModule(1).getEncoder(), "Module 1 CANCoder");
|
||||
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(2).getDriveMotor(), "Module 2 Drive");
|
||||
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(2).getSteerMotor(), "Module 2 Steer");
|
||||
FaultCANCoder.addDevice(swerveDrivetrainReal.getModule(2).getEncoder(), "Module 2 CANCoder");
|
||||
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(3).getDriveMotor(), "Module 3 Drive");
|
||||
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(3).getSteerMotor(), "Module 3 Steer");
|
||||
FaultCANCoder.addDevice(swerveDrivetrainReal.getModule(3).getEncoder(), "Module 3 CANCoder");
|
||||
// FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getDriveMotor(), "Module 0 Drive");
|
||||
// FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getSteerMotor(), "Module 0 Steer");
|
||||
// FaultCANCoder.addDevice(swerveDrivetrainReal.getModule(0).getEncoder(), "Module 0 CANCoder");
|
||||
// FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(1).getDriveMotor(), "Module 1 Drive");
|
||||
// FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(1).getSteerMotor(), "Module 1 Steer");
|
||||
// FaultCANCoder.addDevice(swerveDrivetrainReal.getModule(1).getEncoder(), "Module 1 CANCoder");
|
||||
// FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(2).getDriveMotor(), "Module 2 Drive");
|
||||
// FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(2).getSteerMotor(), "Module 2 Steer");
|
||||
// FaultCANCoder.addDevice(swerveDrivetrainReal.getModule(2).getEncoder(), "Module 2 CANCoder");
|
||||
// FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(3).getDriveMotor(), "Module 3 Drive");
|
||||
// FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(3).getSteerMotor(), "Module 3 Steer");
|
||||
// FaultCANCoder.addDevice(swerveDrivetrainReal.getModule(3).getEncoder(), "Module 3 CANCoder");
|
||||
|
||||
break;
|
||||
// case SIM:
|
||||
@@ -125,7 +125,7 @@ public class RobotMap {
|
||||
// rightCamera = new VisionIO() {};
|
||||
// reefLidar = new LidarIO() {};
|
||||
// reverseLidar = new LidarIO() {};
|
||||
swerveDrivetrain = new SwerveIO() {};
|
||||
// swerveDrivetrain = new SwerveIO() {};
|
||||
// elevatorIO = new ElevatorIO() {};
|
||||
break;
|
||||
}
|
||||
|
||||
@@ -7,12 +7,12 @@ public final class BuildConstants {
|
||||
public static final String MAVEN_GROUP = "";
|
||||
public static final String MAVEN_NAME = "2026KPopRobotHunters";
|
||||
public static final String VERSION = "unspecified";
|
||||
public static final int GIT_REVISION = 8;
|
||||
public static final String GIT_SHA = "a27cde3f84484e652e5dcc1fd2f432871a2f0245";
|
||||
public static final String GIT_DATE = "2026-01-13 19:41:42 MST";
|
||||
public static final int GIT_REVISION = 9;
|
||||
public static final String GIT_SHA = "fe412d09810b860f3ac2a65296613feac250a4e9";
|
||||
public static final String GIT_DATE = "2026-01-19 13:57:43 MST";
|
||||
public static final String GIT_BRANCH = "master";
|
||||
public static final String BUILD_DATE = "2026-01-19 13:56:58 MST";
|
||||
public static final long BUILD_UNIX_TIME = 1768856218593L;
|
||||
public static final String BUILD_DATE = "2026-01-27 19:38:56 MST";
|
||||
public static final long BUILD_UNIX_TIME = 1769567936908L;
|
||||
public static final int DIRTY = 1;
|
||||
|
||||
private BuildConstants(){}
|
||||
|
||||
@@ -108,7 +108,7 @@ public final class Constants {
|
||||
public static final class LEDConstants {
|
||||
public static final int LED_SPARK_ID = 9;
|
||||
|
||||
public static final LEDPatterns DEFAULT_PATTERN = LEDPatterns.FOREST_WAVES;
|
||||
public static final LEDPatterns DEFAULT_PATTERN = LEDPatterns.SOLID_RED_ORANGE;
|
||||
|
||||
public static final LEDPatterns WAITING_PATTERN = LEDPatterns.SOLID_RED;
|
||||
public static final LEDPatterns DOWN_PATTERN = LEDPatterns.SOLID_YELLOW;
|
||||
|
||||
@@ -10,6 +10,7 @@ package frc4388.robot.subsystems;
|
||||
import org.littletonrobotics.junction.AutoLogOutput;
|
||||
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.PWM;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Spark;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc4388.robot.constants.Constants.LEDConstants;
|
||||
@@ -24,11 +25,19 @@ import frc4388.utility.structs.LEDPatterns;
|
||||
* Driver
|
||||
*/
|
||||
public class LED extends SubsystemBase implements Queryable {
|
||||
public LED() {
|
||||
private PWM m_pwm;
|
||||
|
||||
public LED(int PWMport) {
|
||||
FaultReporter.register(this);
|
||||
m_pwm = new PWM(PWMport);
|
||||
|
||||
m_pwm.setBoundsMicroseconds(2003, 1550, 1500, 1460, 999);
|
||||
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
|
||||
m_pwm.setSpeed(0.0);
|
||||
m_pwm.setZeroLatch();
|
||||
|
||||
}
|
||||
|
||||
private static Spark LEDController = new Spark(LEDConstants.LED_SPARK_ID);
|
||||
private LEDPatterns mode = LEDConstants.DEFAULT_PATTERN;
|
||||
|
||||
public void setMode(LEDPatterns pattern){
|
||||
@@ -41,14 +50,27 @@ public class LED extends SubsystemBase implements Queryable {
|
||||
}
|
||||
|
||||
public void update() {
|
||||
if(!LEDController.isAlive() || LEDController.isSafetyEnabled()) return;
|
||||
|
||||
if(DriverStation.isDisabled()){
|
||||
LEDController.set(LEDConstants.DEFAULT_PATTERN.getValue());
|
||||
m_pwm.setSpeed(LEDConstants.DEFAULT_PATTERN.getValue());
|
||||
}else
|
||||
LEDController.set(mode.getValue());
|
||||
m_pwm.setSpeed(mode.getValue());
|
||||
}
|
||||
|
||||
// I freaking hate unmaintained code so much
|
||||
// https://github.com/REVrobotics/Blinkin-Firmware/pull/12
|
||||
// Turns out the REV Blinkin firmware has an undocumented 'feature'
|
||||
// that means that whenever a specific pulse length is randomly generated,
|
||||
// the pulse has a chance of changing the selected strip of the Blinkin
|
||||
// 2125 μs for 5v, 2145 μs for 12v
|
||||
// Also check out: https://www.chiefdelphi.com/t/rev-blinkin-resetting-strip-mode-randomly/432510/12
|
||||
public void setTo5V() {
|
||||
try {
|
||||
m_pwm.setPulseTimeMicroseconds(2125);
|
||||
Thread.sleep(10);
|
||||
update();
|
||||
} catch (InterruptedException e) {}
|
||||
}
|
||||
|
||||
@AutoLogOutput
|
||||
public String state() {
|
||||
return mode.getClass().toString();
|
||||
@@ -63,8 +85,8 @@ public class LED extends SubsystemBase implements Queryable {
|
||||
public Status diagnosticStatus() {
|
||||
Status status = new Status();
|
||||
|
||||
if(!LEDController.isAlive())
|
||||
status.addReport(ReportLevel.ERROR, "LED is DISCONNECTED");
|
||||
// if(!LEDController.isAlive())
|
||||
// status.addReport(ReportLevel.ERROR, "LED is DISCONNECTED");
|
||||
|
||||
status.addReport(ReportLevel.INFO, "LED Mode: " + mode.name());
|
||||
|
||||
|
||||
Reference in New Issue
Block a user