Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
27 commits
Select commit Hold shift + click to select a range
fe6c579
Added start for solo controller
Jetblackdragon Sep 19, 2025
e261298
All controls for solo controller
Jetblackdragon Sep 20, 2025
77b4bae
Merge branch 'main' of https://github.com/robototes/Reefscape2025 int…
Jetblackdragon Sep 20, 2025
d66fb27
spot
Jetblackdragon Sep 20, 2025
8a941ba
drive pratice changes
RobototesProgrammers Sep 21, 2025
c5f6f8e
V2 Set up for solo controls
Jetblackdragon Sep 24, 2025
e96486b
Override on driving when sticks are press down
Jetblackdragon Sep 24, 2025
d534668
dpot
Jetblackdragon Sep 24, 2025
fc7533b
LEDs for solo mode
TrisDooley Sep 24, 2025
460a687
Drive practice changes
RobototesProgrammers Sep 25, 2025
67b5733
Drive pracitce changes
RobototesProgrammers Sep 25, 2025
94dc7fc
Rebump up current limits
Jetblackdragon Sep 25, 2025
7d21c83
NO_GAME_PIECE mode actually works
Jetblackdragon Sep 25, 2025
e4a648d
Drive c
RobototesProgrammers Sep 28, 2025
b2d7d37
Code Clean up
Jetblackdragon Sep 28, 2025
13299e7
added booleanInIntake
Jetblackdragon Oct 1, 2025
3277113
Supercycling working
Jetblackdragon Oct 1, 2025
4503b62
quick fix
Jetblackdragon Oct 2, 2025
7c4aa9c
spot 😭
Jetblackdragon Oct 2, 2025
8260fb2
ground intake sets intake mode to coral
Jetblackdragon Oct 2, 2025
c382db6
command name correction
Jetblackdragon Oct 2, 2025
d80af1a
hold voltage out until retract
RobototesProgrammers Oct 3, 2025
0d78e78
Code cleanup
Jetblackdragon Oct 3, 2025
be66692
Merge branch 'cyclesuper' of https://github.com/robototes/Reefscape20…
Jetblackdragon Oct 3, 2025
0b3c6f6
merge conflict
Jetblackdragon Oct 3, 2025
b64b691
spotttt
Jetblackdragon Oct 3, 2025
9d38745
More code clean up
Jetblackdragon Oct 5, 2025
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
320 changes: 300 additions & 20 deletions src/main/java/frc/robot/Controls.java

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion src/main/java/frc/robot/generated/CompTunerConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ public class CompTunerConstants {

// The stator current at which the wheels start to slip;
// This needs to be tuned to your individual robot
private static final Current kSlipCurrent = Amps.of(120.0);
private static final Current kSlipCurrent = Amps.of(80.0);

// Initial configs for the drive and steer motors and the azimuth encoder; these cannot be null.
// Some configs will be overwritten; check the `with*InitialConfigs()` API documentation.
Expand Down
12 changes: 7 additions & 5 deletions src/main/java/frc/robot/sensors/ElevatorLight.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Hardware;
import frc.robot.util.ScoringMode;
import frc.robot.util.SoloScoringMode;
import java.util.function.DoubleSupplier;
import java.util.function.Supplier;

Expand Down Expand Up @@ -82,13 +82,15 @@ public Command animate(LEDPattern animation, String name) {
.withName("Animate" + name);
}

public Command showScoringMode(Supplier<ScoringMode> scoringMode) {
public Command showScoringMode(Supplier<SoloScoringMode> scoringMode) {
return run(() -> {
ScoringMode currentMode = scoringMode.get();
if (currentMode == ScoringMode.ALGAE) {
SoloScoringMode currentMode = scoringMode.get();
if (currentMode == SoloScoringMode.ALGAE_IN_CLAW) {
updateLEDs(LEDPattern.solid(Color.kTeal));
} else {
} else if (currentMode == SoloScoringMode.CORAL_IN_CLAW) {
updateLEDs(LEDPattern.solid(Color.kWhite));
} else if (currentMode == SoloScoringMode.NO_GAME_PIECE) {
updateLEDs(LEDPattern.solid(Color.kDeepPink));
}
})
.withName("Animate Scoring Mode");
Expand Down
11 changes: 8 additions & 3 deletions src/main/java/frc/robot/sensors/IntakeSensor.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@ public class IntakeSensor {

private final LaserCan intakeSensor;
// VALUES ARE IN METERS
private static final double INTAKE_LOWER_LIMIT = 0.010;
private static final double INTAKE_UPPER_LIMIT = 0.1;
private static final double INTAKE_LOWER_LIMIT = 0.005;
private static final double INTAKE_UPPER_LIMIT = 0.05;

public IntakeSensor() {
intakeSensor = new LaserCan(Hardware.GROUND_INTAKE_SENSOR);
Expand All @@ -29,7 +29,7 @@ public IntakeSensor() {
private void ConfigureSensor(LaserCan Sensor) {
try {
Sensor.setRangingMode(LaserCan.RangingMode.SHORT);
Sensor.setRegionOfInterest(new LaserCan.RegionOfInterest(8, 8, 16, 16));
Sensor.setRegionOfInterest(new LaserCan.RegionOfInterest(4, 4, 16, 16));
Sensor.setTimingBudget(LaserCan.TimingBudget.TIMING_BUDGET_33MS);
} catch (ConfigurationFailedException e) {
System.out.println("Configuration Failed! " + e);
Expand Down Expand Up @@ -59,4 +59,9 @@ public Trigger inIntake() {
})
.debounce(0.1);
}

public boolean booleanInIntake() {
double distance = getSensorDistance().in(Meters);
return distance > INTAKE_LOWER_LIMIT && distance < INTAKE_UPPER_LIMIT;
}
}
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/ArmPivot.java
Original file line number Diff line number Diff line change
Expand Up @@ -195,9 +195,9 @@ public void factoryDefaults() {
talonFXConfiguration.MotorOutput.NeutralMode = NeutralModeValue.Brake;

// enabling current limits
talonFXConfiguration.CurrentLimits.StatorCurrentLimit = 80; // starting low for testing
talonFXConfiguration.CurrentLimits.StatorCurrentLimit = 80;
talonFXConfiguration.CurrentLimits.StatorCurrentLimitEnable = true;
talonFXConfiguration.CurrentLimits.SupplyCurrentLimit = 40; // starting low for testing
talonFXConfiguration.CurrentLimits.SupplyCurrentLimit = 20;
talonFXConfiguration.CurrentLimits.SupplyCurrentLimitEnable = true;

// PID
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/ClimbPivot.java
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ public enum TargetPositions {
private final double CLIMB_HOLD_CLIMBED = -0.0705;
private final double CLIMB_IN_SPEED = -0.75;

private final double climbInKp = 30;
private final double climbInKp = 50;
private final double climbOutKp = 50;

// positions for relation between motor encoder and WCP encoder
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/GroundSpinny.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ public class GroundSpinny extends SubsystemBase {
public static final double GROUND_INTAKE_JITTER_SPEED = 1;
public static final double FUNNEL_INTAKE_SPEED = -2;
public static final double QUICK_HANDOFF_EXTAKE_SPEED = 1;
private static final double STATOR_CURRENT_STALL_THRESHOLD = 20;
private static final double STATOR_CURRENT_STALL_THRESHOLD = 50;

// TalonFX
private final TalonFX motor;
Expand Down
15 changes: 15 additions & 0 deletions src/main/java/frc/robot/subsystems/SuperStructure.java
Original file line number Diff line number Diff line change
Expand Up @@ -203,6 +203,21 @@ public Command groundIntake(BooleanSupplier retract) {
}
}

public Command holdGroundIntakeOut(BooleanSupplier retract) {
if (groundSpinny == null || groundArm == null) {
return Commands.none().withName("hold ground intake disabled");
}

return Commands.sequence(
Copy link

Choose a reason for hiding this comment

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

is Commands.sequence() needed here, since the only item in it is the Commands.parallel()?

Commands.parallel(
groundArm
.moveToPosition(GroundArm.GROUND_POSITION)
.andThen(groundArm.setVoltage(GroundArm.GROUND_HOLD_VOLTAGE))
.until(retract),
groundSpinny.setGroundIntakePower()))
.withName("Hold Ground Intake Out");
}

// This is the actual version in use. It moves the coral directly into the claw.
public Command quickGroundIntake(BooleanSupplier retract) { // thanks joseph
if (groundSpinny == null || groundArm == null || intakeSensor == null) {
Expand Down
7 changes: 7 additions & 0 deletions src/main/java/frc/robot/util/SoloScoringMode.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
package frc.robot.util;

public enum SoloScoringMode {
CORAL_IN_CLAW,
ALGAE_IN_CLAW,
NO_GAME_PIECE;
}