Skip to content

Commit 801af39

Browse files
authored
Merge pull request #262 from thedropbears/short_circuit_auto
Short circuit state machines in auto to run routines
2 parents 6ec6d3a + f5262b7 commit 801af39

File tree

4 files changed

+31
-8
lines changed

4 files changed

+31
-8
lines changed

autonomous/auto_base.py

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -149,10 +149,8 @@ def driving_to_coral(self) -> None:
149149

150150
@state
151151
def scoring_coral(self, initial_call: bool) -> None:
152-
if initial_call:
153-
self.coral_placer.place()
154-
elif self.coral_placer.coral_is_scored():
155-
self.next_state("retreating")
152+
# TODO: ADD CORAL BACK WHEN ITS FUNCTIONAL
153+
self.next_state("retreating")
156154

157155
@state
158156
def retreating(self) -> None:

components/shooter.py

Lines changed: 16 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
import math
22

3+
import wpilib
34
from magicbot import feedback, tunable
45
from phoenix6.configs import (
56
ClosedLoopRampsConfigs,
@@ -12,6 +13,7 @@
1213
from phoenix6.signals import InvertedValue, NeutralModeValue
1314

1415
from ids import TalonId
16+
from utilities.game import ALGAE_MAX_DIAMETER, ALGAE_MIN_DIAMETER
1517

1618

1719
class ShooterComponent:
@@ -72,7 +74,20 @@ def __init__(self) -> None:
7274
self.top_desired_flywheel_speed = 0.0
7375
self.bottom_desired_flywheel_speed = 0.0
7476

75-
self.algae_size = 0.0
77+
self._algae_size = 0.0
78+
79+
@property
80+
def algae_size(self) -> float:
81+
return (
82+
self._algae_size
83+
if not wpilib.DriverStation.isAutonomous()
84+
or not wpilib.RobotBase.isSimulation()
85+
else (ALGAE_MIN_DIAMETER + ALGAE_MAX_DIAMETER) / 2.0
86+
)
87+
88+
@algae_size.setter
89+
def algae_size(self, value: float) -> None:
90+
self._algae_size = value
7691

7792
def spin_flywheels(
7893
self, top_flywheel_shoot_speed: float, bottom_flywheel_shoot_speed: float

controllers/floor_intake.py

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

3+
import wpilib
34
from magicbot import StateMachine, state, tunable
45

56
from components.injector import InjectorComponent
@@ -46,10 +47,15 @@ def intaking(self, initial_call: bool):
4647
@state(must_finish=True)
4748
def measuring(self, initial_call):
4849
if initial_call:
49-
self.algae_measurement.measure()
50+
if (
51+
not wpilib.DriverStation.isAutonomous()
52+
and not wpilib.RobotBase.isSimulation()
53+
):
54+
self.algae_measurement.measure()
5055
self.wrist.go_to_neutral()
5156
self.intake_component.retract()
52-
elif not self.algae_measurement.is_executing:
57+
58+
if not self.algae_measurement.is_executing:
5359
self.done()
5460

5561
def done(self) -> None:

controllers/reef_intake.py

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,11 @@ def intaking(self, initial_call: bool):
8686
def safing(self, initial_call: bool):
8787
if initial_call:
8888
self.origin_robot_pose = self.chassis.get_pose()
89-
self.algae_measurement.measure()
89+
if (
90+
not wpilib.DriverStation.isAutonomous()
91+
and not wpilib.RobotBase.isSimulation()
92+
):
93+
self.algae_measurement.measure()
9094
self.chassis.stop_snapping()
9195

9296
robot_pose = self.chassis.get_pose()

0 commit comments

Comments
 (0)