Skip to content

Commit 1def486

Browse files
shooter
1 parent 5d1e933 commit 1def486

File tree

1 file changed

+5
-8
lines changed

1 file changed

+5
-8
lines changed

components/shooter.py

Lines changed: 5 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
import math
22

33
import wpilib
4-
from magicbot import feedback, tunable
4+
from magicbot import feedback, tunable, will_reset_to
55
from phoenix6.configs import (
66
ClosedLoopRampsConfigs,
77
FeedbackConfigs,
@@ -17,7 +17,10 @@
1717

1818

1919
class ShooterComponent:
20-
FLYWHEEL_INTAKE_SPEED = tunable(-20.0)
20+
top_desired_flywheel_speed = will_reset_to(0.0)
21+
bottom_desired_flywheel_speed = will_reset_to(0.0)
22+
23+
FLYWHEEL_INTAKE_SPEED = tunable(-40.0)
2124
FLYWHEEL_RPS_TOLERANCE = 1.0
2225
FLYWHEEL_RAMP_TIME = 1
2326
FLYWHEEL_GEAR_RATIO = 1 / (1.0 / 1.0)
@@ -71,9 +74,6 @@ def __init__(self) -> None:
7174
bottom_flywheel_config.apply(flywheel_gear_ratio)
7275
bottom_flywheel_config.apply(flywheel_closed_loop_ramp_config)
7376

74-
self.top_desired_flywheel_speed = 0.0
75-
self.bottom_desired_flywheel_speed = 0.0
76-
7777
self._algae_size = 16.25
7878
self.has_measured = True
7979

@@ -146,6 +146,3 @@ def execute(self) -> None:
146146
self.bottom_desired_flywheel_speed, override_brake_dur_neutral=True
147147
)
148148
)
149-
150-
self.top_desired_flywheel_speed = 0.0
151-
self.bottom_desired_flywheel_speed = 0.0

0 commit comments

Comments
 (0)