Skip to content

Commit

Permalink
changed parameters for AimShooter and deleted unused variables
Browse files Browse the repository at this point in the history
  • Loading branch information
trixydevs committed Feb 2, 2024
1 parent ba4d296 commit 5512db9
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 7 deletions.
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,7 @@ public class RobotContainer {
private Pigeon2 pigeon;
private IndexCommand defaulNoteHandlingCommand;
private IndexerSubsystem indexer;
private AimShooter defaultShooterAngleCommand;
private SendableChooser<String> climbSpotChooser;
private SendableChooser<Command> autoChooser;
// Replace with CommandPS4Controller or CommandJoystick if needed
Expand Down Expand Up @@ -170,7 +171,8 @@ private void shooterInst() {
shooter = new ShooterSubsystem(ShooterConstants.SHOOTER_MOTOR_POWER);
shooter.setDefaultCommand(defaulNoteHandlingCommand);
angleShooterSubsystem = new AngleShooterSubsystem();
angleShooterSubsystem.setDefaultCommand(new AimShooter(angleShooterSubsystem, ()-> (operatorController.getPOV() == 0)));
defaultShooterAngleCommand = new AimShooter(angleShooterSubsystem, operatorController::getPOV);
angleShooterSubsystem.setDefaultCommand(defaultShooterAngleCommand);
}
private void intakeInst() {
intake = new IntakeSubsystem();
Expand Down
9 changes: 5 additions & 4 deletions src/main/java/frc/robot/commands/AimShooter.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
package frc.robot.commands;

import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.settings.Constants.Field;
Expand All @@ -9,11 +10,11 @@

public class AimShooter extends Command {
AngleShooterSubsystem angleShooterSubsystem;
BooleanSupplier aimAtAmp;
DoubleSupplier aimAtAmpSupplier;

public AimShooter(AngleShooterSubsystem angleShooterSubsystem, BooleanSupplier aimAtAmp) {
public AimShooter(AngleShooterSubsystem angleShooterSubsystem, DoubleSupplier aimAtAmp) {
this.angleShooterSubsystem = angleShooterSubsystem;
this.aimAtAmp = aimAtAmp;
this.aimAtAmpSupplier = aimAtAmp;
}

@Override
Expand All @@ -23,7 +24,7 @@ public void initialize() {

@Override
public void execute() {
if (!aimAtAmp.getAsBoolean()) {
if (!(aimAtAmpSupplier.getAsDouble() == 0)) {
double desiredShooterAngleSpeed = angleShooterSubsystem.calculateSpeakerAngleDifference() * ShooterConstants.AUTO_AIM_SHOOTER_kP;
angleShooterSubsystem.pitchShooter(desiredShooterAngleSpeed);
} else {
Expand Down
1 change: 0 additions & 1 deletion src/main/java/frc/robot/commands/AngleShooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@ public AngleShooter(AngleShooterSubsystem shooter, DoubleSupplier desiredShooter
// Use addRequirements() here to declare subsystem dependencies.\
m_shooter = shooter;
this.desiredShooterAngleSupplier = desiredShooterAngleSupplier;
this.desiredShooterAngle = desiredShooterAngle;
addRequirements(shooter);
}

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 @@ -66,7 +66,7 @@ public void execute() {
}
if (shootIfReadySupplier.getAsBoolean()) {
if((angleShooterSubsytem.calculateSpeakerAngleDifference()<ShooterConstants.ALLOWED_ERROR)
&& (drivetrain.getSpeakerAngleDifference())<DriveConstants.ALLOWED_ERROR
&& drivetrain.getSpeakerAngleDifference()<DriveConstants.ALLOWED_ERROR
&& Math.abs(shooter.getError())<ShooterConstants.ALLOWED_SPEED_ERROR) {
m_Indexer.on();
} else {
Expand Down

0 comments on commit 5512db9

Please sign in to comment.