Skip to content
Merged
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
179 changes: 98 additions & 81 deletions src/main/deploy/choreo/DepotAuto.traj

Large diffs are not rendered by default.

183 changes: 183 additions & 0 deletions src/main/deploy/choreo/OutpostGroundPreload.traj

Large diffs are not rendered by default.

260 changes: 260 additions & 0 deletions src/main/deploy/choreo/OutpostGroundPreload_copy1.traj

Large diffs are not rendered by default.

443 changes: 222 additions & 221 deletions src/main/deploy/choreo/RushToCenterUnoDip.traj

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ public Robot() {
case REAL:
// Running on a real robot, log to a USB stick ("/U/logs")
Logger.addDataReceiver(new WPILOGWriter());
// Logger.addDataReceiver(new NT4Publisher());
Logger.addDataReceiver(new NT4Publisher());
break;

case SIM:
Expand Down
12 changes: 4 additions & 8 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -397,14 +397,10 @@ private void configureButtonBindings() {
.withName("ToggleIntakeDeploy"));

// X Button: hold to spin flywheel at manualFlywheelSpeed (tuning, Choreographer off)
/*controller
.x()
.whileTrue(
Commands.parallel(
flywheel.runFixedCommand(manualFlywheelSpeed).withName("TuneFlywheelSpin"),
kicker.runCommand())
.withName("TuneFlywheelAndKicker"))
.onFalse(Commands.parallel(flywheel.stopCommand(), kicker.stopCommand()));*/
controller
.x()
.onTrue(choreographer.setGoalCommand(Choreographer.Goal.REVERSE_INDEXER))
.onFalse(choreographer.setGoalCommand(Choreographer.Goal.IDLE));

// Y Button: hold to move hood to manualHoodAngle (tuning, Choreographer off)
controller
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/generated/TunerConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ public class TunerConstants {

// 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(100);
private static final Current kSlipCurrent = Amps.of(80);

// 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 Expand Up @@ -97,8 +97,8 @@ public class TunerConstants {
private static final int kPigeonId = 13;

// These are only used for simulation
private static final MomentOfInertia kSteerInertia = KilogramSquareMeters.of(0.01);
private static final MomentOfInertia kDriveInertia = KilogramSquareMeters.of(0.01);
private static final MomentOfInertia kSteerInertia = KilogramSquareMeters.of(0.004);
private static final MomentOfInertia kDriveInertia = KilogramSquareMeters.of(0.025);
// Simulated voltage necessary to overcome friction
private static final Voltage kSteerFrictionVoltage = Volts.of(0.2);
private static final Voltage kDriveFrictionVoltage = Volts.of(0.2);
Expand Down
16 changes: 14 additions & 2 deletions src/main/java/frc/robot/subsystems/Choreographer.java
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,8 @@ public enum Goal {
INTAKE,
SCORE_HUB,
CLIMB_EXTEND,
CLIMB_RETRACT
CLIMB_RETRACT,
REVERSE_INDEXER
}

public enum State {
Expand All @@ -45,7 +46,8 @@ public enum State {
WAITING_FOR_ALIGNMENT,
SHOOTING,
CLIMB_EXTENDING,
CLIMB_RETRACTING
CLIMB_RETRACTING,
REVERSING_INDEXER
}

@Getter
Expand Down Expand Up @@ -119,6 +121,7 @@ public void periodic() {
case SCORE_HUB -> handleScoreHub();
case CLIMB_EXTEND -> handleClimb(State.CLIMB_EXTENDING);
case CLIMB_RETRACT -> handleClimb(State.CLIMB_RETRACTING);
case REVERSE_INDEXER -> handleReverseIndexer();
}

logOutputs();
Expand All @@ -132,6 +135,15 @@ private void handleIdle() {
currentState = State.IDLE;
}

private void handleReverseIndexer() {
flywheel.stop();
hood.stow();
indexer.runReversed();
kicker.stop();

currentState = State.REVERSING_INDEXER;
}

private void handleIntake() {
flywheel.stop();
hood.stow();
Expand Down
9 changes: 9 additions & 0 deletions src/main/java/frc/robot/subsystems/indexer/Indexer.java
Original file line number Diff line number Diff line change
Expand Up @@ -163,6 +163,11 @@ public void run() {
running = true;
}

public void runReversed() {
running = true;
reversing = true;
}

/** Run the indexer at a custom voltage (bypasses stall detection). */
public void runVolts(double volts) {
running = true;
Expand All @@ -183,6 +188,10 @@ public Command runCommand() {
return runEnd(this::run, this::stop).withName("Indexer.run");
}

public Command runReversedCommand() {
return runEnd(this::runReversed, this::stop).withName("Indexer.runReversed");
}

/** Command to stop the indexer. */
public Command stopCommand() {
return runOnce(this::stop).withName("Indexer.stop");
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/intake/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ public class Intake extends FullSubsystem {
private static final LoggedTunableNumber toleranceDeg =
new LoggedTunableNumber("IntakePivot/ToleranceDeg");
private static final LoggedTunableNumber runVolts =
new LoggedTunableNumber("IntakeRollers/RunVolts", 5.5);
new LoggedTunableNumber("IntakeRollers/RunVolts", 7.25);
private static final LoggedTunableNumber homingRollerReverseVolts =
new LoggedTunableNumber("Intake/Homing/RollerReverseVolts", -2.0);
private static final LoggedTunableNumber homingPulseOnSec =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,7 @@ public static record LaunchPreset(

static {
minDistance = 1.969;
maxDistance = 5;
maxDistance = 6;
phaseDelay = 0.03;
passingMinDistance = 5.4;
passingMaxDistance = 17.16;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ public enum ControlMode {
static {
switch (Constants.getMode()) {
case REAL, REPLAY -> {
voltageKP.initDefault(0.1);
voltageKP.initDefault(.7);
voltageKD.initDefault(0.0);
voltageKS.initDefault(0.23013);
voltageKV.initDefault(0.12021);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,12 +63,12 @@ public FlywheelIOTalonFX() {
config.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;
config.MotorOutput.NeutralMode = NeutralModeValue.Coast;
config.Feedback.SensorToMechanismRatio = 1.0;
config.CurrentLimits.SupplyCurrentLimit = 80.0;
config.CurrentLimits.SupplyCurrentLimit = 45.0;
config.CurrentLimits.SupplyCurrentLimitEnable = true;

var followerConfig = new TalonFXConfiguration();
followerConfig.MotorOutput.NeutralMode = NeutralModeValue.Coast;
followerConfig.CurrentLimits.SupplyCurrentLimit = 80.0;
followerConfig.CurrentLimits.SupplyCurrentLimit = 45.0;
followerConfig.CurrentLimits.SupplyCurrentLimitEnable = true;

PhoenixUtil.tryUntilOk(5, () -> talon.getConfigurator().apply(config));
Expand Down
Loading