Class WristIOTalonFXReal
java.lang.Object
frc.alotobots.reefscape.subsystems.wrist.io.WristIOTalonFXReal
- All Implemented Interfaces:
WristIO
Hardware implementation of the WristIO interface using TalonFX motor controller and CANCoder for
real robot operation. This class manages the physical wrist mechanism, handling motor control,
position sensing, and safety limits.
-
Nested Class Summary
Nested classes/interfaces inherited from interface frc.alotobots.reefscape.subsystems.wrist.io.WristIO
WristIO.WristIOInputs
-
Constructor Summary
ConstructorsConstructorDescriptionCreates a new WristIOTalonFXReal instance and configures all motor controller and encoder settings. -
Method Summary
Modifier and TypeMethodDescriptionvoid
setWristOpenLoop
(double percentOutput) Sets the wrist motor to run in open-loop mode at a specified percentage of maximum output.void
setWristPosition
(Angle position, int pidSlot) Sets the wrist to a target position using closed-loop control.void
setWristPositionMotionMagic
(Angle position, int pidSlot) Sets the wrist to a target position using closed-loop control and motion magic.void
setWristVelocity
(AngularVelocity velocity, int pidSlot) Sets the wrist to run at a target velocity using closed-loop control.void
stop()
Stops the wrist motor by setting the motor output to zero.void
updateInputs
(WristIO.WristIOInputs inputs) Updates the input values for the wrist subsystem by reading the latest status from hardware.
-
Constructor Details
-
WristIOTalonFXReal
public WristIOTalonFXReal()Creates a new WristIOTalonFXReal instance and configures all motor controller and encoder settings. This includes PID configurations, software limits, current limits, and sensor settings.
-
-
Method Details
-
updateInputs
Updates the input values for the wrist subsystem by reading the latest status from hardware. This includes position, velocity, current, voltage, and limit switch states.- Specified by:
updateInputs
in interfaceWristIO
- Parameters:
inputs
- The WristIOInputs object to update with the latest hardware state
-
setWristPosition
Sets the wrist to a target position using closed-loop control.- Specified by:
setWristPosition
in interfaceWristIO
- Parameters:
position
- The target angle to move topidSlot
- The PID slot to use (0 for velocity, 1 for position)
-
setWristPositionMotionMagic
Sets the wrist to a target position using closed-loop control and motion magic.- Specified by:
setWristPositionMotionMagic
in interfaceWristIO
- Parameters:
position
- The target angle to move topidSlot
- The PID slot to use (0 for velocity, 1 for position)
-
setWristVelocity
Sets the wrist to run at a target velocity using closed-loop control.- Specified by:
setWristVelocity
in interfaceWristIO
- Parameters:
velocity
- The target velocity to move atpidSlot
- The PID slot to use (0 for velocity, 1 for position)
-
setWristOpenLoop
public void setWristOpenLoop(double percentOutput) Sets the wrist motor to run in open-loop mode at a specified percentage of maximum output.- Specified by:
setWristOpenLoop
in interfaceWristIO
- Parameters:
percentOutput
- The motor output percentage (-1.0 to 1.0)
-
stop
public void stop()Stops the wrist motor by setting the motor output to zero.
-