Skip to content

Commit

Permalink
Leds removed from others
Browse files Browse the repository at this point in the history
  • Loading branch information
justinb4003 committed Mar 16, 2024
1 parent 1f43a0f commit d47f4ab
Show file tree
Hide file tree
Showing 10 changed files with 64 additions and 77 deletions.
5 changes: 1 addition & 4 deletions commands/amp_load.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,14 @@
from subsystems.intake import Intake
from subsystems.photoeyes import Photoeyes
from subsystems.amp import Amp
from subsystems.leds import Leds


class AmpLoad(Command):
def __init__(self, amp: Amp, intake: Intake, photoeyes: Photoeyes, leds: Leds) -> None:
def __init__(self, amp: Amp, intake: Intake, photoeyes: Photoeyes) -> None:
super().__init__()
self.amp = amp
self.photoeyes = photoeyes
self.intake = intake
self.leds = leds
self.addRequirements(amp)

def initialize(self) -> None:
Expand Down Expand Up @@ -42,7 +40,6 @@ def isFinished(self) -> bool:
if self.timer.get() > 3.0:
return True
if self.photoeyes.get_amp_loaded() is True:
self.leds.amp_loaded()
return True
return False

4 changes: 1 addition & 3 deletions commands/eject_note.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,13 @@
from commands2 import Command
from subsystems.intake import Intake
from subsystems.photoeyes import Photoeyes
from subsystems.leds import Leds


class EjectNote(Command):
def __init__(self, intake: Intake, photoeyes: Photoeyes, leds: Leds):
def __init__(self, intake: Intake, photoeyes: Photoeyes):
super().__init__()
self.intake = intake
self.photoeyes = photoeyes
self.leds = leds
self.addRequirements(intake)

def initialize(self):
Expand Down
6 changes: 1 addition & 5 deletions commands/intake_note.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,16 @@
from subsystems.shooter import Shooter
from subsystems.amp import Amp
from subsystems.photoeyes import Photoeyes
from subsystems.leds import Leds


class IntakeNote(Command):
def __init__(self, intake: Intake, shooter: Shooter, amp: Amp,
photoeyes: Photoeyes, leds: Leds):
photoeyes: Photoeyes):
super().__init__()
self.intake = intake
self.shooter = shooter
self.amp = amp
self.photoeyes = photoeyes
self.leds = leds
self.addRequirements(intake)

def initialize(self):
Expand All @@ -31,12 +29,10 @@ def initialize(self):
def execute(self):
if self.forceQuit:
return
self.leds.intake_running()
self.intake.feed()
if self.photoeyes.get_intake_loaded():
self.intake.halt()
self.intake.tilt_up()
self.leds.intake_loaded()
self.forceQuit = True
pass

Expand Down
4 changes: 1 addition & 3 deletions commands/return_to_home.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,16 @@
from subsystems.shooter import Shooter
from subsystems.amp import Amp
from subsystems.photoeyes import Photoeyes
from subsystems.leds import Leds


class ReturnToHome(Command):
def __init__(self, intake: Intake, shooter: Shooter, amp: Amp,
photoeyes: Photoeyes, leds: Leds):
photoeyes: Photoeyes):
super().__init__()
self.intake = intake
self.shooter = shooter
self.amp = amp
self.photoeyes = photoeyes
self.leds = leds
self.addRequirements(intake)

def initialize(self):
Expand Down
5 changes: 1 addition & 4 deletions commands/shooter_load.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,21 +2,19 @@
from wpilib import Timer

from subsystems.intake import Intake
from subsystems.leds import Leds
from subsystems.photoeyes import Photoeyes
from subsystems.amp import Amp
from subsystems.shooter import Shooter


class ShooterLoad(Command):
def __init__(self, amp: Amp, intake: Intake, shooter: Shooter,
photoeyes: Photoeyes, leds: Leds) -> None:
photoeyes: Photoeyes) -> None:
super().__init__()
self.amp = amp
self.photoeyes = photoeyes
self.intake = intake
self.shooter = shooter
self.leds = leds
self.addRequirements(amp)
self.addRequirements(shooter)
self.addRequirements(intake)
Expand Down Expand Up @@ -53,7 +51,6 @@ def isFinished(self) -> bool:
if self.timer.get() > 4.0:
return True
if self.photoeyes.get_shooter_loaded() is True:
self.leds.shooter_loaded()
return True
return False

34 changes: 15 additions & 19 deletions robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -72,17 +72,21 @@ def robotInit(self) -> None:
self.commander_joystick2)

self.gyro = gyro.Gyro()
self.leds = leds.Leds()
self.photoeyes = photoeyes.Photoeyes()

