From 15a7fff3235112ac8c4e6dd4a86d263826ed8c63 Mon Sep 17 00:00:00 2001 From: SyntaxBreak <> Date: Fri, 23 Jan 2026 18:30:03 +1100 Subject: [PATCH 1/9] swapped id numbers --- ids.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ids.py b/ids.py index c2e1113..6ed2191 100644 --- a/ids.py +++ b/ids.py @@ -17,12 +17,12 @@ class TalonId(enum.IntEnum): DRIVE_FR = 4 STEER_FR = 8 - FLYWHEEL_LEFT = 9 - FLYWHEEL_RIGHT = 10 + FLYWHEEL_RIGHT = 9 + FLYWHEEL_LEFT = 10 FEEDER = 11 - LEFT_FUNNEL = 12 - RIGHT_FUNNEL = 13 + RIGHT_FUNNEL = 12 + LEFT_FUNNEL = 13 @enum.unique From d89d8f0f265c49146710eaed7df113a856db102e Mon Sep 17 00:00:00 2001 From: SyntaxBreak <> Date: Fri, 23 Jan 2026 19:29:49 +1100 Subject: [PATCH 2/9] Reversed shooter rotation --- components/shooter.py | 23 +++++++++++------------ 1 file changed, 11 insertions(+), 12 deletions(-) diff --git a/components/shooter.py b/components/shooter.py index af08507..d7c9144 100644 --- a/components/shooter.py +++ b/components/shooter.py @@ -1,9 +1,8 @@ from magicbot import tunable, will_reset_to from phoenix5 import ControlMode, TalonSRX from phoenix6 import configs, controls -from phoenix6.controls import Follower from phoenix6.hardware import TalonFX -from phoenix6.signals import MotorAlignmentValue +from phoenix6.signals import InvertedValue, MotorAlignmentValue from ids import TalonId @@ -16,14 +15,9 @@ class ShooterComponent: desired_feeder_percentage = tunable(1) def __init__(self) -> None: - self.flywheel_motor_left = TalonFX( - device_id=TalonId.FLYWHEEL_LEFT - ) # Defined from behind shooter - self.flywheel_motor_right = TalonFX( - device_id=TalonId.FLYWHEEL_RIGHT - ) # Defined from behind shooter + self.flywheel_motor_left = TalonFX(TalonId.FLYWHEEL_LEFT) + self.flywheel_motor_right = TalonFX(TalonId.FLYWHEEL_RIGHT) self.feeder_motor = TalonSRX(TalonId.FEEDER) - self.feeder_motor.setInverted(False) gains_cfg = ( configs.Slot0Configs() @@ -36,7 +30,13 @@ def __init__(self) -> None: ) self.flywheel_motor_left.configurator.apply( - configs.TalonFXConfiguration().with_slot0(gains_cfg) + configs.TalonFXConfiguration() + .with_slot0(gains_cfg) + .with_motor_output( + configs.MotorOutputConfigs().with_inverted( + InvertedValue.COUNTER_CLOCKWISE_POSITIVE + ) + ) ) def shoot(self) -> None: @@ -48,9 +48,8 @@ def execute(self) -> None: controls.VelocityVoltage(self.target_shooter_rps) ) self.flywheel_motor_right.set_control( - Follower( + controls.Follower( TalonId.FLYWHEEL_LEFT, MotorAlignmentValue(MotorAlignmentValue.OPPOSED) ) ) - self.feeder_motor.set(ControlMode.PercentOutput, self.target_feeder_percentage) From 0591112b79845a2bcb5b314e6ca84f49d876660e Mon Sep 17 00:00:00 2001 From: SyntaxBreak <> Date: Fri, 23 Jan 2026 19:42:13 +1100 Subject: [PATCH 3/9] Reversed intake funnel rotation --- components/intake.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/components/intake.py b/components/intake.py index 0a30679..ea62ed5 100644 --- a/components/intake.py +++ b/components/intake.py @@ -19,13 +19,13 @@ def __init__(self) -> None: self.motor = SparkMax(SparkId.INTAKE, SparkMax.MotorType.kBrushless) self.left_funnel_motor = TalonSRX(TalonId.LEFT_FUNNEL) self.right_funnel_motor = TalonSRX(TalonId.RIGHT_FUNNEL) + motor_config = SparkMaxConfig() - motor_config.inverted(False) motor_config.setIdleMode(SparkMaxConfig.IdleMode.kCoast) + configure_spark_ephemeral(self.motor, motor_config) + self.left_funnel_motor.setInverted(True) - self.right_funnel_motor.setInverted(True) - configure_spark_ephemeral(self.motor, motor_config) def intake(self) -> None: self.desired_output = self.intake_output @@ -34,4 +34,4 @@ def intake(self) -> None: def execute(self) -> None: self.motor.set(self.desired_output) self.left_funnel_motor.set(ControlMode.PercentOutput, self.desired_funnel) - self.right_funnel_motor.set(ControlMode.PercentOutput, self.desired_funnel) + self.right_funnel_motor.set(ControlMode.Follower) From f46f3ed0aa8c88e0a7571756c3fa04d23126a1d7 Mon Sep 17 00:00:00 2001 From: SyntaxBreak <> Date: Fri, 23 Jan 2026 19:42:52 +1100 Subject: [PATCH 4/9] Reversed intake funnel rotation --- components/intake.py | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/components/intake.py b/components/intake.py index ea62ed5..7367d6f 100644 --- a/components/intake.py +++ b/components/intake.py @@ -1,5 +1,5 @@ from magicbot import tunable, will_reset_to -from phoenix5 import ControlMode, TalonSRX +from phoenix5 import ControlMode, FollowerType, TalonSRX from rev import SparkMax, SparkMaxConfig from ids import SparkId, TalonId @@ -24,9 +24,6 @@ def __init__(self) -> None: motor_config.setIdleMode(SparkMaxConfig.IdleMode.kCoast) configure_spark_ephemeral(self.motor, motor_config) - self.left_funnel_motor.setInverted(True) - - def intake(self) -> None: self.desired_output = self.intake_output self.desired_funnel = self.funnel_output @@ -34,4 +31,6 @@ def intake(self) -> None: def execute(self) -> None: self.motor.set(self.desired_output) self.left_funnel_motor.set(ControlMode.PercentOutput, self.desired_funnel) - self.right_funnel_motor.set(ControlMode.Follower) + self.right_funnel_motor.follow( + self.left_funnel_motor, FollowerType(ControlMode.PercentOutput) + ) From 6a88a449e48e785f242c90786b5b3d01901ad8d9 Mon Sep 17 00:00:00 2001 From: SyntaxBreak <> Date: Fri, 23 Jan 2026 19:47:51 +1100 Subject: [PATCH 5/9] Inverted right funnel motor --- components/intake.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/components/intake.py b/components/intake.py index 7367d6f..1ab85a5 100644 --- a/components/intake.py +++ b/components/intake.py @@ -20,6 +20,8 @@ def __init__(self) -> None: self.left_funnel_motor = TalonSRX(TalonId.LEFT_FUNNEL) self.right_funnel_motor = TalonSRX(TalonId.RIGHT_FUNNEL) + self.right_funnel_motor.setInverted(True) + motor_config = SparkMaxConfig() motor_config.setIdleMode(SparkMaxConfig.IdleMode.kCoast) configure_spark_ephemeral(self.motor, motor_config) From 20df50db972950b4c79e7e21e6c8c1437b709b27 Mon Sep 17 00:00:00 2001 From: SyntaxBreak <> Date: Fri, 23 Jan 2026 19:50:00 +1100 Subject: [PATCH 6/9] Fixed prek --- components/intake.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/components/intake.py b/components/intake.py index 1ab85a5..12d01d6 100644 --- a/components/intake.py +++ b/components/intake.py @@ -21,7 +21,7 @@ def __init__(self) -> None: self.right_funnel_motor = TalonSRX(TalonId.RIGHT_FUNNEL) self.right_funnel_motor.setInverted(True) - + motor_config = SparkMaxConfig() motor_config.setIdleMode(SparkMaxConfig.IdleMode.kCoast) configure_spark_ephemeral(self.motor, motor_config) From 8c62e24664034b36c2cdd5850baa5b45c38afa90 Mon Sep 17 00:00:00 2001 From: SyntaxBreak <> Date: Sat, 24 Jan 2026 16:54:42 +1100 Subject: [PATCH 7/9] Fixed id --- ids.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ids.py b/ids.py index 6ed2191..43304b1 100644 --- a/ids.py +++ b/ids.py @@ -21,9 +21,8 @@ class TalonId(enum.IntEnum): FLYWHEEL_LEFT = 10 FEEDER = 11 - RIGHT_FUNNEL = 12 LEFT_FUNNEL = 13 - + RIGHT_FUNNEL = 12 @enum.unique class CancoderId(enum.IntEnum): From 9c1c9971532a98f10e35ae4fe730c55cecc7b04d Mon Sep 17 00:00:00 2001 From: SyntaxBreak <> Date: Sat, 24 Jan 2026 16:59:03 +1100 Subject: [PATCH 8/9] Fixed funnel inversions --- components/intake.py | 1 + 1 file changed, 1 insertion(+) diff --git a/components/intake.py b/components/intake.py index 12d01d6..3fb86c6 100644 --- a/components/intake.py +++ b/components/intake.py @@ -20,6 +20,7 @@ def __init__(self) -> None: self.left_funnel_motor = TalonSRX(TalonId.LEFT_FUNNEL) self.right_funnel_motor = TalonSRX(TalonId.RIGHT_FUNNEL) + self.left_funnel_motor.setInverted(True) self.right_funnel_motor.setInverted(True) motor_config = SparkMaxConfig() From 0441c8bb51e97b8474f390a4da04ec27639281be Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 29 Jan 2026 00:41:07 +0000 Subject: [PATCH 9/9] [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci --- ids.py | 1 + 1 file changed, 1 insertion(+) diff --git a/ids.py b/ids.py index 43304b1..fbfa258 100644 --- a/ids.py +++ b/ids.py @@ -24,6 +24,7 @@ class TalonId(enum.IntEnum): LEFT_FUNNEL = 13 RIGHT_FUNNEL = 12 + @enum.unique class CancoderId(enum.IntEnum): """CAN ID for CTRE CANcoder."""