Skip to content
Open
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
2 changes: 1 addition & 1 deletion lib199
25 changes: 11 additions & 14 deletions src/main/java/org/team199/robot2021/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@

import com.ctre.phoenix.sensors.AbsoluteSensorRange;
import com.ctre.phoenix.sensors.CANCoder;
import com.revrobotics.ControlType;
import com.revrobotics.CANPIDController;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMax.IdleMode;

Expand All @@ -30,7 +32,7 @@ public enum ModuleType {FL, FR, BL, BR};
private String moduleString;
private CANSparkMax drive, turn;
private CANCoder turnEncoder;
private PIDController drivePIDController;
private CANPIDController drivePIDController;
private ProfiledPIDController turnPIDController;
private TrapezoidProfile.Constraints turnConstraints;
private double driveModifier, maxSpeed, turnZero;
Expand Down Expand Up @@ -86,9 +88,12 @@ public SwerveModule(ModuleType type, CANSparkMax drive, CANSparkMax turn, CANCod
Constants.DriveConstants.kBackwardVels[arrIndex],
Constants.DriveConstants.kBackwardAccels[arrIndex]);

drivePIDController = new PIDController(2 * Constants.DriveConstants.drivekP[arrIndex],
Constants.DriveConstants.drivekI[arrIndex],
Constants.DriveConstants.drivekD[arrIndex]);
drivePIDController = drive.getPIDController();

drivePIDController.setP(Constants.DriveConstants.drivekP[arrIndex]);
drivePIDController.setI(Constants.DriveConstants.drivekI[arrIndex]);
drivePIDController.setD(Constants.DriveConstants.drivekD[arrIndex]);
drivePIDController.setOutputRange(-1, 1);


//System.out.println("Velocity Constant: " + (positionConstant / 60));
Expand Down Expand Up @@ -194,17 +199,9 @@ private void setSpeed(double speed) {

// Compute desired and actual speeds in m/s
double desiredSpeed = maxSpeed * speed * driveModifier;
double actualSpeed = getCurrentSpeed();
SmartDashboard.putNumber(moduleString + " Desired Speed (mps)", desiredSpeed);
SmartDashboard.putNumber(moduleString + " Actual Speed (mps)", actualSpeed);
double targetVoltage = (actualSpeed >= 0 ? forwardSimpleMotorFF :
backwardSimpleMotorFF).calculate(desiredSpeed, calculateAntiGravitationalA(pitchDegSupplier.get(), rollDegSupplier.get()));//clippedAcceleration);

// Use robot characterization as a simple physical model to account for internal resistance, frcition, etc.
// Add a PID adjustment for error correction (also "drives" the actual speed to the desired speed)
targetVoltage += drivePIDController.calculate(actualSpeed, desiredSpeed);
double appliedVoltage = MathUtil.clamp(targetVoltage / 12, -1, 1);
drive.set(appliedVoltage);

drivePIDController.setReference(desiredSpeed, ControlType.kVelocity);
}

/**
Expand Down