Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update Libraries to 2025 #22

Merged
merged 8 commits into from
Dec 13, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
9 changes: 5 additions & 4 deletions src/main/java/frc/robot/shuffleboard/MotorTab.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
package frc.robot.shuffleboard;

import com.revrobotics.CANSparkMax;
import com.revrobotics.spark.SparkMax;

import edu.wpi.first.networktables.DoublePublisher;
import edu.wpi.first.networktables.NetworkTable;
Expand All @@ -20,7 +20,7 @@ public class MotorTab {
private final DoublePublisher[] stickyFaultPublisher;
private final DoublePublisher[] motorTemperaturePublishers;
private final DoublePublisher[] motorEncoderPublishers;
private final CANSparkMax[] motors = new CANSparkMax[Constants.NUMBER_OF_MOTORS];
private final SparkMax[] motors = new SparkMax[Constants.NUMBER_OF_MOTORS];
private int numberOfMotors = 0;
private final int totalNumberOfMotors;

Expand Down Expand Up @@ -71,7 +71,7 @@ public MotorTab(int totalNumberOfMotors, String tabName) {
* @param newMotors
* an array of the new motors to be added
*/
public void addMotor(CANSparkMax[] newMotors) {
public void addMotor(SparkMax[] newMotors) {
if (newMotors.length + numberOfMotors > totalNumberOfMotors) {
tooManyMotors.setText("Too many motors. Increase Constants.NUMBER_OF_MOTORS to: " + (newMotors.length + numberOfMotors));
tooManyMotors.set(true);
Expand Down Expand Up @@ -111,7 +111,8 @@ public void update() {
for (int i = 0; i < numberOfMotors; i++) {
busVoltagePublishers[i].set(motors[i].getBusVoltage());
optionCurrentPublishers[i].set(motors[i].getOutputCurrent());
stickyFaultPublisher[i].set(motors[i].getStickyFaults());
// TODO: Get motor sticky fault publishing working again
// stickyFaultPublisher[i].set(motors[i].getStickyFaults());
motorTemperaturePublishers[i].set(motors[i].getMotorTemperature());
motorEncoderPublishers[i].set(motors[i].getEncoder().getPosition());
}
Expand Down
186 changes: 91 additions & 95 deletions src/main/java/frc/robot/subsystems/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,23 @@

package frc.robot.subsystems;

import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.SparkPIDController.ArbFFUnits;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.config.AbsoluteEncoderConfig;
import com.revrobotics.spark.config.ClosedLoopConfig;
import com.revrobotics.spark.config.SparkBaseConfig;
import com.revrobotics.spark.config.SparkMaxConfig;
import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor;
import com.revrobotics.spark.SparkClosedLoopController.ArbFFUnits;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode;

import java.util.function.Supplier;

import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.SparkAbsoluteEncoder;
import com.revrobotics.SparkPIDController;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.spark.SparkAbsoluteEncoder;
import com.revrobotics.spark.SparkClosedLoopController;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.ArmFeedforward;
Expand All @@ -34,13 +41,11 @@
public class Arm extends SubsystemBase {
// Arm
/** this is the right arm motor */
private final CANSparkMax leaderArmMotor = new CANSparkMax(ArmConstants.LEFT_MOTOR_ID, MotorType.kBrushless);
private final CANSparkMax followerArmMotor = new CANSparkMax(ArmConstants.RIGHT_MOTOR_ID, MotorType.kBrushless);
private final SparkMax leaderArmMotor = new SparkMax(ArmConstants.LEFT_MOTOR_ID, MotorType.kBrushless);
private final SparkMax followerArmMotor = new SparkMax(ArmConstants.RIGHT_MOTOR_ID, MotorType.kBrushless);

private final SparkAbsoluteEncoder armAbsoluteEncoder = leaderArmMotor
.getAbsoluteEncoder(SparkAbsoluteEncoder.Type.kDutyCycle);

private final SparkPIDController armPIDController = leaderArmMotor.getPIDController();
private final SparkAbsoluteEncoder armAbsoluteEncoder = leaderArmMotor.getAbsoluteEncoder();
private final SparkClosedLoopController armPIDController = leaderArmMotor.getClosedLoopController();

private ArmFeedforward extendedArmFeedForward = new ArmFeedforward(ArmConstants.EXTENDED_KS, ArmConstants.EXTENDED_KG, ArmConstants.EXTENDED_KV);
private ArmFeedforward retractedArmFeedForward = new ArmFeedforward(ArmConstants.RETRACTED_KS, ArmConstants.RETRACTED_KG, ArmConstants.RETRACTED_KV);
Expand All @@ -56,13 +61,12 @@ public class Arm extends SubsystemBase {

// Elevator
/** the right motor */
private final CANSparkMax leaderElevatorMotor = new CANSparkMax(ElevatorConstants.RIGHT_MOTOR_ID, MotorType.kBrushless);
private final SparkMax leaderElevatorMotor = new SparkMax(ElevatorConstants.RIGHT_MOTOR_ID, MotorType.kBrushless);
/** the left motor */
private final CANSparkMax followerElevatorMotor = new CANSparkMax(ElevatorConstants.LEFT_MOTOR_ID, MotorType.kBrushless);
private final SparkMax followerElevatorMotor = new SparkMax(ElevatorConstants.LEFT_MOTOR_ID, MotorType.kBrushless);

private final RelativeEncoder elevatorEncoder = leaderElevatorMotor.getEncoder();

private final SparkPIDController elevatorPIDController = leaderElevatorMotor.getPIDController();
private final SparkClosedLoopController elevatorPIDController = leaderElevatorMotor.getClosedLoopController();

InterpolatingDoubleTreeMap elevatorKSTable = new InterpolatingDoubleTreeMap();
InterpolatingDoubleTreeMap elevatorKGTable = new InterpolatingDoubleTreeMap();
Expand All @@ -83,40 +87,42 @@ public class Arm extends SubsystemBase {

/** Creates a new Arm. */
public Arm() {
// Applied to motors that need slow status updates
// TODO: Get this to actually do something
SparkBaseConfig slowPeriodicConfig = new SparkMaxConfig();

// setup arm motors
ClosedLoopConfig armControllerConfig = new ClosedLoopConfig()
.p(ArmConstants.KP)
.i(ArmConstants.KI)
.d(ArmConstants.KD)
.outputRange(ArmConstants.kMinOutput, ArmConstants.kMaxOutput)
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
.positionWrappingEnabled(false);

leaderArmMotor.restoreFactoryDefaults();
leaderArmMotor.setIdleMode(IdleMode.kBrake);
leaderArmMotor.setSmartCurrentLimit(ArmConstants.MAX_AMPERAGE);
leaderArmMotor.setInverted(true);
AbsoluteEncoderConfig armAbsoluteEncoderConfig = new AbsoluteEncoderConfig()
.positionConversionFactor(ArmConstants.ABS_POSITION_CONVERSION_FACTOR)
.velocityConversionFactor(ArmConstants.ABS_VELOCITY_CONVERSION_FACTOR)
.inverted(true)
.zeroOffset(ArmConstants.ARM_OFFSET);

followerArmMotor.restoreFactoryDefaults();
followerArmMotor.setIdleMode(IdleMode.kBrake);
followerArmMotor.setSmartCurrentLimit(ArmConstants.MAX_AMPERAGE);
followerArmMotor.follow(leaderArmMotor, true);
SparkBaseConfig armMotorConfig = new SparkMaxConfig()
.idleMode(IdleMode.kBrake)
.smartCurrentLimit(ArmConstants.MAX_AMPERAGE);

followerArmMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus0, 1000);
followerArmMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus1, 1000);
followerArmMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus3, 1000);
followerArmMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus4, 1000);
followerArmMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus5, 1000);
followerArmMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus6, 1000);
followerArmMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus7, 1000);
followerArmMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus2, 1000);
SparkBaseConfig leaderArmMotorConfig = new SparkMaxConfig()
.apply(armMotorConfig)
.inverted(true)
.apply(armControllerConfig)
.apply(armAbsoluteEncoderConfig);

// setup the arm pid controller
armPIDController.setP(ArmConstants.KP);
armPIDController.setI(ArmConstants.KI);
armPIDController.setD(ArmConstants.KD);
armPIDController.setOutputRange(ArmConstants.kMinOutput, ArmConstants.kMaxOutput);
armPIDController.setFeedbackDevice(armAbsoluteEncoder);
armPIDController.setPositionPIDWrappingEnabled(false);
SparkBaseConfig followerArmMotorConfig = new SparkMaxConfig()
.apply(armMotorConfig)
.follow(leaderArmMotor, true)
.apply(slowPeriodicConfig);

// setup the arm encoder
armAbsoluteEncoder.setPositionConversionFactor(ArmConstants.ABS_POSITION_CONVERSION_FACTOR);
armAbsoluteEncoder.setVelocityConversionFactor(ArmConstants.ABS_VELOCITY_CONVERSION_FACTOR);
armAbsoluteEncoder.setInverted(true);
armAbsoluteEncoder.setZeroOffset(ArmConstants.ARM_OFFSET);
leaderArmMotor.configure(leaderArmMotorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
followerArmMotor.configure(followerArmMotorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);

armTarget = armAbsoluteEncoder.getPosition();

Expand All @@ -136,48 +142,33 @@ public Arm() {
armAngleBasedOnDistanceRetracted.put(4.29, 38.3);
armAngleBasedOnDistanceRetracted.put(4.31, 37.6);

followerElevatorMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus0, 1000);
followerElevatorMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus1, 1000);
followerElevatorMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus3, 1000);
followerElevatorMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus4, 1000);
followerElevatorMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus5, 1000);
followerElevatorMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus6, 1000);
followerElevatorMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus7, 1000);
followerElevatorMotor.setPeriodicFramePeriod(CANSparkMax.PeriodicFrame.kStatus2, 1000);
// setup elevator motors
leaderElevatorMotor.restoreFactoryDefaults();
leaderElevatorMotor.setIdleMode(IdleMode.kBrake);
leaderElevatorMotor.setSmartCurrentLimit(ElevatorConstants.MAX_AMPERAGE);
leaderElevatorMotor.setInverted(true);
ClosedLoopConfig elevatorControllerConfig = new ClosedLoopConfig()
.p(ElevatorConstants.KP)
.i(ElevatorConstants.KI)
.d(ElevatorConstants.KD)
.outputRange(ElevatorConstants.kMinOutput, ElevatorConstants.kMaxOutput);

