From dda6bcaeefe357c989f619513ec12a65ba49667e Mon Sep 17 00:00:00 2001 From: Max Worrall <96847801+Tsunami014@users.noreply.github.com> Date: Thu, 11 Jan 2024 14:10:01 +1100 Subject: [PATCH 1/6] Added base shooter class --- components/shooter.py | 32 ++++++++++++++++++++++++++++++++ 1 file changed, 32 insertions(+) create mode 100644 components/shooter.py diff --git a/components/shooter.py b/components/shooter.py new file mode 100644 index 00000000..e4d57aab --- /dev/null +++ b/components/shooter.py @@ -0,0 +1,32 @@ +from magicbot import tunable +import wpilib + + +class Shooter: + shooter_motor: wpilib.Talon + shoot_speed = tunable(1.0) # speed is tunable via NetworkTables + + def __init__(self): + self.deployed = False + + def shoot(self): + pass + + def stop(self): + pass + + def deploy(self): + """Causes the shooter motor to spin""" + self.deployed = True + + def is_ready(self): + return True + + def execute(self): + """This gets called at the end of the control loop""" + if self.deployed: + self.shooter_motor.set(self.shoot_speed) + else: + self.shooter_motor.set(0) + + self.deployed = False From 2bbee83d124fd0c1884bf6f6d558fa0491786b19 Mon Sep 17 00:00:00 2001 From: clubpenguin Date: Sun, 14 Jan 2024 10:56:28 +1100 Subject: [PATCH 2/6] added motors configuration aswell as the set speed and rotation --- components/shooter.py | 57 ++++++++++++++++++++++++++++++++----------- ids.py | 8 ++++++ 2 files changed, 51 insertions(+), 14 deletions(-) diff --git a/components/shooter.py b/components/shooter.py index e4d57aab..c51f932b 100644 --- a/components/shooter.py +++ b/components/shooter.py @@ -1,32 +1,61 @@ -from magicbot import tunable -import wpilib +from magicbot import tunable, feedback +from rev import CANSparkMax +from ids import SparkMaxIds, TalonIds +import phoenix6 +from phoenix6.configs import ( + config_groups, + MotorOutputConfigs, +) +from phoenix6.controls import VoltageOut +import phoenix6.hardware class Shooter: - shooter_motor: wpilib.Talon - shoot_speed = tunable(1.0) # speed is tunable via NetworkTables + flywheel_speed = tunable(0.0) + inject_speed = tunable(0.0) def __init__(self): self.deployed = False + self.top_flywheel = phoenix6.hardware.TalonFX(TalonIds.top_flywheel) + self.bottom_flywheel = phoenix6.hardware.TalonFX(TalonIds.bottom_flywheel) + self.inject_flywheel = CANSparkMax( + SparkMaxIds.inject_flywheel, CANSparkMax.MotorType.kBrushless + ) - def shoot(self): - pass + # Configure bottom flywheel motor + bottom_config = self.bottom_flywheel.configurator + bottom_flywheel_config = MotorOutputConfigs() + bottom_flywheel_config.inverted = config_groups.InvertedValue.CLOCKWISE_POSITIVE + + bottom_config.apply(bottom_flywheel_config) - def stop(self): - pass + self.inject_flywheel.setInverted(True) - def deploy(self): - """Causes the shooter motor to spin""" + self.should_inject = False + + def shoot(self): + """causes shooter motors to spin""" self.deployed = True + def inject(self): + self.should_inject = True + def is_ready(self): return True + @feedback + def motor_speeds(self) -> float: + # return the current speed of both flywheel and inject motors + return self.flywheel_speed, self.inject_speed + def execute(self): """This gets called at the end of the control loop""" - if self.deployed: - self.shooter_motor.set(self.shoot_speed) + voltsge_request = VoltageOut(12.0 * self.flywheel_speed) + if self.should_inject: + self.inject_flywheel.set(self.inject_speed) else: - self.shooter_motor.set(0) + self.inject_flywheel.set(0.0) - self.deployed = False + self.top_flywheel.set_control(voltsge_request) + self.bottom_flywheel.set_control(voltsge_request) + self.should_inject = False diff --git a/ids.py b/ids.py index c44404d8..4892e40a 100644 --- a/ids.py +++ b/ids.py @@ -15,6 +15,9 @@ class TalonIds(enum.IntEnum): drive_4 = 4 steer_4 = 8 + top_flywheel = 9 + bottom_flywheel = 10 + @enum.unique class CancoderIds(enum.IntEnum): @@ -22,3 +25,8 @@ class CancoderIds(enum.IntEnum): swerve_2 = 2 swerve_3 = 3 swerve_4 = 4 + + +@enum.unique +class SparkMaxIds(enum.IntEnum): + inject_flywheel = 1 From b19a0139010ee811b3052ebdecfd1fb94285d100 Mon Sep 17 00:00:00 2001 From: clubpenguin Date: Sun, 14 Jan 2024 10:58:49 +1100 Subject: [PATCH 3/6] imported shooter component to robot.py and made an injecting button in teleopperiodic --- robot.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/robot.py b/robot.py index 587925b1..600f9ca6 100644 --- a/robot.py +++ b/robot.py @@ -5,6 +5,7 @@ import magicbot from components.chassis import Chassis +from components.shooter import Shooter from utilities.scalers import rescale_js @@ -14,6 +15,7 @@ class MyRobot(magicbot.MagicRobot): # Components chassis: Chassis + shooter: Shooter max_speed = magicbot.tunable(Chassis.max_wheel_speed * 0.95) @@ -60,6 +62,10 @@ def teleopPeriodic(self) -> None: if self.rumble_timer.hasElapsed(self.rumble_duration): self.gamepad.setRumble(wpilib.XboxController.RumbleType.kBothRumble, 0) + # injecting + if self.gamepad.getBButton(): + self.shooter.inject() + def testInit(self) -> None: pass From 58cd673db29299edae01f9a2bd76ae85bb4baee0 Mon Sep 17 00:00:00 2001 From: clubpenguin Date: Mon, 15 Jan 2024 13:37:08 +1100 Subject: [PATCH 4/6] removed motor speeds feedback method --- components/shooter.py | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/components/shooter.py b/components/shooter.py index c51f932b..264a643e 100644 --- a/components/shooter.py +++ b/components/shooter.py @@ -1,4 +1,4 @@ -from magicbot import tunable, feedback +from magicbot import tunable from rev import CANSparkMax from ids import SparkMaxIds, TalonIds import phoenix6 @@ -43,11 +43,6 @@ def inject(self): def is_ready(self): return True - @feedback - def motor_speeds(self) -> float: - # return the current speed of both flywheel and inject motors - return self.flywheel_speed, self.inject_speed - def execute(self): """This gets called at the end of the control loop""" voltsge_request = VoltageOut(12.0 * self.flywheel_speed) From af0948cf9ee9cfc361421d9f889fbaafe9e0330f Mon Sep 17 00:00:00 2001 From: clubpenguin Date: Mon, 15 Jan 2024 14:25:14 +1100 Subject: [PATCH 5/6] removed inject method and deployed variable --- components/shooter.py | 5 ----- robot.py | 2 +- 2 files changed, 1 insertion(+), 6 deletions(-) diff --git a/components/shooter.py b/components/shooter.py index 264a643e..978014cc 100644 --- a/components/shooter.py +++ b/components/shooter.py @@ -15,7 +15,6 @@ class Shooter: inject_speed = tunable(0.0) def __init__(self): - self.deployed = False self.top_flywheel = phoenix6.hardware.TalonFX(TalonIds.top_flywheel) self.bottom_flywheel = phoenix6.hardware.TalonFX(TalonIds.bottom_flywheel) self.inject_flywheel = CANSparkMax( @@ -34,10 +33,6 @@ def __init__(self): self.should_inject = False def shoot(self): - """causes shooter motors to spin""" - self.deployed = True - - def inject(self): self.should_inject = True def is_ready(self): diff --git a/robot.py b/robot.py index 2a0b5012..e9fe622b 100644 --- a/robot.py +++ b/robot.py @@ -82,7 +82,7 @@ def teleopPeriodic(self) -> None: # injecting if self.gamepad.getBButton(): - self.shooter.inject() + self.shooter.shoot() def testInit(self) -> None: pass From 7b4b59e409ceb3178ccb3da10370b13e06e69db5 Mon Sep 17 00:00:00 2001 From: clubpenguin Date: Mon, 15 Jan 2024 14:29:19 +1100 Subject: [PATCH 6/6] renamed variable voltsge_request to flywheel_request --- components/shooter.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/components/shooter.py b/components/shooter.py index 978014cc..9c95e7dd 100644 --- a/components/shooter.py +++ b/components/shooter.py @@ -40,12 +40,12 @@ def is_ready(self): def execute(self): """This gets called at the end of the control loop""" - voltsge_request = VoltageOut(12.0 * self.flywheel_speed) + flywheel_request = VoltageOut(12.0 * self.flywheel_speed) if self.should_inject: self.inject_flywheel.set(self.inject_speed) else: self.inject_flywheel.set(0.0) - self.top_flywheel.set_control(voltsge_request) - self.bottom_flywheel.set_control(voltsge_request) + self.top_flywheel.set_control(flywheel_request) + self.bottom_flywheel.set_control(flywheel_request) self.should_inject = False