This repository has been archived by the owner on May 19, 2024. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
feat(shooter): Add serializer motor TalonFX.
- Loading branch information
1 parent
29bd5aa
commit f27f2cf
Showing
3 changed files
with
54 additions
and
37 deletions.
There are no files selected for viewing
36 changes: 0 additions & 36 deletions
36
src/main/java/frc/robot/shooter/SerializerMotorIOSparkMax.java
This file was deleted.
Oops, something went wrong.
53 changes: 53 additions & 0 deletions
53
src/main/java/frc/robot/shooter/SerializerMotorIOTalonFX.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,53 @@ | ||
package frc.robot.shooter; | ||
|
||
import com.ctre.phoenix6.StatusSignal; | ||
import com.ctre.phoenix6.configs.TalonFXConfiguration; | ||
import com.ctre.phoenix6.hardware.TalonFX; | ||
import com.ctre.phoenix6.signals.NeutralModeValue; | ||
|
||
import edu.wpi.first.math.controller.SimpleMotorFeedforward; | ||
import frc.lib.Configurator; | ||
|
||
/** Serializer motor using TalonFX. */ | ||
public class SerializerMotorIOTalonFX implements SerializerMotorIO { | ||
|
||
private final TalonFX talonFX; | ||
|
||
private final StatusSignal<Double> velocityRotationsPerSecond, statorCurrentAmps; | ||
|
||
private final SimpleMotorFeedforward velocityFeedforward; | ||
|
||
public SerializerMotorIOTalonFX() { | ||
talonFX = new TalonFX(20); | ||
|
||
velocityRotationsPerSecond = talonFX.getVelocity(); | ||
statorCurrentAmps = talonFX.getStatorCurrent(); | ||
|
||
velocityFeedforward = new SimpleMotorFeedforward(0, 0); | ||
} | ||
|
||
@Override | ||
public void configure() { | ||
final TalonFXConfiguration config = new TalonFXConfiguration(); | ||
|
||
config.MotorOutput.NeutralMode = NeutralModeValue.Coast; | ||
|
||
Configurator.configureTalonFX(talonFX.getConfigurator(), config); | ||
} | ||
|
||
@Override | ||
public void update(SerializerMotorIOValues values) { | ||
velocityRotationsPerSecond.refresh(); | ||
statorCurrentAmps.refresh(); | ||
|
||
values.velocityRotationsPerSecond = velocityRotationsPerSecond.getValue(); | ||
values.currentAmps = statorCurrentAmps.getValue(); | ||
} | ||
|
||
@Override | ||
public void setSetpoint(double velocityRotationsPerSecond) { | ||
double volts = velocityFeedforward.calculate(velocityRotationsPerSecond); | ||
|
||
talonFX.setVoltage(volts); | ||
} | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters