Skip to content

Commit

Permalink
Thursday Changes
Browse files Browse the repository at this point in the history
  • Loading branch information
AlexNunemacher committed Feb 21, 2025
1 parent 6d7a24c commit acccd66
Show file tree
Hide file tree
Showing 7 changed files with 62 additions and 50 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Auto.java
Original file line number Diff line number Diff line change
Expand Up @@ -229,7 +229,7 @@ public int getTagByTeam() {

public enum ArmHeight {
Home(Position.Home, Position.Home),
L1(Position.L1, Position.L1Prep),
L1(Position.L1, Position.L1),
L2(Position.L2, Position.L2Prep),
L3(Position.L3, Position.L3Prep),
L4(Position.L4, Position.L4Prep),
Expand Down
33 changes: 19 additions & 14 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@
import frc.robot.subsystems.chute.ChuteIONeo550;
import frc.robot.subsystems.chute.ChuteIOSim;
import frc.robot.subsystems.chute.ChuteSubsystem;
import frc.robot.subsystems.climber.ClimberHeadIOSim;
import frc.robot.subsystems.climber.ClimberIOSim;
import frc.robot.subsystems.climber.ClimberHeadIONeo550;
import frc.robot.subsystems.climber.ClimberIOTalonFX;
import frc.robot.subsystems.climber.ClimberSubsystem;
import frc.robot.subsystems.elevator.ElevatorIOSim;
import frc.robot.subsystems.elevator.ElevatorIOTalonFX;
Expand Down Expand Up @@ -117,8 +117,8 @@ public RobotContainer() {
wristSubsystem = new WristSubsystem(new WristIONeo550()); // new WristIONeo550());
climberSubsystem =
new ClimberSubsystem(
new ClimberIOSim(),
new ClimberHeadIOSim()); // new ClimberIOTalonFX(), new
new ClimberIOTalonFX(),
new ClimberHeadIONeo550()); // new ClimberIOTalonFX(), new
// ClimberHeadIONeo550());
lights = new LightsSubsystem();
chuteSubsystem = new ChuteSubsystem(new ChuteIONeo550()); // new ChuteIONeo550());
Expand Down Expand Up @@ -146,7 +146,8 @@ public RobotContainer() {
armSubsystem = new ArmSubsystem(new ArmPivotIOSim());
wristSubsystem = new WristSubsystem(new WristIOSim());
intakeSubsystem = new IntakeSubsystem(new IntakeRollerIOSim(), new FlipperIOSim());
climberSubsystem = new ClimberSubsystem(new ClimberIOSim(), new ClimberHeadIOSim());
climberSubsystem =
new ClimberSubsystem(new ClimberIOTalonFX(), new ClimberHeadIONeo550());
lights = new LightsSubsystem();
chuteSubsystem = new ChuteSubsystem(new ChuteIOSim());
}
Expand Down Expand Up @@ -381,8 +382,12 @@ private void configureBindings() {
CORAL.and(operatorController.getY())
.onTrue(stateManager.moveToPosition(Position.L4Prep))
.onFalse(stateManager.moveToPosition(Position.L4));
CORAL.and(operatorController.getX()).onTrue(stateManager.moveToPosition(Position.L3));
CORAL.and(operatorController.getB()).onTrue(stateManager.moveToPosition(Position.L2));
CORAL.and(operatorController.getX())
.onTrue(stateManager.moveToPosition(Position.L3Prep))
.onFalse(stateManager.moveToPosition(Position.L3));
CORAL.and(operatorController.getB())
.onTrue(stateManager.moveToPosition(Position.L2Prep))
.onFalse(stateManager.moveToPosition(Position.L2));
CORAL.and(operatorController.getA()).onTrue(stateManager.moveToPosition(Position.L1));
CORAL.and(operatorController.getStart())
.onTrue(stateManager.moveToPosition(Position.Source));
Expand All @@ -395,30 +400,30 @@ private void configureBindings() {
CORAL.and(operatorController.getDPadLeft()).onTrue(chuteSubsystem.moveChuteUp());
CORAL.and(operatorController.getDPadRight()).onTrue(chuteSubsystem.moveChuteDown());

ALGAE.and(operatorController.getY()).onTrue(stateManager.moveToPosition(Position.NetAlgae));
// ALGAE.and(operatorController.getY()).onTrue(stateManager.moveToPosition(Position.NetAlgae));
ALGAE.and(operatorController.getX()).onTrue(stateManager.moveToPosition(Position.L3Algae));
ALGAE.and(operatorController.getB()).onTrue(stateManager.moveToPosition(Position.L2Algae));
ALGAE.and(operatorController.getA())
.onTrue(stateManager.moveToPosition(Position.Processor));
ALGAE.and(operatorController.getStart())
.onTrue(stateManager.moveToPosition(Position.Processor));
.onTrue(stateManager.moveToPosition(Position.GroundAlgae));
ALGAE.and(operatorController.getDPadDown())
.onTrue(stateManager.moveToPosition(Position.Home));
.onTrue(stateManager.moveToPosition(Position.AlgaeHome));
ALGAE.and(operatorController.getDPadUp())
.onTrue(stateManager.moveToPosition(Position.Handoff));
ALGAE.and(operatorController.getDPadLeft())
.onTrue(stateManager.moveToPosition(Position.Quick34));
ALGAE.and(operatorController.getDPadRight())
.onTrue(stateManager.moveToPosition(Position.Quick23));

operatorController.getBack().onTrue(wristSubsystem.flipWristPosition());
// operatorController.getBack().onTrue(wristSubsystem.flipWristPosition());

// Driver Align Bindings, for a different/later day
// CORAL.and(leftDriveController.getTrigger()).whileTrue(alignToReef(9, 0));

// Climb Bindings
leftDriveController.getLeftThumb().whileTrue(climberSubsystem.downPosition());
leftDriveController.getRightThumb().whileTrue(climberSubsystem.upPosition());
leftDriveController.getLeftThumb().whileTrue(climberSubsystem.moveClimberDownVoltage());
leftDriveController.getRightThumb().whileTrue(climberSubsystem.moveClimberUpVoltage());
leftDriveController.getBottomThumb().whileTrue(climberSubsystem.intakeCage());

// leftDriveController.getBottomThumb().whileTrue(alignToPiece());
Expand Down Expand Up @@ -511,7 +516,7 @@ private void configureBindings() {
SmartDashboard.putData(stateManager);
}

leftDriveController.getRightBottomLeft().onTrue(elevatorSubsystem.zeroElevatorCommand());
// leftDriveController.getRightBottomLeft().onTrue(elevatorSubsystem.zeroElevatorCommand());
}

private double deadband(double value, double deadband) {
Expand Down
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/constants/ClimberConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,9 @@ public class ClimberConstants {

public static final int CLIMBER_HEAD_ID = 40;

public static final String CANbus = "CANivore";
public static final String canbus = "rio";

public static final String WinchCanbus = "CANivore";

public static final double ClimberHeadCurrent = 30;
}
Original file line number Diff line number Diff line change
Expand Up @@ -144,30 +144,35 @@ public static enum Position {
ChuteUpNull(0, 0, 0, ChuteUp, TRUE, FALSE),
HandoffPrep(165, -0.5, 1.58, ChuteDownNull),
Handoff(132, -0.5, 1.58, HandoffPrep),
PointUp(165, 2.05, 1.58, CenterZoneNull),
PointUp(165, 2.15, 1.58, CenterZoneNull),
AlgaePointUp(165, 2.15, -1.58, ChuteUpNull),
UpZoneNull(0, 0, 0, PointUp, TRUE, FALSE),
L1Prep(298.5, 2.05, -1.58, ChuteUpNull),
L1(298.5, 2.05, -1.58, L1Prep),
L2Prep(298.5, 2.05, -1.58, UpZoneNull),
L2(298.5, 2.05, -1.58, L2Prep),
L3Prep(298.5, 2.05, -1.58, UpZoneNull),
L3(298.5, 2.05, -1.58, L3Prep),
L4Prep(298.5, 2.15, -1.58, UpZoneNull),
L4(298.5, 1.7, -1.58, L4Prep),
Quick34(298.5, 2.05, -1.58, UpZoneNull),
Quick23(298.5, 2.05, -1.58, UpZoneNull),
L2AlgaePrep(298.5, 2.05, -1.58, UpZoneNull),
L2Algae(298.5, 2.05, -1.58, L2AlgaePrep),
L3AlgaePrep(298.5, 2.05, -1.58, UpZoneNull),
L3Algae(298.5, 2.05, -1.58, L3AlgaePrep),
NetAlgaePrep(298.5, 2.05, -1.58, UpZoneNull),
NetAlgae(298.5, 2.05, -1.58, NetAlgaePrep),
Source(165, 2.05, 0, PointUp),
AlgaeHome(165, 0, 1.58, CenterZoneNull),
// L1Prep(297, 2.15, -1.58, ChuteUpNull),
L1(130, 0.9, 0, UpZoneNull),
L2Prep(120, 2.15, -1.58, UpZoneNull),
L2(90, 2.15, -1.58, L2Prep),
L3Prep(190, 2.15, -1.58, UpZoneNull),
L3(170, 2.15, -1.58, L3Prep),
L4Prep(297, 2.15, -1.58, UpZoneNull),
L4(297, 1.7, -1.58, L4Prep),
Quick34(250, 0.7, 0, UpZoneNull),
Quick23(150, 0.7, 0, UpZoneNull),
// L2AlgaePrep(297, 2.15, -1.58, UpZoneNull),
L2Algae(170, 1.2, -1.58, UpZoneNull),
// L3AlgaePrep(297, 2.15, -1.58, UpZoneNull),
L3Algae(250, 1.2, -1.58, UpZoneNull),
// NetAlgaePrep(297, 2.15, -1.58, UpZoneNull),
// NetAlgae(297, 2.15, -1.58, NetAlgaePrep),
Source(130, 2.15, 0, PointUp),
AlgaeHome(100, 2.15, -1.58, AlgaePointUp),
AlgaeHomeNull(0.0, 0.0, 0.0, AlgaeHome, TRUE, FALSE),
Climb(165, 0, 1.58, ChuteUpNull),
Processor(165, 0, 1.58, ChuteUpNull),
IcecreamCoral(165, 0, 1.58, ChuteUpNull),
IcecreamAlgae(165, 0, 1.58, ChuteUpNull),
Processor(65, 1.58, -1.58, AlgaeHomeNull),

// IcecreamCoral(165, 0, 1.58, AlgaeHome),
// IcecreamAlgae(165, 0, 1.58, AlgaeHome),
GroundAlgaePrep(65, 1.58, 1.58, AlgaeHomeNull),
GroundAlgae(20, 1.58, 1.58, GroundAlgaePrep),
StartPrep(140, 0, -1.58, ChuteUpNull),
Start(0, 0, -1.58, StartPrep),
Tunable(165, 0, 1.58, CenterZoneNull, FALSE);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
public class ClimberIOTalonFX implements ClimberIO {
// TBD: Hardcode IDs or add support to make changeable in method
private final TalonFX climbermotor =
new TalonFX(ClimberConstants.CLIMBER_ID, ClimberConstants.CANbus);
new TalonFX(ClimberConstants.CLIMBER_ID, ClimberConstants.WinchCanbus);
private final MotionMagicVoltage motionMagicVoltage = new MotionMagicVoltage(0);

public ClimberIOTalonFX() {
Expand All @@ -23,10 +23,10 @@ public ClimberIOTalonFX() {

SoftwareLimitSwitchConfigs softwareLimitSwitchConfigs =
new SoftwareLimitSwitchConfigs()
.withForwardSoftLimitEnable(true)
.withForwardSoftLimitEnable(false)
.withForwardSoftLimitThreshold(ClimberConstants.upperLimit)
.withReverseSoftLimitThreshold(ClimberConstants.lowerLimit)
.withReverseSoftLimitEnable(true);
.withReverseSoftLimitEnable(false);

talonConfig.apply(
new TalonFXConfiguration()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,7 @@ public Command stopClimber() {
return run(
() -> {
climberIO.setVoltage(0);
climberHeadIO.setVoltage(0);
});
}

Expand All @@ -120,14 +121,14 @@ public Command setHeadVoltage(double voltage) {
public Command intakeCage() {
return run(
() -> {
climberHeadIO.setVoltage(12);
climberHeadIO.setVoltage(-12);
});
}

public Command ejectCage() {
return run(
() -> {
climberHeadIO.setVoltage(-12); // +- is a guess
climberHeadIO.setVoltage(12); // +- is a guess
});
}
}
13 changes: 6 additions & 7 deletions src/main/java/frc/robot/subsystems/wrist/WristSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.WristConstants;
import java.util.function.DoubleSupplier;
Expand Down Expand Up @@ -73,12 +72,12 @@ public Command setPosition(double position) {
.andThen(followReferenceThrubore());
}

public Command flipWristPosition() {
return Commands.runOnce(
() -> {
isWristFlipped = !isWristFlipped;
});
}
// public Command flipWristPosition() {
// return Commands.runOnce(
// () -> {
// isWristFlipped = !isWristFlipped;
// });
// }

private Command followReferenceThrubore() {
return run(
Expand Down

0 comments on commit acccd66

Please sign in to comment.