Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

cleaned up bindings, and made every binding how we want for competito… #60

Merged
merged 5 commits into from
Feb 13, 2024
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
49 changes: 24 additions & 25 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -195,8 +195,6 @@ private void indexInit() {
private void indexCommandInst() {
defaulNoteHandlingCommand = new IndexCommand(indexer, driverController::getR2Button, driverController::getL2Button, shooter, intake, driveTrain, angleShooterSubsystem);
indexer.setDefaultCommand(defaulNoteHandlingCommand);
shooter.setDefaultCommand(defaulNoteHandlingCommand);
intake.setDefaultCommand(defaulNoteHandlingCommand);
}

private void autoInit() {
Expand All @@ -223,44 +221,45 @@ private void lightsInst() {
* joysticks}.
*/
private void configureBindings() {
// Schedule `ExampleCommand` when `exampleCondition` changes to `true`
new Trigger(m_exampleSubsystem::exampleCondition)
.onTrue(new ExampleCommand(m_exampleSubsystem));

// new Trigger(driverController::getCrossButton).onTrue(new autoAimParallel(driveTrain/*, shooter*/));
new Trigger(driverController::getPSButton).onTrue(new InstantCommand(driveTrain::zeroGyroscope));
SmartDashboard.putData(new RotateRobot(driveTrain, driveTrain::calculateSpeakerAngle));
new Trigger(driverController::getTriangleButton).onTrue(new GoToClimbSpot(driveTrain, climbSpotChooser));
new Trigger(driverController::getCrossButton).whileTrue(new GoToAmp(driveTrain));
new Trigger(driverController::getR1Button).whileTrue(new AimRobotMoving(
new Trigger(driverController::getCircleButton).whileTrue(new GoToAmp(driveTrain));
new Trigger(driverController::getL2Button).whileTrue(new AimRobotMoving(
driveTrain,
() -> modifyAxis(-driverController.getRawAxis(Z_AXIS), DEADBAND_NORMAL),
() -> modifyAxis(-driverController.getRawAxis(Y_AXIS), DEADBAND_NORMAL),
() -> modifyAxis(-driverController.getRawAxis(X_AXIS), DEADBAND_NORMAL),
driverController::getR1Button));

new Trigger(driverController::getCircleButton).onTrue(new CollectNote(driveTrain, limelight));
new Trigger(driverController::getTouchpadPressed).onTrue(new InstantCommand(driveTrain::stop, driveTrain));
driverController::getL2Button));

new Trigger(driverController::getR1Button).onTrue(new CollectNote(driveTrain, limelight));
if(shooterExists) {
new Trigger(operatorController::getCircleButton).onTrue(new ManualShoot(shooter));
AngleShooter shooterUpCommand = new AngleShooter(angleShooterSubsystem, () -> Constants.ShooterConstants.shooterup);
new Trigger(driverController::getL1Button).onTrue(shooterUpCommand);
new Trigger(()->driverController.getPOV() == 180).whileTrue(shooterUpCommand);
SmartDashboard.putData("Manual Angle Shooter Up", shooterUpCommand);
}
if(indexerExists) {
new Trigger(driverController::getL1Button).whileTrue(new ManualShoot(indexer));
}
if(climberExists) {
new Trigger(operatorController::getCrossButton).onTrue(new AutoClimb(climber)).onFalse(new InstantCommand(()-> climber.climberStop()));
new Trigger(operatorController::getTriangleButton).onTrue(new InstantCommand(()-> climber.climberGo(ClimberConstants.CLIMBER_SPEED_UP))).onFalse(new InstantCommand(()-> climber.climberStop()));
new Trigger(operatorController::getSquareButton).onTrue(new ClimberPullDown(climber));
new Trigger(driverController::getCrossButton).onTrue(new AutoClimb(climber)).onFalse(new InstantCommand(()-> climber.climberStop()));
new Trigger(driverController::getTriangleButton).onTrue(new InstantCommand(()-> climber.climberGo(ClimberConstants.CLIMBER_SPEED_UP))).onFalse(new InstantCommand(()-> climber.climberStop()));
new Trigger(driverController::getSquareButton).whileTrue(new ClimberPullDown(climber));
}
SmartDashboard.putData("set offsets", new InstantCommand(driveTrain::setEncoderOffsets));
SmartDashboard.putData(new InstantCommand(driveTrain::forceUpdateOdometryWithVision));

// //Intake bindings
// new Trigger(operatorController::getL1Button).onTrue(new IntakeCommand(intake, iDirection.INTAKE));
// new Trigger(operatorController::getL2Button).onTrue(new IntakeCommand(intake, iDirection.OUTAKE));
// new Trigger(operatorController::getR2Button).onTrue(new IntakeCommand(intake, iDirection.COAST));
//for testing Rotate Robot command
/* bindings:
* L2: aim at speaker and rev up shooter to max (hold)
* L1: manually feed shooter (hold)
* R2: shoot if everything is lined up (hold)
* R1: automatically pick up note (press)
* Circle: lineup with the amp (hold)
* D-Pad down: move shooter up manually (hold)
* D-pad right: aim shooter at amp (hold)
* Triangle: move climber up (hold)
* Cross: auto-climb down (hold)
* Square: manually pull down with climber (hold)
*
*/
};


Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/AimShooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ public void initialize() {

@Override
public void execute() {
if (!(aimAtAmpSupplier.getAsDouble() == 0)) {
if (!(aimAtAmpSupplier.getAsDouble() == 90)) {
double desiredShooterAngleSpeed = angleShooterSubsystem.calculateSpeakerAngleDifference() * ShooterConstants.AUTO_AIM_SHOOTER_kP;
angleShooterSubsystem.pitchShooter(desiredShooterAngleSpeed);
} else {
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/IndexCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ public void execute() {
if(revUpSupplier.getAsBoolean()) {
shooter.shootThing(1);
} else {
shooter.shootThing(0.3);
shooter.shootThing(ShooterConstants.SHOOTER_AMP_POWER);
}
}
if (shootIfReadySupplier.getAsBoolean()) {
Expand Down
14 changes: 7 additions & 7 deletions src/main/java/frc/robot/commands/ManualShoot.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,16 @@

package frc.robot.commands;
import frc.robot.settings.Constants.ShooterConstants;
import frc.robot.subsystems.ShooterSubsystem;
import frc.robot.subsystems.IndexerSubsystem;
import edu.wpi.first.wpilibj2.command.Command;

public class ManualShoot extends Command {
public ShooterSubsystem shooter;
private IndexerSubsystem indexer;
/** Creates a new ManualShoot. */
public ManualShoot(ShooterSubsystem shooter) {
public ManualShoot(IndexerSubsystem indexer) {
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(shooter);
this.shooter = shooter;
addRequirements(indexer);
this.indexer = indexer;
}

// Called when the command is initially scheduled.
Expand All @@ -23,13 +23,13 @@ public void initialize() {}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
shooter.shootThing(ShooterConstants.SHOOTER_MOTOR_POWER);
indexer.on();
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
shooter.turnOff();
indexer.off();
}

// Returns true when the command should end.
Expand Down
1 change: 1 addition & 0 deletions src/main/java/frc/robot/settings/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -258,6 +258,7 @@ public static final class ShooterConstants{
public static final int SHOOTER_L_MOTORID = 2491;
public static final int PITCH_MOTOR_ID = 2491;
public static final double SHOOTER_MOTOR_POWER = 1;
public static final double SHOOTER_AMP_POWER = 0.3;
public static final double SHOOTING_SPEED_MPS = 10;
public static final double RUNNING_VELOCITY_RPS = 2491;
public static final double ALLOWED_ERROR = 1;
Expand Down
Loading