22
33import numpy as np
44import wpilib
5- from magicbot import feedback , tunable
5+ from magicbot import feedback , tunable , will_reset_to
66from phoenix5 import ControlMode , TalonSRX
77from rev import (
88 SparkMax ,
2323
2424class IntakeComponent :
2525 intake_output = tunable (0.9 )
26+ desired_output = will_reset_to (0.0 )
2627
2728 # Offset is measured in the vertical position
2829 VERTICAL_ENCODER_VALUE = 4.592024
@@ -42,8 +43,6 @@ def __init__(self, intake_mech_root: wpilib.MechanismRoot2d) -> None:
4243 self .intake_motor = TalonSRX (TalonId .INTAKE )
4344 self .intake_motor .setInverted (True )
4445
45- self .desired_output = 0.0
46-
4746 self .arm_motor = SparkMax (SparkId .INTAKE_ARM , SparkMax .MotorType .kBrushless )
4847 self .encoder = DutyCycleEncoder (DioChannel .INTAKE_ENCODER , math .tau , 0 )
4948 configure_through_bore_encoder (self .encoder )
@@ -210,8 +209,6 @@ def on_enable(self) -> None:
210209 def execute (self ) -> None :
211210 self .intake_motor .set (ControlMode .PercentOutput , self .desired_output )
212211
213- self .desired_output = 0.0
214-
215212 self .tracked_state = self .motion_profile .calculate (
216213 wpilib .Timer .getFPGATimestamp () - self .last_setpoint_update_time ,
217214 self .initial_state ,
0 commit comments