Skip to content

Commit

Permalink
Use of SparkFlex
Browse files Browse the repository at this point in the history
  • Loading branch information
Java4First committed Feb 16, 2024
1 parent db5a46f commit 70dc256
Showing 1 changed file with 21 additions and 21 deletions.
42 changes: 21 additions & 21 deletions src/main/java/frc/robot/subsystems/drive/ModuleIOSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@

import com.revrobotics.AbsoluteEncoder;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkFlex;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.CANSparkLowLevel.PeriodicFrame;
import com.revrobotics.CANSparkMax;
Expand Down Expand Up @@ -44,7 +45,7 @@ public class ModuleIOSparkMax implements ModuleIO {
private static final double DRIVE_GEAR_RATIO = (45.0 * 22) / (SWERVE_PINION_TEETH * 15);
private static final double TURN_GEAR_RATIO = (9424.0 / 203); // Rev Steering

private final CANSparkMax driveSparkMax;
private final CANSparkFlex driveSparkMax;
private final CANSparkMax turnSparkMax;

private final RelativeEncoder driveEncoder;
Expand All @@ -65,28 +66,29 @@ public ModuleIOSparkMax(int index) {
m_index = index;
switch (index) {
case 0: // FL
driveSparkMax = new CANSparkMax(1, MotorType.kBrushless);
driveSparkMax = new CANSparkFlex(1, MotorType.kBrushless);
turnSparkMax = new CANSparkMax(2, MotorType.kBrushless);
turnAbsoluteEncoder = turnSparkMax.getAbsoluteEncoder(SparkAbsoluteEncoder.Type.kDutyCycle);
absoluteEncoderOffset = new Rotation2d(-1.57); // MUST BE CALIBRATED
absoluteEncoderOffset = new Rotation2d(Units.degreesToRadians(-90.0)); // MUST BE CALIBRATED
break;
case 1: // FR
driveSparkMax = new CANSparkMax(5, MotorType.kBrushless);
driveSparkMax = new CANSparkFlex(5, MotorType.kBrushless);
turnSparkMax = new CANSparkMax(6, MotorType.kBrushless);
turnAbsoluteEncoder = turnSparkMax.getAbsoluteEncoder(SparkAbsoluteEncoder.Type.kDutyCycle);
absoluteEncoderOffset = new Rotation2d(3.14); // MUST BE CALIBRATED
absoluteEncoderOffset =
new Rotation2d(Units.degreesToRadians(-180.0)); // MUST BE CALIBRATED
break;
case 2: // BL
driveSparkMax = new CANSparkMax(3, MotorType.kBrushless);
driveSparkMax = new CANSparkFlex(3, MotorType.kBrushless);
turnSparkMax = new CANSparkMax(4, MotorType.kBrushless);
turnAbsoluteEncoder = turnSparkMax.getAbsoluteEncoder(SparkAbsoluteEncoder.Type.kDutyCycle);
absoluteEncoderOffset = new Rotation2d(0); // MUST BE CALIBRATED
absoluteEncoderOffset = new Rotation2d(Units.degreesToRadians(0.0)); // MUST BE CALIBRATED
break;
case 3: // BR
driveSparkMax = new CANSparkMax(7, MotorType.kBrushless);
driveSparkMax = new CANSparkFlex(7, MotorType.kBrushless);
turnSparkMax = new CANSparkMax(8, MotorType.kBrushless);
turnAbsoluteEncoder = turnSparkMax.getAbsoluteEncoder(SparkAbsoluteEncoder.Type.kDutyCycle);
absoluteEncoderOffset = new Rotation2d(1.57); // MUST BE CALIBRATED
absoluteEncoderOffset = new Rotation2d(Units.degreesToRadians(90.0)); // MUST BE CALIBRATED
break;
default:
throw new RuntimeException("Invalid module index");
Expand All @@ -108,7 +110,7 @@ public ModuleIOSparkMax(int index) {
turnSparkMax.enableVoltageCompensation(12.0);

driveEncoder.setPosition(0.0);
driveEncoder.setMeasurementPeriod(10);
driveEncoder.setMeasurementPeriod(15);
driveEncoder.setAverageDepth(2);

turnRelativeEncoder.setPosition(0.0);
Expand Down Expand Up @@ -143,30 +145,28 @@ public void updateInputs(ModuleIOInputs inputs) {

/* Original */
// inputs.turnAbsolutePosition =
// new Rotation2d(
// turnAbsoluteEncoder.getVoltage() / RobotController.getVoltage5V() * 2.0 *
// new Rotation2d(
// turnAbsoluteEncoder.getVoltage() / RobotController.getVoltage5V() * 2.0 *
// Math.PI)
// .minus(absoluteEncoderOffset);
// .minus(absoluteEncoderOffset);

/* For Calibration of Offsets */
// inputs.turnAbsolutePosition = new Rotation2d(turnAbsoluteEncoder.getPosition() * 2.0 *
// inputs.turnAbsolutePosition = new
// Rotation2d(turnAbsoluteEncoder.getPosition() * 2.0 *
// Math.PI);
// SmartDashboard.putNumber(
// "turnAbsolutePosition[" + m_index + "]", inputs.turnAbsolutePosition.getDegrees());
// "turnAbsolutePosition[" + m_index + "]",
// inputs.turnAbsolutePosition.getDegrees());

/* Our Version */
/*
inputs.turnAbsolutePosition =
new Rotation2d(turnAbsoluteEncoder.getPosition() * 2.0 * Math.PI)
.minus(absoluteEncoderOffset); */

inputs.turnAbsolutePosition =
Rotation2d.fromRotations(turnAbsoluteEncoder.getPosition()).minus(absoluteEncoderOffset);

SmartDashboard.putNumber(
"turnAbsolutePosition[" + m_index + "]", inputs.turnAbsolutePosition.getDegrees());
inputs.turnPosition =
Rotation2d.fromRotations(turnRelativeEncoder.getPosition() / TURN_GEAR_RATIO);
SmartDashboard.putNumber(
"turnRelativePosition[" + m_index + "]", inputs.turnPosition.getDegrees());
inputs.turnVelocityRadPerSec =
Units.rotationsPerMinuteToRadiansPerSecond(turnRelativeEncoder.getVelocity())
/ TURN_GEAR_RATIO;
Expand Down

0 comments on commit 70dc256

Please sign in to comment.