self.amp = amp.Amp(self.commander, self.photoeyes)
self.shooter = shooter.Shooter(self.leds)
self.shooter = shooter.Shooter()
self.note_tracker = note_tracker.NoteTracker()
self.intake = intake.Intake(self.commander, self.photoeyes)
self.swerve = drivetrain.Drivetrain(self.gyro, self.driver,
self.note_tracker, self.leds)
self.note_tracker)
self.note_tracker = note_tracker.NoteTracker()
self.climber = climber.Climber(self.driver)
self.leds = leds.Leds(
self.amp, self.intake, self.shooter,
self.swerve, self.note_tracker,
self.climber, self.photoeyes
)
self.param_editor = param_editor.ParamEditor(
self.swerve.defcmd.straight_drive_pid
)
Expand Down Expand Up @@ -116,22 +120,20 @@ def configure_commander_controls(self):
intake_button = JoystickButton(self.commander_joystick1,
RBM.intake_ready_c1)
intake_button.whileTrue(IntakeNote(self.intake, self.shooter,
self.gyro, self.photoeyes,
self.leds))
self.gyro, self.photoeyes))

eject_button = JoystickButton(self.commander_joystick1,
RBM.intake_eject_c1)
eject_button.onTrue(EjectNote(self.intake, self.photoeyes, self.leds))
eject_button.onTrue(EjectNote(self.intake, self.photoeyes))

amp_load_button = JoystickButton(self.commander_joystick2,
RBM.load_note_amp_c2)
amp_load_button.onTrue(AmpLoad(self.amp, self.intake, self.photoeyes, self.leds))
amp_load_button.onTrue(AmpLoad(self.amp, self.intake, self.photoeyes))

shooter_load_button = JoystickButton(self.commander_joystick1,
RBM.load_note_shooter_c1)
shooter_load_button.onTrue(ShooterLoad(self.amp, self.intake,
self.shooter, self.photoeyes,
self.leds))
self.shooter, self.photoeyes))

amp_set_height_amp = JoystickButton(self.commander_joystick2,
RBM.amp_lift_home_c2)
Expand Down Expand Up @@ -186,12 +188,6 @@ def configure_commander_controls(self):
shooter_spin.onFalse(InstantCommand(self.shooter.spin_down))

def robotPeriodic(self) -> None:
SmartDashboard.putNumber("Amp Height", self.amp.get_height())
if DriverStation.isDisabled():
self.leds.set_connect_status()

# SmartDashboard.putNumber("Climber Speed", self.driver.get_climber_trigger())

