Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 7 additions & 5 deletions components/intake.py
Original file line number Diff line number Diff line change
@@ -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
Expand All @@ -19,12 +19,12 @@ 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)

self.left_funnel_motor.setInverted(True)
self.right_funnel_motor.setInverted(True)

motor_config = SparkMaxConfig()
motor_config.setIdleMode(SparkMaxConfig.IdleMode.kCoast)
configure_spark_ephemeral(self.motor, motor_config)

def intake(self) -> None:
Expand All @@ -34,4 +34,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.PercentOutput, self.desired_funnel)
self.right_funnel_motor.follow(
self.left_funnel_motor, FollowerType(ControlMode.PercentOutput)
)
23 changes: 11 additions & 12 deletions components/shooter.py
Original file line number Diff line number Diff line change
@@ -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

Expand All @@ -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()
Expand All @@ -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:
Expand All @@ -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)
8 changes: 4 additions & 4 deletions ids.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
LEFT_FUNNEL = 13
RIGHT_FUNNEL = 12


@enum.unique
Expand Down