Skip to content
This repository has been archived by the owner on Nov 24, 2024. It is now read-only.

secondary intake motor #72

Merged
merged 2 commits into from
Nov 4, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
public final class IntakeConstants {
/* CAN */
public static final int kIntakeMotorID = 33;
public static final int kSecondaryIntakeMotorID = 999;
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This needs to be changed


public static final double kPassthroughIntakeVoltage = -8;
public static final double kIntakeIntakeVoltage = 12;
Expand Down
10 changes: 10 additions & 0 deletions src/main/java/frc/robot/subsystems/intake/IntakeIOTalonFX.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@

import com.ctre.phoenix6.BaseStatusSignal;
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.controls.Follower;
import com.ctre.phoenix6.controls.MotionMagicVelocityVoltage;
import com.ctre.phoenix6.controls.NeutralOut;
import com.ctre.phoenix6.controls.VelocityVoltage;
Expand All @@ -25,6 +26,9 @@ public class IntakeIOTalonFX implements IntakeIO {
new MotionMagicVelocityVoltage(0).withSlot(0);
private final VoltageOut intakeVoltageReq = new VoltageOut(0);

private final TalonFX secondaryIntakeMotor = new TalonFX(IntakeConstants.kSecondaryIntakeMotorID);
final Follower secondaryIntakeFollowReq = new Follower(intakeMotor.getDeviceID(), false);

private final StatusSignal<Double> intakeMotorVoltage = intakeMotor.getMotorVoltage();
private final StatusSignal<Double> intakeMotorVelocity = intakeMotor.getVelocity();
private final StatusSignal<Double> intakeMotorStatorCurrent = intakeMotor.getStatorCurrent();
Expand Down Expand Up @@ -56,6 +60,11 @@ public IntakeIOTalonFX() {
PhoenixUtil.checkErrorAndRetry(() -> intakeMotor.getConfigurator().refresh(motorConfig));
TalonUtil.applyAndCheckConfiguration(intakeMotor, motorConfig);

var secondaryMotorConfig = IntakeConstants.intakeMotorConfig; // Same as intake motor.
PhoenixUtil.checkErrorAndRetry(
() -> secondaryIntakeMotor.getConfigurator().refresh(secondaryMotorConfig));
TalonUtil.applyAndCheckConfiguration(secondaryIntakeMotor, secondaryMotorConfig);

var passthroughConfig = IntakeConstants.passthroughMotorConfig;
PhoenixUtil.checkErrorAndRetry(
() -> passthroughMotor.getConfigurator().refresh(passthroughConfig));
Expand All @@ -77,6 +86,7 @@ public IntakeIOTalonFX() {
passthroughMotorReferenceSlope);
intakeMotor.optimizeBusUtilization();
passthroughMotor.optimizeBusUtilization();
secondaryIntakeMotor.setControl(secondaryIntakeFollowReq);
}

@Override
Expand Down
Loading