followerElevatorMotor.restoreFactoryDefaults();
followerElevatorMotor.setIdleMode(IdleMode.kBrake);
followerElevatorMotor.setSmartCurrentLimit(ElevatorConstants.MAX_AMPERAGE);
followerElevatorMotor.follow(leaderArmMotor, true);
SparkBaseConfig elevatorMotorConfig = new SparkMaxConfig()
.smartCurrentLimit(ElevatorConstants.MAX_AMPERAGE)
.idleMode(IdleMode.kBrake);

elevatorTarget = elevatorEncoder.getPosition();
SparkBaseConfig leaderElevatorMotorConfig = new SparkMaxConfig()
.apply(elevatorMotorConfig)
.inverted(true);

SparkBaseConfig followerElevatorMotorConfig = new SparkMaxConfig()
.apply(elevatorMotorConfig)
.follow(leaderArmMotor, true)
.apply(slowPeriodicConfig);

elevatorPIDController.setP(ElevatorConstants.KP);
elevatorPIDController.setI(ElevatorConstants.KI);
elevatorPIDController.setD(ElevatorConstants.KD);
elevatorPIDController.setOutputRange(ElevatorConstants.kMinOutput, ElevatorConstants.kMaxOutput);
leaderElevatorMotor.configure(leaderElevatorMotorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
followerElevatorMotor.configure(followerElevatorMotorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);

elevatorTarget = elevatorEncoder.getPosition();

time.reset();
time.start();

burnFlash();
}

