Skip to content

Commit 8b6bb38

Browse files
committed
LED handling for bloop shot.
1 parent 384127b commit 8b6bb38

File tree

3 files changed

+18
-16
lines changed

3 files changed

+18
-16
lines changed

src/main/java/frc/robot/Robot.java

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -64,6 +64,9 @@ public void robotInit() {
6464
Preferences.initDouble("BUR.Velocity", 1980.0);
6565
Preferences.initDouble("BUR.Angle", 73.25);
6666

67+
Preferences.initDouble("BLP.Velocity", 500.0);
68+
Preferences.initDouble("BLP.Angle", 60.0);
69+
6770
// Instantiate our RobotContainer. This will perform all our button bindings,
6871
// and put our
6972
// autonomous chooser on the dashboard.

src/main/java/frc/robot/shooter/commands/FlywheelController.java

Lines changed: 2 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,6 @@
1414

1515
public class FlywheelController extends CommandBase {
1616

17-
private final double kTolerance = 0.8;
1817
Shooter shooter;
1918
double lastPosition, lastTime, hoodAngle;
2019
double rpm;
@@ -23,8 +22,8 @@ public class FlywheelController extends CommandBase {
2322
private DCMotor flywheel = new DCMotor(0.002081897, 0, 0.317466);
2423
private PIDController flywheelController = new PIDController(0.02, 0, 0);
2524
// private PIDController flywheelController = new PIDController(0.05, 0, 0);
26-
private boolean closeToTarget = false;
27-
private double velocity = 0;
25+
boolean closeToTarget = false;
26+
double velocity = 0;
2827

2928
public FlywheelController(Shooter shooter, double rpm, double hoodAngle) {
3029
this.shooter = shooter;
@@ -70,19 +69,6 @@ void controller() {
7069
lastTime = time;
7170
}
7271

73-
@Override
74-
public void execute() {
75-
double targetDelta = rpm - velocity;
76-
77-
if ((Math.abs(targetDelta) < 20) && !closeToTarget) {
78-
closeToTarget = true;
79-
// Only do this if it is a preset shot
80-
if (this instanceof PresetFlywheelController) {
81-
Status.getInstance().fillLEDs();
82-
}
83-
}
84-
}
85-
8672
@Override
8773
public void end(boolean interrupted) {
8874
controller.stop();

src/main/java/frc/robot/shooter/commands/PresetFlywheelController.java

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22

33
import edu.wpi.first.wpilibj.Preferences;
44
import frc.robot.shooter.Shooter;
5+
import frc.robot.status.Status;
56
import frc.robot.vision.Limelight;
67

78
public class PresetFlywheelController extends FlywheelController {
@@ -45,4 +46,16 @@ public void initialize() {
4546
controller.startPeriodic(0.02);
4647
}
4748

49+
@Override
50+
public void execute() {
51+
double targetDelta = rpm - velocity;
52+
53+
if ((Math.abs(targetDelta) < 20) && !closeToTarget) {
54+
closeToTarget = true;
55+
if (!"BLP".equals(preset)) {
56+
Status.getInstance().fillLEDs();
57+
}
58+
}
59+
}
60+
4861
}

0 commit comments

Comments
 (0)