Skip to content

Commit

Permalink
Start more OOP approach to codriver controls
Browse files Browse the repository at this point in the history
  • Loading branch information
team6101 committed Feb 29, 2024
1 parent 55274bd commit 8e38da2
Show file tree
Hide file tree
Showing 7 changed files with 62 additions and 17 deletions.
5 changes: 4 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,9 @@ public class Constants {

/*SHOOTER CONFIG*/
/**the amount of time we let the wheels rev up when shooting in seconds */
public static final double REV_TIME = 1.0;
public static final double SHOOTER_FLYWHEEL_STARTUP_TIME = 1.0;
/*The amount of seconds that the feeder should wait before turning off after shooting */
public static final double FEEDER_MOTOR_SHUTOFF_TIME = 0;

/*CLIMB CONFIG */
public static final double CLIMB_EXTENDED_ENCODER_POSITION = 5;
Expand Down Expand Up @@ -60,4 +62,5 @@ public class Constants {
/* ROTATION PID CONSTANTS */

public static final double ROTATION_ERROR_DEGREES = 5.;
public static final double SHOOTING_VELOCITY = 4000;
}
11 changes: 0 additions & 11 deletions src/main/java/frc/robot/InputtedCoDriverControls.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@ public static void onEveryFrame() {
if (controller.getXButtonPressed()) {
shootIntoSpeaker();
}
doShooterIntake();
Robot.motors.getIntake().stopMotor();
if (controller.getYButton()) {
doFloorIntake();
Expand Down Expand Up @@ -55,16 +54,6 @@ private static void retractArms() {
Robot.getTeleopActionRunner().removeActionsOfType(ExtendArms.class);
}

private static void doShooterIntake() {
if (controller.getPOV() == 0) {
Robot.motors.getRightFlywheel().set(0.3);
Robot.motors.getLeftFlywheel().set(-0.3);
} else if (controller.getPOV() == 180) {
Robot.motors.getRightFlywheel().set(0);
Robot.motors.getLeftFlywheel().set(0);
}
}

private static void shootIntoSpeaker() {
Robot.getTeleopActionRunner().addActionToRun(new AutonShoot());
}
Expand Down
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/RobotComponents/Climber.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
package frc.robot.RobotComponents;

public class Climber {}
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/RobotComponents/Intake.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
package frc.robot.RobotComponents;

public class Intake {}
23 changes: 23 additions & 0 deletions src/main/java/frc/robot/RobotComponents/Shooter.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
package frc.robot.RobotComponents;

import frc.robot.Constants;
import frc.robot.Robot;
import frc.robot.auton.AutonShooterFeed;

public class Shooter {

public void startShooterMotors() {
Robot.motors.getLeftFlywheel().setVelocity(Constants.SHOOTING_VELOCITY);
Robot.motors.getRightFlywheel().setVelocity(Constants.SHOOTING_VELOCITY);
}

public void stopShooterMotors() {
Robot.motors.getLeftFlywheel().stopMotor();
Robot.motors.getRightFlywheel().stopMotor();
}

public void startFeedMotors() {
Robot.getTeleopActionRunner().removeActionsOfType(AutonShooterFeed.class);
Robot.getTeleopActionRunner().addActionToRun(new AutonShooterFeed());
}
}
8 changes: 3 additions & 5 deletions src/main/java/frc/robot/auton/AutonShoot.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,17 +14,15 @@ public boolean isDone() {
Robot.motors.getFeeder().set(0.2);
Robot.motors.getIntake().set(.2);
}
if (Timer.getFPGATimestamp() >= revFinishedTime + 1.0) {
return true;
}
return false;

return Timer.getFPGATimestamp() >= revFinishedTime + 1.0;
}

@Override
public void initiate() {
Robot.motors.getLeftFlywheel().set(1.0);
Robot.motors.getRightFlywheel().set(-1.0);
revFinishedTime = Timer.getFPGATimestamp() + Constants.REV_TIME;
revFinishedTime = Timer.getFPGATimestamp() + Constants.SHOOTER_FLYWHEEL_STARTUP_TIME;
}

@Override
Expand Down
26 changes: 26 additions & 0 deletions src/main/java/frc/robot/auton/AutonShooterFeed.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
package frc.robot.auton;

import edu.wpi.first.wpilibj.Timer;
import frc.robot.Constants;
import frc.robot.Robot;

public class AutonShooterFeed extends AutonAction {

private double revFinishedTime;

@Override
public boolean isDone() {
return Timer.getFPGATimestamp() > revFinishedTime;
}

@Override
public void initiate() {
Robot.motors.getFeeder().set(0.75);
revFinishedTime = Timer.getFPGATimestamp() + Constants.FEEDER_MOTOR_SHUTOFF_TIME;
}

@Override
public void shutdown() {
Robot.motors.getFeeder().stopMotor();
}
}

0 comments on commit 8e38da2

Please sign in to comment.