Skip to content
This repository was archived by the owner on Feb 16, 2026. It is now read-only.
Merged
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
8 changes: 4 additions & 4 deletions src/main/java/swervelib/motors/SparkFlexSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ public class SparkFlexSwerve extends SwerveMotor
*/
public RelativeEncoder encoder;
/**
* Absolute encoder attached to the SparkMax (if exists)
* Absolute encoder attached to the SparkFlex (if exists)
*/
public SwerveAbsoluteEncoder absoluteEncoder;
/**
Expand Down Expand Up @@ -93,7 +93,7 @@ public SparkFlexSwerve(SparkFlex motor, boolean isDriveMotor, DCMotor motorType)
cfg.closedLoop.feedbackSensor(FeedbackSensor.kPrimaryEncoder); // Configure feedback of the PID controller as the integrated encoder.

// Spin off configurations in a different thread.
// configureSparkMax(() -> motor.setCANTimeout(0)); // Commented out because it prevents feedback.
// configureSparkFlex(() -> motor.setCANTimeout(0)); // Commented out because it prevents feedback.
failureConfiguring = new Alert("Motors",
"Failure configuring motor " +
motor.getDeviceId(),
Expand All @@ -109,7 +109,7 @@ public SparkFlexSwerve(SparkFlex motor, boolean isDriveMotor, DCMotor motorType)
/**
* Initialize the {@link SwerveMotor} as a {@link SparkFlex} connected to a Brushless Motor.
*
* @param id CAN ID of the SparkMax.
* @param id CAN ID of the SparkFlex.
* @param isDriveMotor Is the motor being initialized a drive motor?
* @param motorType {@link DCMotor} which the {@link SparkFlex} is attached to.
*/
Expand Down Expand Up @@ -139,7 +139,7 @@ private void configureSparkFlex(Supplier<REVLibError> config)
/**
* Get the current configuration of the {@link SparkFlex}
*
* @return {@link SparkMaxConfig}
* @return {@link SparkFlexConfig}
*/
public SparkFlexConfig getConfig()
{
Expand Down
9 changes: 4 additions & 5 deletions src/main/java/swervelib/motors/TalonSRXSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced;
import com.ctre.phoenix.motorcontrol.can.TalonSRXConfiguration;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import com.ctre.phoenix6.hardware.TalonFX;
import edu.wpi.first.math.system.plant.DCMotor;
import swervelib.encoders.SwerveAbsoluteEncoder;
import swervelib.math.SwerveMath;
Expand All @@ -26,7 +25,7 @@ public class TalonSRXSwerve extends SwerveMotor
*/
private final boolean factoryDefaultOccurred = false;
/**
* Current TalonFX configuration.
* Current TalonSRX configuration.
*/
private final TalonSRXConfiguration configuration = new TalonSRXConfiguration();
/**
Expand All @@ -46,7 +45,7 @@ public class TalonSRXSwerve extends SwerveMotor
*/
private ConversionFactorsJson moduleConversionFactors;
/**
* If the TalonFX configuration has changed.
* If the TalonSRX configuration has changed.
*/
private boolean configChanged = true;
/**
Expand Down Expand Up @@ -78,7 +77,7 @@ public TalonSRXSwerve(WPI_TalonSRX motor, boolean isDriveMotor, DCMotor motorTyp
*
* @param id ID of the TalonSRX on the canbus.
* @param isDriveMotor Whether the motor is a drive or steering motor.
* @param motorType {@link DCMotor} which the {@link TalonFX} is attached to.
* @param motorType {@link DCMotor} which the {@link TalonSRX} is attached to.
*/
public TalonSRXSwerve(int id, boolean isDriveMotor, DCMotor motorType)
{
Expand Down Expand Up @@ -473,4 +472,4 @@ public boolean isAttachedAbsoluteEncoder()
{
return absoluteEncoder;
}
}
}
6 changes: 3 additions & 3 deletions src/main/java/swervelib/motors/ThriftyNovaSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ public class ThriftyNovaSwerve extends SwerveMotor
{

/**
* SparkMAX Instance.
* ThriftyNova Instance.
*/
private ThriftyNova motor;
/**
Expand Down Expand Up @@ -66,7 +66,7 @@ public class ThriftyNovaSwerve extends SwerveMotor
/**
* Initialize the swerve motor.
*
* @param motor The SwerveMotor as a SparkMax object.
* @param motor The SwerveMotor as a ThriftyNova object.
* @param isDriveMotor Is the motor being initialized a drive motor?
* @param motorType {@link DCMotor} controlled by the {@link ThriftyNova}
*/
Expand Down Expand Up @@ -96,7 +96,7 @@ public ThriftyNovaSwerve(ThriftyNova motor, boolean isDriveMotor, DCMotor motorT
/**
* Initialize the {@link SwerveMotor} as a {@link ThriftyNova} connected to a Brushless Motor.
*
* @param id CAN ID of the SparkMax.
* @param id CAN ID of the ThriftyNova.
* @param isDriveMotor Is the motor being initialized a drive motor?
* @param motor {@link DCMotor} controlled by the {@link ThriftyNova}
*/
Expand Down