private void burnFlash() {
Timer.delay(0.005);
leaderArmMotor.burnFlash();
Timer.delay(0.005);
followerArmMotor.burnFlash();
Timer.delay(0.005);
leaderElevatorMotor.burnFlash();
Timer.delay(0.005);
followerElevatorMotor.burnFlash();
Timer.delay(0.005);
}

private ElevatorFeedforward getElevatorFeedforward() {
Expand Down Expand Up @@ -316,29 +307,34 @@ public Command ArmDefaultCommand(Supplier<Double> armVelocity, Supplier<Double>

public Command ToggleBrakeModes() {
return this.runOnce(() -> {
if (leaderArmMotor.getIdleMode() == IdleMode.kBrake) {
CoffeeCoder1 marked this conversation as resolved.
Show resolved Hide resolved
leaderArmMotor.setIdleMode(IdleMode.kCoast);
followerArmMotor.setIdleMode(IdleMode.kCoast);
SparkBaseConfig newArmConfig = new SparkMaxConfig();
if (leaderArmMotor.configAccessor.getIdleMode() == IdleMode.kBrake) {
newArmConfig.idleMode(IdleMode.kCoast);
} else {
leaderArmMotor.setIdleMode(IdleMode.kBrake);
followerArmMotor.setIdleMode(IdleMode.kBrake);
newArmConfig.idleMode(IdleMode.kBrake);
}
if (leaderElevatorMotor.getIdleMode() == IdleMode.kBrake) {
leaderElevatorMotor.setIdleMode(IdleMode.kCoast);
followerElevatorMotor.setIdleMode(IdleMode.kCoast);
leaderArmMotor.configure(newArmConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
followerArmMotor.configure(newArmConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);

SparkBaseConfig newElevatorConfig = new SparkMaxConfig();
if (leaderElevatorMotor.configAccessor.getIdleMode() == IdleMode.kBrake) {
newElevatorConfig.idleMode(IdleMode.kCoast);
} else {
leaderElevatorMotor.setIdleMode(IdleMode.kBrake);
followerElevatorMotor.setIdleMode(IdleMode.kBrake);
newElevatorConfig.idleMode(IdleMode.kBrake);
}
leaderElevatorMotor.configure(newElevatorConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
followerElevatorMotor.configure(newElevatorConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
}).ignoringDisable(true);
}

public Command EnableBrakeMode() {
return this.runOnce(() -> {
leaderArmMotor.setIdleMode(IdleMode.kBrake);
followerArmMotor.setIdleMode(IdleMode.kBrake);
leaderElevatorMotor.setIdleMode(IdleMode.kBrake);
followerElevatorMotor.setIdleMode(IdleMode.kBrake);
SparkBaseConfig newConfig = new SparkMaxConfig()
.idleMode(IdleMode.kBrake);
leaderArmMotor.configure(newConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
followerArmMotor.configure(newConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
leaderElevatorMotor.configure(newConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
followerElevatorMotor.configure(newConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
}).ignoringDisable(true);
}

Expand Down Expand Up @@ -368,7 +364,7 @@ public void periodic() {
double armFeedFowardValue = armFeedFoward.calculate(Units.degreesToRadians(currentArmTarget), velocity);
// System.out.println("arm feed foward: " + armFeedFowardValue);

armPIDController.setReference(currentArmTarget, CANSparkMax.ControlType.kPosition, 0, armFeedFowardValue, ArbFFUnits.kVoltage);
armPIDController.setReference(currentArmTarget, SparkMax.ControlType.kPosition, 0, armFeedFowardValue, ArbFFUnits.kVoltage);
lastAcutalArmTarget = currentArmTarget;
}
if (!ElevatorConstants.KILL_IT_ALL) {
Expand All @@ -384,7 +380,7 @@ public void periodic() {

if (currentElevatorTarget != lastAcutalElevatorTarget) {
double elevatorFeedFowardValue = getElevatorFeedforward().calculate(elevatorEncoder.getVelocity());
elevatorPIDController.setReference(currentElevatorTarget, CANSparkMax.ControlType.kPosition, 0, elevatorFeedFowardValue, ArbFFUnits.kVoltage);
elevatorPIDController.setReference(currentElevatorTarget, SparkMax.ControlType.kPosition, 0, elevatorFeedFowardValue, ArbFFUnits.kVoltage);
lastAcutalElevatorTarget = currentElevatorTarget;
}

Expand Down
41 changes: 15 additions & 26 deletions src/main/java/frc/robot/subsystems/Climber.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,50 +4,39 @@

package frc.robot.subsystems;

import com.revrobotics.CANSparkMax;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.config.SparkBaseConfig;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
import com.revrobotics.spark.config.SparkMaxConfig;

import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

public class Climber extends SubsystemBase {
private final CANSparkMax rightClimber = new CANSparkMax(Constants.ClimberConstants.RIGHT_CLIMBER_PORT, MotorType.kBrushless);
private final SparkMax rightClimber = new SparkMax(Constants.ClimberConstants.RIGHT_CLIMBER_PORT, MotorType.kBrushless);
private final RelativeEncoder rightClimberEncoder;

private final CANSparkMax leftClimber = new CANSparkMax(Constants.ClimberConstants.LEFT_CLIMBER_PORT, MotorType.kBrushless);
private final SparkMax leftClimber = new SparkMax(Constants.ClimberConstants.LEFT_CLIMBER_PORT, MotorType.kBrushless);
private final RelativeEncoder leftClimberEncoder;

/** Creates a new Climber. */
public Climber() {
rightClimber.restoreFactoryDefaults();
SparkBaseConfig motorConfig = new SparkMaxConfig()
.idleMode(IdleMode.kBrake);

leftClimber.restoreFactoryDefaults();

rightClimber.setIdleMode(IdleMode.kBrake);
rightClimber.setInverted(true);

leftClimber.setIdleMode(IdleMode.kBrake);
leftClimber.configure(motorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
rightClimber.configure(motorConfig.inverted(true), ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);

leftClimberEncoder = leftClimber.getEncoder();
rightClimberEncoder = rightClimber.getEncoder();
leftClimberEncoder.setPosition(0.0);
rightClimberEncoder.setPosition(0.0);

// balanceController.setSetpoint(0.0);

burnFlash();
}

private void burnFlash() {
Timer.delay(0.005);
leftClimber.burnFlash();
Timer.delay(0.005);
rightClimber.burnFlash();
Timer.delay(0.005);
}

public void setSpeed(double leftSpeed, double rightSpeed) {
Expand Down Expand Up @@ -88,7 +77,7 @@ public double getPositionLeftMotor() {
@Override
public void periodic() {}

public CANSparkMax[] getMotors() {
return new CANSparkMax[] { leftClimber, rightClimber };
public SparkMax[] getMotors() {
return new SparkMax[] { leftClimber, rightClimber };
}
}
Loading
Loading