Skip to content

Commit

Permalink
Added ZeroShooterArm command
Browse files Browse the repository at this point in the history
  • Loading branch information
Primo4586 committed Mar 2, 2024
1 parent 5aeab6b commit f76231f
Show file tree
Hide file tree
Showing 3 changed files with 55 additions and 3 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.basicCommands.ShooterArmCommands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.shooterArm.ShooterArmSubsystem;
import frc.robot.subsystems.shooterArm.ShooterArmConstants.shooterArmConstants;

public class ZeroShooterArm extends Command {
/** Creates a new ZeroShooterArm. */
private final ShooterArmSubsystem shooterArm = ShooterArmSubsystem.getInstance();
private boolean zerodOut = false;
private boolean canReset = false;

public ZeroShooterArm() {
addRequirements(shooterArm);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
canReset = !shooterArm.getSwitch();
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(!canReset){
shooterArm.setSpeed(-shooterArmConstants.RESET_SPEED);
}

if(!shooterArm.getSwitch()){
shooterArm.setSpeed(shooterArmConstants.RESET_SPEED);
canReset = true;
}
else if(canReset){
zerodOut = true;
}
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
shooterArm.setPosition(shooterArmConstants.RESET_POSE);
shooterArm.setSpeed(0);
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return zerodOut;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
public class AutoAlignToSpeaker extends Command {
/** Creates a new TurnToDegree. */
SwerveSubsystem swerve = SwerveSubsystem.getInstance();
TakeFeedSubsystem feeder = TakeFeedSubsystem.getInstance();

private Vision vision = Vision.getInstance();
double angleFromTarget = vision.GetAngleFromTarget().getDegrees();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,14 +13,12 @@
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.FieldConstants.Speaker;
import frc.robot.subsystems.swerve.SwerveSubsystem;
import frc.robot.subsystems.takeFeed.TakeFeedSubsystem;
import frc.util.AllianceFlipUtil;
import frc.util.vision.Vision;

public class TeleopAlignToSpeaker extends Command {
/** Creates a new TurnToDegree. */
SwerveSubsystem swerve = SwerveSubsystem.getInstance();
TakeFeedSubsystem feeder = TakeFeedSubsystem.getInstance();

private Vision vision = Vision.getInstance();
double angleFromTarget = vision.GetAngleFromTarget().getDegrees();
Expand Down

0 comments on commit f76231f

Please sign in to comment.