Skip to content

Commit

Permalink
p1 open house
Browse files Browse the repository at this point in the history
  • Loading branch information
AlexNunemacher committed Feb 22, 2025
1 parent 8c1a6a0 commit 67902cb
Show file tree
Hide file tree
Showing 4 changed files with 38 additions and 35 deletions.
63 changes: 33 additions & 30 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -93,12 +93,12 @@ public class RobotContainer {

private Supplier<ChassisSpeeds> driverVelocitySupplier;

private Trigger DRIVER_TRIGGER;
private Trigger DROP_TRIGGER;
private Trigger AUTO_ALIGNED;
private Trigger USING_AUTO_ALIGN;
private Trigger AUTO_DRIVER_TRIGGER;

private InternalButton normalRelease;
private InternalButton normalRelease = new InternalButton();

public RobotContainer() {
if (Robot.isReal()) {
Expand Down Expand Up @@ -209,13 +209,16 @@ private void configureBindings() {
return drivetrain.driveDriverRelative(driverVelocitySupplier.get());
}));

DRIVER_TRIGGER = rightDriveController.getTrigger();
DROP_TRIGGER = leftDriveController.getTrigger();

final Trigger EJECT_TRIGGER = rightDriveController.getTrigger();
final Trigger ALIGN_TRIGGER = rightDriveController.getBottomThumb();

USING_AUTO_ALIGN = new Trigger(() -> false);

AUTO_ALIGNED = new Trigger(() -> false);

AUTO_DRIVER_TRIGGER = (USING_AUTO_ALIGN.negate().or(AUTO_ALIGNED)).and(DRIVER_TRIGGER);
AUTO_DRIVER_TRIGGER = (USING_AUTO_ALIGN.negate().or(AUTO_ALIGNED)).and(DROP_TRIGGER);

// drive.withVelocityX(-leftDriveController.getYAxis().get() *
// GlobalConstants.MAX_TRANSLATIONAL_SPEED) // Drive forward with negative Y
Expand Down Expand Up @@ -396,24 +399,24 @@ private void configureBindings() {
ARMWRIST.and(operatorController.getX()).whileTrue(wristSubsystem.turnWristLeft());
ARMWRIST.and(operatorController.getB()).whileTrue(wristSubsystem.turnWristRight());

CORAL.and(operatorController.getY())
.onTrue(stateManager.moveToPosition(Position.L4Prep))
.onFalse(stateManager.moveToPosition(Position.L4));
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.getY())
// .onTrue(stateManager.moveToPosition(Position.L4Prep))
// .onFalse(stateManager.moveToPosition(Position.L4));
// 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));

operatorController.getLeftTrigger().onTrue(stateManager.moveToPosition(Position.Start));
operatorController.getLeftTrigger().onTrue(stateManager.moveToPosition(Position.Climb));

bindPlaceSeq(operatorController.getY(), Position.L4Prep, Position.L4, 0.1);
bindPlaceSeq(CORAL.and(operatorController.getY()), Position.L4Prep, Position.L4, 0.1);

bindPlaceSeq(operatorController.getX(), Position.L3Prep, Position.L3, 0.1);
bindPlaceSeq(CORAL.and(operatorController.getX()), Position.L3Prep, Position.L3, 0.1);

bindPlaceSeq(operatorController.getB(), Position.L2Prep, Position.L2, 0.1);
bindPlaceSeq(CORAL.and(operatorController.getB()), Position.L2Prep, Position.L2, 0.1);

operatorController.getA().onTrue(stateManager.moveToPosition(Position.L1));

Expand All @@ -423,8 +426,10 @@ private void configureBindings() {
CORAL.and(operatorController.getDPadDown())
.onTrue(stateManager.moveToPosition(Position.Home));
CORAL.and(operatorController.getDPadUp())
.onTrue(stateManager.moveToPosition(Position.HandoffPrep))
.onFalse(stateManager.moveToPosition(Position.Handoff));
.onFalse(stateManager.moveToPosition(Position.HandoffPrep))
.onTrue(stateManager.moveToPosition(Position.Handoff));
CORAL.and(operatorController.getDPadUp()).whileTrue(gripperSubsystem.intakeSpinCoral());

CORAL.and(operatorController.getDPadLeft()).onTrue(chuteSubsystem.moveChuteUp());
CORAL.and(operatorController.getDPadRight()).onTrue(chuteSubsystem.moveChuteDown());

Expand All @@ -437,8 +442,8 @@ private void configureBindings() {
.onTrue(stateManager.moveToPosition(Position.GroundAlgae));
ALGAE.and(operatorController.getDPadDown())
.onTrue(stateManager.moveToPosition(Position.AlgaeHome));
ALGAE.and(operatorController.getDPadUp())
.onTrue(stateManager.moveToPosition(Position.Handoff));
// ALGAE.and(operatorController.getDPadUp())
// .onTrue(stateManager.moveToPosition(Position.Handoff));
ALGAE.and(operatorController.getDPadLeft())
.onTrue(stateManager.moveToPosition(Position.Quick34));
ALGAE.and(operatorController.getDPadRight())
Expand Down Expand Up @@ -471,14 +476,13 @@ private void configureBindings() {
.andThen(
Commands.waitUntil(
gripperSubsystem.HAS_PIECE))));
CORAL.and(rightDriveController.getRightThumb())
.whileTrue(gripperSubsystem.ejectSpinCoral());
CORAL.and(EJECT_TRIGGER).whileTrue(gripperSubsystem.ejectSpinCoral());

ALGAE.and(rightDriveController.getLeftThumb()).onTrue(gripperSubsystem.intakeSpinAlgae());
ALGAE.and(rightDriveController.getRightThumb())
ALGAE.and(EJECT_TRIGGER)
.and(stateManager.PROCESSOR)
.whileTrue(gripperSubsystem.slowEjectSpinAlgae());
ALGAE.and(rightDriveController.getRightThumb())
ALGAE.and(EJECT_TRIGGER)
.and(stateManager.PROCESSOR.negate())
.whileTrue(gripperSubsystem.ejectSpinAlgae());

Expand All @@ -492,19 +496,18 @@ private void configureBindings() {

stateManager
.LEFT_CORAL
.and(leftDriveController.getTrigger())
.and(ALIGN_TRIGGER)
.whileTrue(alignToReef(AligningConstants.leftOffset));

stateManager
.ALGAE
.and(leftDriveController.getTrigger())
.and(ALIGN_TRIGGER)
.whileTrue(alignToReef(AligningConstants.centerOffset));

stateManager
.RIGHT_CORAL
.and(leftDriveController.getTrigger())
.and(ALIGN_TRIGGER)
.whileTrue(alignToReef(AligningConstants.rightOffset));

// Technical Bindings

leftDriveController.getLeftBottomMiddle().onTrue(climberSubsystem.zeroClimberCommand());
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/constants/TunerConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,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(60.0);
private static final Current kSlipCurrent = Amps.of(102);

// 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 All @@ -80,7 +80,7 @@ public class TunerConstants {

// Theoretical free speed (m/s) at 12 V applied output;
// This needs to be tuned to your individual robot
public static final LinearVelocity kSpeedAt12Volts = MetersPerSecond.of(4.73);
public static final LinearVelocity kSpeedAt12Volts = MetersPerSecond.of(6.218);

// Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns;
// This may need to be tuned to your individual robot
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ public static enum Position {
AlgaeHome(100, 2.15, -1.58, ChuteUpNull),
AlgaeHomeNull(0.0, 0.0, 0.0, AlgaeHome, TRUE, FALSE),
// Climb(170, 0, 1.58, ChuteUpNull),
Processor(65, 1.58, -1.58, AlgaeHomeNull),
Processor(80, 1.58, -1.58, AlgaeHomeNull),

// IcecreamCoral(170, 0, 1.58, AlgaeHome),
// IcecreamAlgae(170, 0, 1.58, AlgaeHome),
Expand All @@ -182,6 +182,7 @@ public static enum Position {
StartPrepPrep(140, 0, 1.58, StartPrepPrepPrep),
StartPrep(140, 0, -1.58, StartPrepPrep),
Start(0, 0, -1.58, StartPrep),
Climb(10, 0, -1.58, StartPrep),
Tunable(170, 0, 1.58, CenterZoneNull, FALSE);

private double elevatorHeight;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -559,8 +559,7 @@ public void periodic() {
"Drive/setpointChassisSpeeds",
m_applyFieldSpeedsOrbit.getPreviousSetpoint().robotRelativeSpeeds());

ChassisSpeeds speedsPreview =
m_applyFieldSpeedsOrbit.getPreviousSetpoint().robotRelativeSpeeds();
ChassisSpeeds speedsPreview = getChassisSpeeds();

double currentSpeed =
Math.hypot(speedsPreview.vxMetersPerSecond, speedsPreview.vyMetersPerSecond);
Expand Down

0 comments on commit 67902cb

Please sign in to comment.