Skip to content

Commit 857687c

Browse files
changed neo to talon (#204)
* changed neo to talon * progress monday 14th * things are working for some reason (auto untested, intake needs to be fixed mechanically)
1 parent 3990770 commit 857687c

File tree

8 files changed

+53
-58
lines changed

8 files changed

+53
-58
lines changed

src/main/java/frc/robot/Constants.java

+4-4
Original file line numberDiff line numberDiff line change
@@ -52,9 +52,9 @@ public static final class FeatureFlags {
5252
public static final boolean runVision = true;
5353
public static final boolean runLocalizer = true;
5454

55-
public static final boolean runIntake = false;
56-
public static final boolean runScoring = false;
57-
public static final boolean runEndgame = false;
55+
public static final boolean runIntake = true;
56+
public static final boolean runScoring = true;
57+
public static final boolean runEndgame = true;
5858
public static final boolean runDrive = true;
5959

6060
public static final boolean enableLEDS = true;
@@ -257,7 +257,7 @@ private static AprilTagFieldLayout initLayout(String name) {
257257

258258
public static final class IntakeConstants {
259259
public static final int leftIntakeMotorID = 9;
260-
public static final int rightIntakeMotorID = 10;
260+
// public static final int rightIntakeMotorID = 10;
261261
public static final int indexTwoMotorID = 14;
262262

263263
public static final double intakePower = 12.0;

src/main/java/frc/robot/RobotContainer.java

+2-2
Original file line numberDiff line numberDiff line change
@@ -38,8 +38,8 @@
3838
import frc.robot.subsystems.endgame.EndgameSubsystem;
3939
import frc.robot.subsystems.endgame.EndgameSubsystem.EndgameAction;
4040
import frc.robot.subsystems.intake.IntakeIO;
41+
import frc.robot.subsystems.intake.IntakeIOFalcon;
4142
import frc.robot.subsystems.intake.IntakeIOSim;
42-
import frc.robot.subsystems.intake.IntakeIOSparkMax;
4343
import frc.robot.subsystems.intake.IntakeSubsystem;
4444
import frc.robot.subsystems.intake.IntakeSubsystem.IntakeAction;
4545
import frc.robot.subsystems.localization.CameraContainerReal;
@@ -150,7 +150,7 @@ public void configureSubsystems() {
150150
}
151151

152152
if (FeatureFlags.runIntake) {
153-
intakeSubsystem = new IntakeSubsystem(new IntakeIOSparkMax());
153+
intakeSubsystem = new IntakeSubsystem(new IntakeIOFalcon());
154154
}
155155

156156
if (FeatureFlags.runVision) {

src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.java src/main/java/frc/robot/subsystems/intake/IntakeIOFalcon.java

+13-19
Original file line numberDiff line numberDiff line change
@@ -6,32 +6,30 @@
66
import com.ctre.phoenix6.controls.VoltageOut;
77
import com.ctre.phoenix6.hardware.TalonFX;
88
import com.ctre.phoenix6.signals.NeutralModeValue;
9-
import com.revrobotics.CANSparkLowLevel.MotorType;
10-
import com.revrobotics.CANSparkMax;
119
import edu.wpi.first.wpilibj.DigitalInput;
1210
import frc.robot.Constants.IntakeConstants;
1311
import frc.robot.Constants.SensorConstants;
1412

15-
public class IntakeIOSparkMax implements IntakeIO {
13+
public class IntakeIOFalcon implements IntakeIO {
1614

17-
private CANSparkMax leftIntake =
18-
new CANSparkMax(IntakeConstants.leftIntakeMotorID, MotorType.kBrushless);
19-
private CANSparkMax rightIntake =
20-
new CANSparkMax(IntakeConstants.rightIntakeMotorID, MotorType.kBrushless);
15+
private TalonFX leftIntake = new TalonFX(IntakeConstants.leftIntakeMotorID);
2116

2217
private TalonFX belt = new TalonFX(IntakeConstants.indexTwoMotorID);
2318

2419
DigitalInput bannerSensor = new DigitalInput(SensorConstants.uptakeSensorPort);
2520

26-
public IntakeIOSparkMax() {
27-
leftIntake.setSmartCurrentLimit(50);
28-
rightIntake.setSmartCurrentLimit(50);
29-
21+
public IntakeIOFalcon() {
3022
leftIntake.setInverted(true);
31-
rightIntake.setInverted(true);
3223

3324
belt.setInverted(true);
3425

26+
TalonFXConfigurator leftConfig = leftIntake.getConfigurator();
27+
leftConfig.apply(new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Coast));
28+
leftConfig.apply(
29+
new CurrentLimitsConfigs()
30+
.withStatorCurrentLimit(120)
31+
.withStatorCurrentLimitEnable(true));
32+
3533
TalonFXConfigurator beltConfig = belt.getConfigurator();
3634
beltConfig.apply(new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Brake));
3735
beltConfig.apply(
@@ -42,11 +40,8 @@ public IntakeIOSparkMax() {
4240

4341
@Override
4442
public void updateInputs(IntakeIOInputs inputs) {
45-
inputs.leftIntakeVoltage = leftIntake.getAppliedOutput() * 12;
46-
inputs.leftIntakeStatorCurrent = leftIntake.getOutputCurrent();
47-
48-
inputs.rightIntakeVoltage = rightIntake.getAppliedOutput() * 12;
49-
inputs.rightIntakeStatorCurrent = rightIntake.getOutputCurrent();
43+
inputs.leftIntakeVoltage = leftIntake.getMotorVoltage().getValueAsDouble();
44+
inputs.leftIntakeStatorCurrent = leftIntake.getStatorCurrent().getValueAsDouble();
5045

5146
inputs.beltVoltage = belt.getMotorVoltage().getValueAsDouble();
5247
inputs.beltStatorCurrent = belt.getStatorCurrent().getValueAsDouble();
@@ -57,8 +52,7 @@ public void updateInputs(IntakeIOInputs inputs) {
5752

5853
@Override
5954
public void setIntakeVoltage(double volts) {
60-
leftIntake.set(volts / 12);
61-
rightIntake.set(volts / 12);
55+
leftIntake.setControl(new VoltageOut(volts));
6256
}
6357

6458
@Override

src/main/java/frc/robot/subsystems/intake/IntakeSubsystem.java

+1
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@ public void periodic() {
4545

4646
Logger.recordOutput("intake/running", inputs.leftIntakeVoltage != 0.0);
4747
Logger.recordOutput("intake/belting", inputs.beltVoltage != 0.0);
48+
Logger.recordOutput("intake/scorerWantsNote", scorerWantsNote.getAsBoolean());
4849

4950
Logger.recordOutput("intake/state", state.toString());
5051
}

src/main/java/frc/robot/subsystems/scoring/ScoringSubsystem.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -326,7 +326,7 @@ private void shoot() {
326326

327327
double shootRPM = shooterInterpolated.getValue(distancetoGoal);
328328
shooterIo.setShooterVelocityRPM(shootRPM);
329-
double aimAngleRad = aimerInterpolated.getValue(distancetoGoal);
329+
double aimAngleRad = aimerInterpolated.getValue(distancetoGoal) - 0.015;
330330
aimerIo.setAimAngleRad(aimAngleRad, false);
331331

332332
shooterIo.setKickerVolts(10);

vendordeps/AdvantageKit.json

+5-5
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
{
22
"fileName": "AdvantageKit.json",
33
"name": "AdvantageKit",
4-
"version": "3.2.0",
4+
"version": "3.2.1",
55
"uuid": "d820cc26-74e3-11ec-90d6-0242ac120003",
66
"frcYear": "2024",
77
"mavenUrls": [],
@@ -10,24 +10,24 @@
1010
{
1111
"groupId": "org.littletonrobotics.akit.junction",
1212
"artifactId": "wpilib-shim",
13-
"version": "3.2.0"
13+
"version": "3.2.1"
1414
},
1515
{
1616
"groupId": "org.littletonrobotics.akit.junction",
1717
"artifactId": "junction-core",
18-
"version": "3.2.0"
18+
"version": "3.2.1"
1919
},
2020
{
2121
"groupId": "org.littletonrobotics.akit.conduit",
2222
"artifactId": "conduit-api",
23-
"version": "3.2.0"
23+
"version": "3.2.1"
2424
}
2525
],
2626
"jniDependencies": [
2727
{
2828
"groupId": "org.littletonrobotics.akit.conduit",
2929
"artifactId": "conduit-wpilibio",
30-
"version": "3.2.0",
30+
"version": "3.2.1",
3131
"skipInvalidPlatforms": false,
3232
"isJar": false,
3333
"validPlatforms": [

vendordeps/PathplannerLib.json

+3-3
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
{
22
"fileName": "PathplannerLib.json",
33
"name": "PathplannerLib",
4-
"version": "2024.2.7",
4+
"version": "2024.2.8",
55
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
66
"frcYear": "2024",
77
"mavenUrls": [
@@ -12,15 +12,15 @@
1212
{
1313
"groupId": "com.pathplanner.lib",
1414
"artifactId": "PathplannerLib-java",
15-
"version": "2024.2.7"
15+
"version": "2024.2.8"
1616
}
1717
],
1818
"jniDependencies": [],
1919
"cppDependencies": [
2020
{
2121
"groupId": "com.pathplanner.lib",
2222
"artifactId": "PathplannerLib-cpp",
23-
"version": "2024.2.7",
23+
"version": "2024.2.8",
2424
"libName": "PathplannerLib",
2525
"headerClassifier": "headers",
2626
"sharedLibrary": false,

0 commit comments

Comments
 (0)