Skip to content

Commit

Permalink
changed neo to talon (#204)
Browse files Browse the repository at this point in the history
* changed neo to talon

* progress monday 14th

* things are working for some reason (auto untested, intake needs to be fixed mechanically)
  • Loading branch information
minhnguyenbhs authored Oct 17, 2024
1 parent 3990770 commit 857687c
Show file tree
Hide file tree
Showing 8 changed files with 53 additions and 58 deletions.
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -52,9 +52,9 @@ public static final class FeatureFlags {
public static final boolean runVision = true;
public static final boolean runLocalizer = true;

public static final boolean runIntake = false;
public static final boolean runScoring = false;
public static final boolean runEndgame = false;
public static final boolean runIntake = true;
public static final boolean runScoring = true;
public static final boolean runEndgame = true;
public static final boolean runDrive = true;

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

public static final class IntakeConstants {
public static final int leftIntakeMotorID = 9;
public static final int rightIntakeMotorID = 10;
// public static final int rightIntakeMotorID = 10;
public static final int indexTwoMotorID = 14;

public static final double intakePower = 12.0;
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@
import frc.robot.subsystems.endgame.EndgameSubsystem;
import frc.robot.subsystems.endgame.EndgameSubsystem.EndgameAction;
import frc.robot.subsystems.intake.IntakeIO;
import frc.robot.subsystems.intake.IntakeIOFalcon;
import frc.robot.subsystems.intake.IntakeIOSim;
import frc.robot.subsystems.intake.IntakeIOSparkMax;
import frc.robot.subsystems.intake.IntakeSubsystem;
import frc.robot.subsystems.intake.IntakeSubsystem.IntakeAction;
import frc.robot.subsystems.localization.CameraContainerReal;
Expand Down Expand Up @@ -150,7 +150,7 @@ public void configureSubsystems() {
}

if (FeatureFlags.runIntake) {
intakeSubsystem = new IntakeSubsystem(new IntakeIOSparkMax());
intakeSubsystem = new IntakeSubsystem(new IntakeIOFalcon());
}

if (FeatureFlags.runVision) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,32 +6,30 @@
import com.ctre.phoenix6.controls.VoltageOut;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.NeutralModeValue;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.CANSparkMax;
import edu.wpi.first.wpilibj.DigitalInput;
import frc.robot.Constants.IntakeConstants;
import frc.robot.Constants.SensorConstants;

public class IntakeIOSparkMax implements IntakeIO {
public class IntakeIOFalcon implements IntakeIO {

private CANSparkMax leftIntake =
new CANSparkMax(IntakeConstants.leftIntakeMotorID, MotorType.kBrushless);
private CANSparkMax rightIntake =
new CANSparkMax(IntakeConstants.rightIntakeMotorID, MotorType.kBrushless);
private TalonFX leftIntake = new TalonFX(IntakeConstants.leftIntakeMotorID);

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

DigitalInput bannerSensor = new DigitalInput(SensorConstants.uptakeSensorPort);

public IntakeIOSparkMax() {
leftIntake.setSmartCurrentLimit(50);
rightIntake.setSmartCurrentLimit(50);

public IntakeIOFalcon() {
leftIntake.setInverted(true);
rightIntake.setInverted(true);

belt.setInverted(true);

TalonFXConfigurator leftConfig = leftIntake.getConfigurator();
leftConfig.apply(new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Coast));
leftConfig.apply(
new CurrentLimitsConfigs()
.withStatorCurrentLimit(120)
.withStatorCurrentLimitEnable(true));

TalonFXConfigurator beltConfig = belt.getConfigurator();
beltConfig.apply(new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Brake));
beltConfig.apply(
Expand All @@ -42,11 +40,8 @@ public IntakeIOSparkMax() {

@Override
public void updateInputs(IntakeIOInputs inputs) {
inputs.leftIntakeVoltage = leftIntake.getAppliedOutput() * 12;
inputs.leftIntakeStatorCurrent = leftIntake.getOutputCurrent();

inputs.rightIntakeVoltage = rightIntake.getAppliedOutput() * 12;
inputs.rightIntakeStatorCurrent = rightIntake.getOutputCurrent();
inputs.leftIntakeVoltage = leftIntake.getMotorVoltage().getValueAsDouble();
inputs.leftIntakeStatorCurrent = leftIntake.getStatorCurrent().getValueAsDouble();

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

@Override
public void setIntakeVoltage(double volts) {
leftIntake.set(volts / 12);
rightIntake.set(volts / 12);
leftIntake.setControl(new VoltageOut(volts));
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ public void periodic() {

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

Logger.recordOutput("intake/state", state.toString());
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -326,7 +326,7 @@ private void shoot() {

double shootRPM = shooterInterpolated.getValue(distancetoGoal);
shooterIo.setShooterVelocityRPM(shootRPM);
double aimAngleRad = aimerInterpolated.getValue(distancetoGoal);
double aimAngleRad = aimerInterpolated.getValue(distancetoGoal) - 0.015;
aimerIo.setAimAngleRad(aimAngleRad, false);

shooterIo.setKickerVolts(10);
Expand Down
10 changes: 5 additions & 5 deletions vendordeps/AdvantageKit.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "AdvantageKit.json",
"name": "AdvantageKit",
"version": "3.2.0",
"version": "3.2.1",
"uuid": "d820cc26-74e3-11ec-90d6-0242ac120003",
"frcYear": "2024",
"mavenUrls": [],
Expand All @@ -10,24 +10,24 @@
{
"groupId": "org.littletonrobotics.akit.junction",
"artifactId": "wpilib-shim",
"version": "3.2.0"
"version": "3.2.1"
},
{
"groupId": "org.littletonrobotics.akit.junction",
"artifactId": "junction-core",
"version": "3.2.0"
"version": "3.2.1"
},
{
"groupId": "org.littletonrobotics.akit.conduit",
"artifactId": "conduit-api",
"version": "3.2.0"
"version": "3.2.1"
}
],
"jniDependencies": [
{
"groupId": "org.littletonrobotics.akit.conduit",
"artifactId": "conduit-wpilibio",
"version": "3.2.0",
"version": "3.2.1",
"skipInvalidPlatforms": false,
"isJar": false,
"validPlatforms": [
Expand Down
6 changes: 3 additions & 3 deletions vendordeps/PathplannerLib.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "PathplannerLib.json",
"name": "PathplannerLib",
"version": "2024.2.7",
"version": "2024.2.8",
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
"frcYear": "2024",
"mavenUrls": [
Expand All @@ -12,15 +12,15 @@
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-java",
"version": "2024.2.7"
"version": "2024.2.8"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-cpp",
"version": "2024.2.7",
"version": "2024.2.8",
"libName": "PathplannerLib",
"headerClassifier": "headers",
"sharedLibrary": false,
Expand Down
Loading

0 comments on commit 857687c

Please sign in to comment.