Skip to content

Commit ec8acaf

Browse files
Change motors in DriveSubsystem to Spark Flexes (#18)
* Change motors in DriveSubsystem to Spark Flexes * Oakestra Constants
1 parent 742aead commit ec8acaf

File tree

2 files changed

+21
-21
lines changed

2 files changed

+21
-21
lines changed

src/main/java/frc/robot/Constants.java

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -47,20 +47,20 @@ public static final class IOConstants {
4747

4848
public static final class DriveConstants {
4949
// TODO: set motor and encoder constants
50-
public static final int kFrontLeftDriveMotorPort = 4;
51-
public static final int kRearLeftDriveMotorPort = 5;
52-
public static final int kFrontRightDriveMotorPort = 12;
50+
public static final int kFrontLeftDriveMotorPort = 32;
51+
public static final int kRearLeftDriveMotorPort = 29;
52+
public static final int kFrontRightDriveMotorPort = 36;
5353
public static final int kRearRightDriveMotorPort = 34;
5454

55-
public static final int kFrontLeftTurningMotorPort = 11;
56-
public static final int kRearLeftTurningMotorPort = 9;
57-
public static final int kFrontRightTurningMotorPort = 36;
58-
public static final int kRearRightTurningMotorPort = 16;
55+
public static final int kFrontLeftTurningMotorPort = 28;
56+
public static final int kRearLeftTurningMotorPort = 22;
57+
public static final int kFrontRightTurningMotorPort = 37;
58+
public static final int kRearRightTurningMotorPort = 26;
5959

60-
public static final int kFrontLeftTurningEncoderPort = 19;
61-
public static final int kRearLeftTurningEncoderPort = 20;
62-
public static final int kFrontRightTurningEncoderPort = 18;
63-
public static final int kRearRightTurningEncoderPort = 17;
60+
public static final int kFrontLeftTurningEncoderPort = 5;
61+
public static final int kRearLeftTurningEncoderPort = 6;
62+
public static final int kFrontRightTurningEncoderPort = 3;
63+
public static final int kRearRightTurningEncoderPort = 4;
6464

6565
// TODO: Test motor orientations before driving on an actual robot
6666
public static final boolean kFrontLeftDriveMotorReversed = false;
@@ -116,7 +116,7 @@ public static final class VisionConstants {
116116
public static final Vector<N3> kOdometrySTDDevs = VecBuilder.fill(0.1, 0.1, 0.1);
117117
public static final Vector<N3> kVisionSTDDevs = VecBuilder.fill(0.7, 0.7, 999999);
118118

119-
public static final boolean kUseVision = true;
119+
public static final boolean kUseVision = false;
120120
}
121121

122122
public static final class ElevatorConstants {

src/main/java/frc/robot/subsystems/SwerveModule.java

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -5,12 +5,12 @@
55
package frc.robot.subsystems;
66

77
import com.ctre.phoenix6.hardware.CANcoder;
8+
import com.revrobotics.spark.SparkFlex;
89
import com.revrobotics.spark.SparkBase.PersistMode;
910
import com.revrobotics.spark.SparkBase.ResetMode;
1011
import com.revrobotics.spark.SparkLowLevel.MotorType;
11-
import com.revrobotics.spark.SparkMax;
12+
import com.revrobotics.spark.config.SparkFlexConfig;
1213
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
13-
import com.revrobotics.spark.config.SparkMaxConfig;
1414

1515
import edu.wpi.first.math.controller.PIDController;
1616
import edu.wpi.first.math.geometry.Rotation2d;
@@ -21,11 +21,11 @@
2121
import frc.robot.Robot;
2222

2323
public class SwerveModule {
24-
private final SparkMax m_driveMotor;
25-
private final SparkMax m_turningMotor;
24+
private final SparkFlex m_driveMotor;
25+
private final SparkFlex m_turningMotor;
2626

27-
private final SparkMaxConfig m_driveMotorConfig = new SparkMaxConfig();
28-
private final SparkMaxConfig m_turningMotorConfig = new SparkMaxConfig();
27+
private final SparkFlexConfig m_driveMotorConfig = new SparkFlexConfig();
28+
private final SparkFlexConfig m_turningMotorConfig = new SparkFlexConfig();
2929

3030
private final CANcoder m_turningEncoder;
3131

@@ -50,8 +50,8 @@ public SwerveModule(
5050
int turningMotorPort,
5151
int turningEncoderPort,
5252
boolean driveMotorReversed) {
53-
m_driveMotor = new SparkMax(driveMotorPort, MotorType.kBrushless);
54-
m_turningMotor = new SparkMax(turningMotorPort, MotorType.kBrushless);
53+
m_driveMotor = new SparkFlex(driveMotorPort, MotorType.kBrushless);
54+
m_turningMotor = new SparkFlex(turningMotorPort, MotorType.kBrushless);
5555
m_turningEncoder = new CANcoder(turningEncoderPort);
5656

5757
// converts default units to meters per second
@@ -97,7 +97,7 @@ public void setDesiredState(SwerveModuleState desiredState) {
9797
m_state.optimize(getEncoderAngle(m_turningEncoder));
9898
driveOutput = m_state.speedMetersPerSecond / DriveConstants.kMaxSpeedMetersPerSecond;
9999

100-
turnOutput = m_turningPIDController.calculate(getEncoderAngle(m_turningEncoder).getRadians(),
100+
turnOutput = -m_turningPIDController.calculate(getEncoderAngle(m_turningEncoder).getRadians(),
101101
m_state.angle.getRadians());
102102

103103
m_driveMotor.set(driveOutput);

0 commit comments

Comments
 (0)