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
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2025.3.1"
id "edu.wpi.first.GradleRIO" version "2025.3.2"
id "com.peterabeles.gversion" version "1.10"
}

Expand Down
13 changes: 11 additions & 2 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj.DriverStation.MatchType;
import edu.wpi.first.wpilibj.util.Color;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.util.Color;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.autonomous.AutoChooser;
Expand Down Expand Up @@ -119,7 +119,6 @@ public Robot() {
m_subsystems.add(m_intakes);
m_subsystems.add(m_hopper);
m_subsystems.add(m_taskScheduler);
m_subsystems.add(m_leds);

m_swerveSysId = new SwerveSysId(m_swerve.getSwerveModules(), "SwerveSysId");
}
Expand Down Expand Up @@ -326,6 +325,16 @@ public void teleopPeriodic() {
m_hopper.forward();
}

ElevatorState elevatorState = m_operatorController.getDesiredElevatorState();
if (m_operatorController.getWantsElevatorOverride()){
m_elevator.setState(elevatorState);
if(elevatorState == ElevatorState.L4) {
m_arm.setArmState(ArmState.EXTEND);
} else {
m_arm.setArmState(ArmState.STOW);
}
}

if (m_driverController.getWantsClearTellyTasks()) {
m_taskScheduler.reset();
}
Expand Down
14 changes: 7 additions & 7 deletions src/main/java/frc/robot/constants/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -192,10 +192,10 @@ public static class ElevatorConstants {
public final double k_IZone = 0.0;
public final double k_FF = 0.50;

public final double k_maxVelocity = 130;
public final double k_maxAcceleration = 400;
public final double k_maxVelocity = 150; //130;
public final double k_maxAcceleration = 600; //400;

public final int k_maxCurrent = 40;
public final int k_maxCurrent = 50;

public final double k_stowHeight = 0.0;
public final double k_L1Height = 16.0;
Expand All @@ -216,7 +216,7 @@ public static class ArmConstants {

public final double k_P = 10.8;
public final double k_I = 0.0;
public final double k_D = 0.0;
public final double k_D = 0.005;
public final double k_IZone = 0.0;

public final double k_FFS = 0.0;
Expand All @@ -227,15 +227,15 @@ public static class ArmConstants {
public final double k_constantVoltage = -0.4;
public final double k_stowThreshold = 0.02;

public final int k_maxCurrent = 10; // TODO: maybe change this?
public final int k_maxCurrent = 20; // TODO: maybe change this?

public double k_stowAngle;
public double k_L4Angle;
public double k_horizontalAngle;
public double k_sourceAngle;

public final double k_maxAcceleration = 0.8;
public final double k_maxVelocity = 0.4;
public final double k_maxAcceleration = 2.0;
public final double k_maxVelocity = 0.8;

public final double k_allowedError = 0.02; // TODO: Change this please 🥺
}
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/constants/MonarchConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,12 +31,12 @@ public MonarchConstants() {
Arm.k_horizontalAngle = 0.5074164867401123;
Arm.k_sourceAngle = 0.37661659717559814;

Intake.Left.k_stowPosition = 0.542549729347229;
Intake.Left.k_stowPosition = 0.551323413848877;
Intake.Left.k_groundPosition = 0.19023025035858154;
Intake.Left.k_ejectPosition = 0.31802046298980713;
Intake.Left.k_horizontalPosition = 0.31802046298980713;

Intake.Right.k_stowPosition = 0.499617338180542;
Intake.Right.k_stowPosition = 0.4848584532737732;
Intake.Right.k_groundPosition = 0.8430086374282837;
Intake.Right.k_ejectPosition = 0.7199869155883789;
Intake.Right.k_horizontalPosition = 0.7199869155883789;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,4 +92,8 @@ public boolean getWantsReverseHopper() {
public boolean getStoppedReverseHopper() {
return this.getRawButtonReleased(k_hopperButton);
}

public boolean getWantsElevatorOverride(){
return this.getRawButton(Button.START);
}
}
24 changes: 7 additions & 17 deletions src/main/java/frc/robot/subsystems/leds/LEDs.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,8 @@
import edu.wpi.first.wpilibj.AddressableLEDBuffer;
import edu.wpi.first.wpilibj.util.Color;
import frc.robot.constants.RobotConstants;
import frc.robot.subsystems.Subsystem;

public class LEDs extends Subsystem {
public class LEDs implements Runnable {
private static LEDs m_instance;

private AddressableLED m_led;
Expand All @@ -21,6 +20,8 @@ public class LEDs extends Subsystem {
.setColor(Color.kRed);
private Function<Integer, Function<Integer, Function<AddressableLEDBuffer, AddressableLEDBuffer>>> m_rightColor = LEDModes.rainbowChase;

private Thread m_thread;

public static LEDs getInstance() {
if (m_instance == null) {
m_instance = new LEDs();
Expand All @@ -29,18 +30,19 @@ public static LEDs getInstance() {
}

private LEDs() {
super("LEDs");

if (RobotConstants.robotConfig.LEDs.k_isEnabled) {
m_led = new AddressableLED(RobotConstants.robotConfig.LEDs.k_PWMId);
m_led.setLength(m_ledTotalLength);
m_buffer = new AddressableLEDBuffer(m_ledTotalLength);
m_led.start();

m_thread = new Thread(this);
m_thread.setDaemon(true);
}
}

@Override
public void periodic() {
public void run() {
if (RobotConstants.robotConfig.LEDs.k_isEnabled) {
setRightColorMode();
setLeftColorMode();
Expand Down Expand Up @@ -136,16 +138,4 @@ public void setRightColorMode() {
.apply(RobotConstants.robotConfig.LEDs.Right.k_length)
.apply(m_buffer);
}

@Override
public void stop() {
}

@Override
public void writePeriodicOutputs() {
}

@Override
public void reset() {
}
}
10 changes: 5 additions & 5 deletions vendordeps/libgrapplefrc2025.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "libgrapplefrc2025.json",
"name": "libgrapplefrc",
"version": "2025.1.0",
"version": "2025.1.3",
"frcYear": "2025",
"uuid": "8ef3423d-9532-4665-8339-206dae1d7168",
"mavenUrls": [
Expand All @@ -12,14 +12,14 @@
{
"groupId": "au.grapplerobotics",
"artifactId": "libgrapplefrcjava",
"version": "2025.1.0"
"version": "2025.1.3"
}
],
"jniDependencies": [
{
"groupId": "au.grapplerobotics",
"artifactId": "libgrapplefrcdriver",
"version": "2025.1.0",
"version": "2025.1.3",
"skipInvalidPlatforms": true,
"isJar": false,
"validPlatforms": [
Expand All @@ -37,7 +37,7 @@
{
"groupId": "au.grapplerobotics",
"artifactId": "libgrapplefrccpp",
"version": "2025.1.0",
"version": "2025.1.3",
"libName": "grapplefrc",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -55,7 +55,7 @@
{
"groupId": "au.grapplerobotics",
"artifactId": "libgrapplefrcdriver",
"version": "2025.1.0",
"version": "2025.1.3",
"libName": "grapplefrcdriver",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand Down