Skip to content

Commit

Permalink
Merge pull request #21 from Pearadox/nazeerbranch4
Browse files Browse the repository at this point in the history
Fix burn flash issue
  • Loading branch information
nh17000 authored Feb 7, 2024
2 parents 63fc0cd + 48af46f commit 9e1004c
Show file tree
Hide file tree
Showing 2 changed files with 52 additions and 44 deletions.
79 changes: 41 additions & 38 deletions src/main/java/frc/lib/drivers/PearadoxSparkMax.java
Original file line number Diff line number Diff line change
@@ -1,7 +1,3 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.lib.drivers;

import com.revrobotics.CANSparkMax;
Expand All @@ -12,49 +8,56 @@
public class PearadoxSparkMax extends CANSparkMax {
/**
* Creates a new CANSparkMax with the necessary configurations.
* @param deviceId The device ID.
* @param m The motor type (Brushed/Brushless).
* @param mode The idle mode (kBrake/kCoast).
* @param limit The current limit.
* @param isInverted The invert type of the motor.
*
* @param deviceId The device ID.
* @param motorType The motor type (Brushed/Brushless).
* @param idleMode The idle mode (kBrake/kCoast).
* @param currentLimit The current limit.
* @param isInverted The invert type of the motor.
* @param following The CANSparkMax of the motor this motor should follow
*/
public PearadoxSparkMax(int deviceId, MotorType m, IdleMode mode, int limit, boolean isInverted){
super(deviceId, m);
public PearadoxSparkMax(int deviceId, MotorType motorType, IdleMode idleMode, int currentLimit, boolean isInverted,
CANSparkMax following, double rampRate) {
super(deviceId, motorType);
this.restoreFactoryDefaults();
this.setSmartCurrentLimit(limit);
this.setSmartCurrentLimit(currentLimit);
this.setInverted(isInverted);
this.setIdleMode(mode);
this.setIdleMode(idleMode);
if (following != null) {
this.follow(following);
}
this.setOpenLoopRampRate(rampRate);
this.burnFlash();
String key = "Spark " + this.getDeviceId() + " Flashes";
Preferences.setDouble(key, Preferences.getDouble(key, 0) + 1);
}

/**
* Creates a new CANSparkMax with the necessary motor and PID configurations.
* @param deviceId The device ID.
* @param m The motor type (Brushed/Brushless).
* @param mode The idle mode (kBrake/kCoast).
* @param limit The current limit.
* @param isInverted The invert type of the motor.
* @param kP The proportional gain value.
* @param kI The integral gain value.
* @param kD The derivative gain value.
* @param minOutput Reverse power minimum to allow the controller to output
* @param maxOutput Reverse power maximum to allow the controller to output
* Creates a new CANSparkMax with the necessary configurations.
*
* @param deviceId The device ID.
* @param motorType The motor type (Brushed/Brushless).
* @param idleMode The idle mode (kBrake/kCoast).
* @param currentLimit The current limit.
* @param isInverted The invert type of the motor.
*/
public PearadoxSparkMax(int deviceId, MotorType m, IdleMode mode, int limit, boolean isInverted,
double kP, double kI, double kD, double minOutput, double maxOutput){
super(deviceId, m);
this.restoreFactoryDefaults();
this.setSmartCurrentLimit(limit);
this.setInverted(isInverted);
this.setIdleMode(mode);
this.getPIDController().setP(kP, 0);
this.getPIDController().setI(kI, 0);
this.getPIDController().setD(kD, 0);
this.getPIDController().setOutputRange(minOutput, maxOutput, 0);
this.burnFlash();
String key = "Spark " + this.getDeviceId() + " Flashes";
Preferences.setDouble(key, Preferences.getDouble(key, 0) + 1);
public PearadoxSparkMax(int deviceId, MotorType motorType, IdleMode idleMode, int currentLimit,
boolean isInverted) {
this(deviceId, motorType, idleMode, currentLimit, isInverted, null, 0);
}

/**
* Creates a new CANSparkMax with the necessary configurations.
*
* @param deviceId The device ID.
* @param motorType The motor type (Brushed/Brushless).
* @param idleMode The idle mode (kBrake/kCoast).
* @param currentLimit The current limit.
* @param isInverted The invert type of the motor.
*/
public PearadoxSparkMax(int deviceId, MotorType motorType, IdleMode idleMode, int currentLimit,
boolean isInverted, double rampRate) {
this(deviceId, motorType, idleMode, currentLimit, isInverted, null, rampRate);
}

}
17 changes: 11 additions & 6 deletions src/main/java/frc/robot/subsystems/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,26 +11,27 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
// import edu.wpi.first.wpilibj.drive.RobotDriveBase.MotorType;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

public class Drivetrain extends SubsystemBase {
private final PearadoxSparkMax leftFront = new PearadoxSparkMax(DrivetrainConstants.leftFrontID,
MotorType.kBrushless, PearadoxSparkMax.IdleMode.kBrake, DrivetrainConstants.limit, false);
MotorType.kBrushless, PearadoxSparkMax.IdleMode.kBrake, DrivetrainConstants.limit, true);

private final PearadoxSparkMax rightFront = new PearadoxSparkMax(DrivetrainConstants.rightFrontID,
MotorType.kBrushless, PearadoxSparkMax.IdleMode.kBrake, DrivetrainConstants.limit, true);
MotorType.kBrushless, PearadoxSparkMax.IdleMode.kBrake, DrivetrainConstants.limit, false);

private final PearadoxSparkMax leftBack = new PearadoxSparkMax(DrivetrainConstants.leftBackID,
MotorType.kBrushless, PearadoxSparkMax.IdleMode.kBrake, DrivetrainConstants.limit, false);
MotorType.kBrushless, PearadoxSparkMax.IdleMode.kBrake, DrivetrainConstants.limit, true, leftFront, 0);

private final PearadoxSparkMax rightBack = new PearadoxSparkMax(DrivetrainConstants.rightBackID,
MotorType.kBrushless, PearadoxSparkMax.IdleMode.kBrake, DrivetrainConstants.limit, true);
MotorType.kBrushless, PearadoxSparkMax.IdleMode.kBrake, DrivetrainConstants.limit, false, rightFront, 0);

/** Creates a new Drivetrain. */
DifferentialDrive m_drivetrain;

public Drivetrain() {
leftBack.follow(leftFront);
rightBack.follow(rightFront);
// leftBack.follow(leftFront);
// rightBack.follow(rightFront);

m_drivetrain = new DifferentialDrive(leftFront, rightFront);
}
Expand All @@ -42,5 +43,9 @@ public void arcadeDrive(double throttle, double twist) {
@Override
public void periodic() {
// This method will be called once per scheduler run
SmartDashboard.putNumber("Left Front", leftFront.getOutputCurrent());
SmartDashboard.putNumber("Left Back", leftBack.getOutputCurrent());
SmartDashboard.putNumber("Right Front", rightFront.getOutputCurrent());
SmartDashboard.putNumber("Right Back", rightBack.getOutputCurrent());
}
}

0 comments on commit 9e1004c

Please sign in to comment.