Skip to content
This repository was archived by the owner on May 19, 2024. It is now read-only.

Commit 5815b70

Browse files
committed
feat(intake): Add TalonFX intake.
1 parent ae9d860 commit 5815b70

File tree

3 files changed

+57
-43
lines changed

3 files changed

+57
-43
lines changed

Diff for: src/main/java/frc/robot/intake/IntakeFactory.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@ public class IntakeFactory {
1414
*/
1515
public static RollerMotorIO createRollerMotor() {
1616
if (Robot.isReal() && RobotConstants.REAL_SUBSYSTEMS.contains(Subsystem.INTAKE))
17-
return new RollerMotorIOSparkMax();
17+
return new RollerMotorIOTalonFX();
1818

1919
return new RollerMotorIOSim();
2020
}

Diff for: src/main/java/frc/robot/intake/RollerMotorIOSparkMax.java

-42
This file was deleted.
+56
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,56 @@
1+
package frc.robot.intake;
2+
3+
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
4+
import com.ctre.phoenix6.configs.TalonFXConfiguration;
5+
import com.ctre.phoenix6.hardware.TalonFX;
6+
import com.ctre.phoenix6.signals.NeutralModeValue;
7+
import frc.lib.Configurator;
8+
9+
/** Roller motor using a TalonFX. */
10+
public class RollerMotorIOTalonFX implements RollerMotorIO {
11+
12+
private final TalonFX topTalonFX, bottomTalonFX;
13+
14+
private final SimpleMotorFeedforward topFeedforward, bottomFeedforward;
15+
16+
public RollerMotorIOTalonFX() {
17+
topTalonFX = new TalonFX(0); // TODO
18+
bottomTalonFX = new TalonFX(0); // TODO
19+
20+
topFeedforward = new SimpleMotorFeedforward(0, 0); // TODO
21+
bottomFeedforward = new SimpleMotorFeedforward(0, 0); // TODO
22+
}
23+
24+
@Override
25+
public void configure() {
26+
final TalonFXConfiguration config = new TalonFXConfiguration();
27+
28+
config.Feedback.SensorToMechanismRatio = 1.0; // TODO
29+
30+
config.MotorOutput.NeutralMode = NeutralModeValue.Coast;
31+
32+
Configurator.configureTalonFX(topTalonFX.getConfigurator(), config);
33+
Configurator.configureTalonFX(bottomTalonFX.getConfigurator(), config);
34+
}
35+
36+
@Override
37+
public void update(RollerMotorIOValues values) {
38+
values.velocityRotationsPerSecond = getVelocity();
39+
values.currentAmps = topTalonFX.getStatorCurrent().refresh().getValue();
40+
}
41+
42+
@Override
43+
public void setSetpoint(double velocityRotationsPerSecond) {
44+
double topVolts = topFeedforward.calculate(velocityRotationsPerSecond);
45+
46+
topTalonFX.setVoltage(topVolts);
47+
48+
double bottomVolts = bottomFeedforward.calculate(velocityRotationsPerSecond);
49+
50+
bottomTalonFX.setVoltage(bottomVolts);
51+
}
52+
53+
public double getVelocity() {
54+
return topTalonFX.getVelocity().refresh().getValue();
55+
}
56+
}

0 commit comments

Comments
 (0)