# Rough idea of how to incorporate vision into odometry
if self.swerve.vision_stable is True:
from math import pi
Expand Down Expand Up @@ -224,7 +220,7 @@ def robotPeriodic(self) -> None:
rot = p.rotation().degrees()
# self.swerve.odometry.addVisionMeasurement(p, 0, (0.1, 0.1, 0.1))
ts = self.vision_timer.getFPGATimestamp() - timelag
print(f'vision heading: {x}, {y}, {rot}, {ts}')
# print(f'vision heading: {x}, {y}, {rot}, {ts}')
xdev, ydev, rotdev = cw
self.swerve.odometry.addVisionMeasurement(
p, ts, (xdev, ydev, rotdev)
Expand All @@ -239,7 +235,7 @@ def auto_station_1(self):
delaycmd = Delay(5)
cmd = PathPlannerAuto("LakeCityTwoNote")
intake_to_shooter = ShooterLoad(self.amp, self.intake, self.shooter,
self.photoeyes, self.leds)
self.photoeyes)
shootcmd = AutoShooterLaunchNote(self.shooter,
shooter.tilt_safe, 80)
cmds = [
Expand All @@ -255,7 +251,7 @@ def auto_station_2(self):
delaycmd = Delay(1)
cmd = PathPlannerAuto("LakeCityTwoNoteCenter")
intake_to_shooter = ShooterLoad(self.amp, self.intake, self.shooter,
self.photoeyes, self.leds)
self.photoeyes)
shootcmd = AutoShooterLaunchNote(self.shooter,
shooter.tilt_safe, 80)
cmds = [
Expand All @@ -271,7 +267,7 @@ def auto_station_3(self):
delaycmd = Delay(1)
cmd = PathPlannerAuto("LakeCityTwoNote3")
intake_to_shooter = ShooterLoad(self.amp, self.intake, self.shooter,
self.photoeyes, self.leds)
self.photoeyes)
shootcmd = AutoShooterLaunchNote(self.shooter,
shooter.tilt_safe, 80)
cmds = [
Expand Down
2 changes: 1 addition & 1 deletion simgui-window.json
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
},
"###NetworkTables": {
"Collapsed": "0",
"Pos": "99,40",
"Pos": "237,11",
"Size": "635,613"
},
"###NetworkTables Info": {
Expand Down
15 changes: 4 additions & 11 deletions subsystems/drivetrain.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@

import json
import math
from subsystems.leds import Leds
import subsystems.swervemodule as swervemodule
import subsystems.gyro as gyro
from commands2 import Subsystem, Command
Expand Down Expand Up @@ -43,16 +42,15 @@ class Drivetrain(Subsystem):
"""
Represents a swerve drive style drivetrain.
"""
def __init__(self, gyro: gyro.Gyro, driver_controller, photon: NoteTracker,
leds: Leds) -> None:
def __init__(self, gyro: gyro.Gyro, driver_controller,
photon: NoteTracker) -> None:
super().__init__()
# TODO: Set these to the right numbers in centimeters
self.frontLeftLocation = Translation2d(swerve_offset, swerve_offset)
self.frontRightLocation = Translation2d(swerve_offset, -swerve_offset)
self.backLeftLocation = Translation2d(-swerve_offset, swerve_offset)
self.backRightLocation = Translation2d(-swerve_offset, -swerve_offset)
self.photon = photon
self.leds = leds

self.lockable = False
self.locked = False
Expand Down Expand Up @@ -156,7 +154,7 @@ def __init__(self, gyro: gyro.Gyro, driver_controller, photon: NoteTracker,
self # Reference to this subsystem to set requirements
)

self.defcmd = DrivetrainDefaultCommand(self, self.controller, photon, leds, gyro)
self.defcmd = DrivetrainDefaultCommand(self, self.controller, photon, gyro)
self.setDefaultCommand(self.defcmd)

def lock_heading(self):
Expand Down Expand Up @@ -317,12 +315,11 @@ class DrivetrainDefaultCommand(Command):
Default command for the drivetrain.
"""
def __init__(self, drivetrain: Drivetrain, controller: DriverController,
photon: NoteTracker, leds: Leds, gyro: Gyro) -> None:
photon: NoteTracker, gyro: Gyro) -> None:
super().__init__()
self.drivetrain = drivetrain
self.controller = controller
self.photon = photon
self.leds = leds
self.gyro = gyro
self.note_pid = PIDController(*PIDC.note_tracking_pid)
self.note_translate_pid = PIDController(*PIDC.note_translate_pid)
Expand Down Expand Up @@ -426,7 +423,6 @@ def execute(self) -> None:
if yaw is not None:
if abs(yaw) < 1.7:
rot = 0
self.leds.tracking_note()
xSpeed = 0.5
else:
if pitch is not None and pitch > 0:
Expand All @@ -435,9 +431,6 @@ def execute(self) -> None:
rot = 0
# Force a translation to center on the note when close
ySpeed = self.note_translate_pid.calculate(yaw, 0)
self.leds.tracking_note()
else:
self.leds.tracking_note_not_found()

if self.controller.get_slow_mode():
self.leds.drivetrain_slow()
Expand Down
57 changes: 38 additions & 19 deletions subsystems/leds.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,15 @@
from commands2 import Subsystem
from wpilib import AddressableLED, DriverStation
from constants import RobotSensorMap as RSM
from subsystems.amp import Amp
from subsystems.shooter import Shooter
from subsystems.drivetrain import Drivetrain
from subsystems.note_tracker import NoteTracker
from subsystems.climber import Climber
from subsystems.photoeyes import Photoeyes
from subsystems.intake import Intake



"""
HSV values:
Expand All @@ -27,10 +36,18 @@


class Leds(Subsystem):
def __init__(self):
def __init__(self, amp: Amp, intake: Intake, shooter: Shooter,
drive: Drivetrain, note_tracker: NoteTracker,
climber: Climber, photoeyes: Photoeyes):
super().__init__()

self.leds = AddressableLED(RSM.addressable_leds)
self.amp = amp
self.intake = intake
self.shooter = shooter
self.drive = drive
self.note_tracker = note_tracker
self.climber = climber
self.photoeyes = photoeyes

self.led_length = 135
self.blinking = False
Expand All @@ -42,10 +59,28 @@ def __init__(self):
self.led_data = [AddressableLED.LEDData() for _ in range(self.led_length)]

self.rainbowFirstPixelHue = 0
self.intake_loaded()

self.leds.setData(self.led_data)
self.leds.start()

def periodic(self) -> None:
if False:
if self.rainbow_mode:
self.rainbow()
elif self.blinking:
if self.blink_counter < blink_loops:
self.blink_counter += 1
else:
self.blink_counter = 0
if self.blink_on:
self.set_color(0)
self.blink_on = False
else:
self.set_color(self.curr_color)
self.blink_on = True
self.leds.setData(self.led_data)

def rainbow(self):
# For every pixel
for i in range(self.led_length):
Expand Down Expand Up @@ -143,20 +178,4 @@ def off(self):

def drivetrain_slow(self):
# self.set_color(RED)
pass

def periodic(self) -> None:
if self.rainbow_mode:
self.rainbow()
elif self.blinking:
if self.blink_counter < blink_loops:
self.blink_counter += 1
else:
self.blink_counter = 0
if self.blink_on:
self.set_color(0)
self.blink_on = False
else:
self.set_color(self.curr_color)
self.blink_on = True
self.leds.setData(self.led_data)
pass
Loading

0 comments on commit d47f4ab

Please sign in to comment.