Skip to content

Commit

Permalink
tidied up
Browse files Browse the repository at this point in the history
  • Loading branch information
SebZanardo committed Jan 25, 2024
1 parent a1163a8 commit 987126d
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 14 deletions.
6 changes: 3 additions & 3 deletions components/shooter.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
import math
from magicbot import tunable, feedback
from rev import CANSparkMax
from ids import SparkMaxIds, TalonIds, DioChannels
Expand All @@ -7,7 +8,6 @@
from wpilib import DutyCycleEncoder
from wpimath.controller import ProfiledPIDControllerRadians
from wpimath.trajectory import TrapezoidProfileRadians
import math
from utilities.functions import clamp


Expand All @@ -20,7 +20,7 @@ class ShooterComponent:
MIN_INCLINE_ANGLE = math.radians(0)
INCLINATOR_TOLERANCE = math.radians(5)

FLYWHEEL_TOLERANCE = 1 # rotation per s
FLYWHEEL_TOLERANCE = 1 # Rotation per second

INCLINATOR_OFFSET = 0.6632

Expand All @@ -31,7 +31,7 @@ def __init__(self) -> None:
self.inclinator.setInverted(True)
self.inclinator_encoder = DutyCycleEncoder(DioChannels.inclinator_encoder)
self.inclinator_encoder.setPositionOffset(self.INCLINATOR_OFFSET)
# invert encoder and map to radians
# Invert encoder and map to radians
self.inclinator_encoder.setDistancePerRotation(-math.tau)
self.flywheel = phoenix6.hardware.TalonFX(TalonIds.shooter_flywheel)
self.injector = CANSparkMax(
Expand Down
23 changes: 12 additions & 11 deletions controllers/shooter.py
Original file line number Diff line number Diff line change
@@ -1,20 +1,23 @@
from math import atan2
from magicbot import StateMachine, state, timed_state, default_state, will_reset_to
from components.chassis import ChassisComponent
from components.shooter import ShooterComponent

from utilities.game import get_goal_speaker_position

from math import atan2


class ShooterController(StateMachine):
chassis: ChassisComponent
shooter_component: ShooterComponent
button_pressed = will_reset_to(False)
SHOOTING_TIME_DURATION = 3

def setup(self) -> None:
pass
FLYWHEEL_SPEED_MAP = {}
INCLINATION_ANGLE_MAP = {}

def shoot(self) -> None:
self.button_pressed = True
self.engage()

def update_ranging(self) -> None:
dist = (
Expand All @@ -36,19 +39,21 @@ def idle(self) -> None:

@state(first=True)
def acquiring(self) -> None:
# determine heading required for goal
# NOTE Turret can't rotate, instead we face the chassis towards the goal
# Determine heading required for goal
translation_to_goal = (
get_goal_speaker_position().toTranslation2d()
- self.chassis.get_pose().translation()
)
bearing_to_speaker = atan2(translation_to_goal.y, translation_to_goal.x)
# set to appropriate heading

# Set to appropriate heading
self.chassis.snap_to_heading(bearing_to_speaker)

# Update ranging but don't check for tolerance yet
self.update_ranging()

# progress state machine if within tolerance
# Progress state machine if within tolerance
if self.chassis.at_desired_heading():
self.next_state("ranging")

Expand All @@ -69,7 +74,3 @@ def shooting(self) -> None:
def resetting(self) -> None:
self.shooter_component.stop_injection()
self.done()

def shoot(self) -> None:
self.button_pressed = True
self.engage()

0 comments on commit 987126d

Please sign in to comment.