Skip to content

Commit

Permalink
Removed unfinished portion. Reformatted library.
Browse files Browse the repository at this point in the history
Signed-off-by: thenetworkgrinch <thenetworkgrinch@users.noreply.github.com>
  • Loading branch information
thenetworkgrinch committed Dec 18, 2024
1 parent 74a6812 commit cc0615c
Show file tree
Hide file tree
Showing 10 changed files with 121 additions and 190 deletions.
95 changes: 47 additions & 48 deletions src/main/java/swervelib/SwerveInputStream.java
Original file line number Diff line number Diff line change
Expand Up @@ -88,53 +88,6 @@ public class SwerveInputStream implements Supplier<ChassisSpeeds>
private SwerveInputMode currentMode = SwerveInputMode.ANGULAR_VELOCITY;


/**
* Drive modes to keep track of.
*/
enum SwerveInputMode
{
/**
* Translation only mode, does not allow for rotation and maintains current heading.
*/
TRANSLATION_ONLY,
/**
* Output based off angular velocity
*/
ANGULAR_VELOCITY,
/**
* Output based off of heading.
*/
HEADING,
/**
* Output based off of targeting.
*/
AIM
}

/**
* Copy the {@link SwerveInputStream} object.
*
* @return Clone of current {@link SwerveInputStream}
*/
public SwerveInputStream copy()
{
SwerveInputStream newStream = new SwerveInputStream(swerveDrive, controllerTranslationX, controllerTranslationY);
newStream.controllerOmega = controllerOmega;
newStream.controllerHeadingX = controllerHeadingX;
newStream.controllerHeadingY = controllerHeadingY;
newStream.axisDeadband = axisDeadband;
newStream.translationAxisScale = translationAxisScale;
newStream.omegaAxisScale = omegaAxisScale;
newStream.aimTarget = aimTarget;
newStream.headingEnabled = headingEnabled;
newStream.aimEnabled = aimEnabled;
newStream.currentMode = currentMode;
newStream.translationOnlyEnabled = translationOnlyEnabled;
newStream.lockedHeading = lockedHeading;
newStream.swerveController = swerveController;
return newStream;
}

/**
* Create a {@link SwerveInputStream} for an easy way to generate {@link ChassisSpeeds} from a driver controller.
*
Expand Down Expand Up @@ -193,6 +146,30 @@ public static SwerveInputStream of(SwerveDrive drive, DoubleSupplier x, DoubleSu
return new SwerveInputStream(drive, x, y);
}

/**
* Copy the {@link SwerveInputStream} object.
*
* @return Clone of current {@link SwerveInputStream}
*/
public SwerveInputStream copy()
{
SwerveInputStream newStream = new SwerveInputStream(swerveDrive, controllerTranslationX, controllerTranslationY);
newStream.controllerOmega = controllerOmega;
newStream.controllerHeadingX = controllerHeadingX;
newStream.controllerHeadingY = controllerHeadingY;
newStream.axisDeadband = axisDeadband;
newStream.translationAxisScale = translationAxisScale;
newStream.omegaAxisScale = omegaAxisScale;
newStream.aimTarget = aimTarget;
newStream.headingEnabled = headingEnabled;
newStream.aimEnabled = aimEnabled;
newStream.currentMode = currentMode;
newStream.translationOnlyEnabled = translationOnlyEnabled;
newStream.lockedHeading = lockedHeading;
newStream.swerveController = swerveController;
return newStream;
}

/**
* Add a rotation axis for Angular Velocity control
*
Expand Down Expand Up @@ -255,7 +232,6 @@ public SwerveInputStream scaleRotation(double scaleRotation)
return this;
}


/**
* Output {@link ChassisSpeeds} based on heading while the supplier is True.
*
Expand Down Expand Up @@ -573,4 +549,27 @@ public ChassisSpeeds get()

return new ChassisSpeeds(vxMetersPerSecond, vyMetersPerSecond, omegaRadiansPerSecond);
}

/**
* Drive modes to keep track of.
*/
enum SwerveInputMode
{
/**
* Translation only mode, does not allow for rotation and maintains current heading.
*/
TRANSLATION_ONLY,
/**
* Output based off angular velocity
*/
ANGULAR_VELOCITY,
/**
* Output based off of heading.
*/
HEADING,
/**
* Output based off of targeting.
*/
AIM
}
}
2 changes: 0 additions & 2 deletions src/main/java/swervelib/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,6 @@ public SwerveModule(int moduleNumber, SwerveModuleConfiguration moduleConfigurat

// Config angle motor/controller
angleMotor.configureIntegratedEncoder(moduleConfiguration.conversionFactors.angle.factor);
angleMotor.configureConversionFactor(moduleConfiguration.conversionFactors);
angleMotor.configurePIDF(moduleConfiguration.anglePIDF);
angleMotor.configurePIDWrapping(0, 360);
angleMotor.setInverted(moduleConfiguration.angleMotorInverted);
Expand All @@ -211,7 +210,6 @@ public SwerveModule(int moduleNumber, SwerveModuleConfiguration moduleConfigurat

// Config drive motor/controller
driveMotor.configureIntegratedEncoder(moduleConfiguration.conversionFactors.drive.factor);
driveMotor.configureConversionFactor(moduleConfiguration.conversionFactors);
driveMotor.configurePIDF(moduleConfiguration.velocityPIDF);
driveMotor.setInverted(moduleConfiguration.driveMotorInverted);
driveMotor.setMotorBrake(true);
Expand Down
10 changes: 5 additions & 5 deletions src/main/java/swervelib/encoders/CANCoderSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,11 +27,7 @@ public class CANCoderSwerve extends SwerveAbsoluteEncoder
/**
* Wait time for status frames to show up.
*/
public static double STATUS_TIMEOUT_SECONDS = Milliseconds.of(10).in(Seconds);
/**
* CANCoder with WPILib sendable and support.
*/
public CANcoder encoder;
public static double STATUS_TIMEOUT_SECONDS = Milliseconds.of(10).in(Seconds);
/**
* An {@link Alert} for if the CANCoder magnet field is less than ideal.
*/
Expand Down Expand Up @@ -60,6 +56,10 @@ public class CANCoderSwerve extends SwerveAbsoluteEncoder
* Angular velocity of the {@link CANcoder}.
*/
private final StatusSignal<AngularVelocity> velocity;
/**
* CANCoder with WPILib sendable and support.
*/
public CANcoder encoder;
/**
* {@link CANcoder} Configurator objet for this class.
*/
Expand Down
17 changes: 0 additions & 17 deletions src/main/java/swervelib/motors/SparkFlexSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@
import com.revrobotics.spark.SparkClosedLoopController;
import com.revrobotics.spark.SparkFlex;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
import com.revrobotics.spark.config.SparkFlexConfig;
Expand All @@ -25,7 +24,6 @@
import java.util.function.Supplier;
import swervelib.encoders.SwerveAbsoluteEncoder;
import swervelib.parser.PIDFConfig;
import swervelib.parser.json.modules.ConversionFactorsJson;
import swervelib.telemetry.SwerveDriveTelemetry;

/**
Expand Down Expand Up @@ -74,15 +72,6 @@ public class SparkFlexSwerve extends SwerveMotor
* Configuration object for {@link SparkFlex} motor.
*/
private SparkFlexConfig cfg = new SparkFlexConfig();
/**
* After the first post-module config update there will be an error thrown to alert to a possible issue.
*/
private boolean startupInitialized = false;
/**
* Module Conversion factors to use.
*/
private ConversionFactorsJson moduleConversionFactors;



/**
Expand Down Expand Up @@ -364,12 +353,6 @@ public void configureIntegratedEncoder(double positionConversionFactor)

}

@Override
public void configureConversionFactor(ConversionFactorsJson factorsJson)
{
this.moduleConversionFactors = factorsJson;
}

/**
* Configure the PIDF values for the closed loop controller.
*
Expand Down
15 changes: 0 additions & 15 deletions src/main/java/swervelib/motors/SparkMaxBrushedMotorSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
import swervelib.encoders.SparkMaxEncoderSwerve;
import swervelib.encoders.SwerveAbsoluteEncoder;
import swervelib.parser.PIDFConfig;
import swervelib.parser.json.modules.ConversionFactorsJson;
import swervelib.telemetry.SwerveDriveTelemetry;

/**
Expand Down Expand Up @@ -79,14 +78,6 @@ public class SparkMaxBrushedMotorSwerve extends SwerveMotor
* Configuration object for {@link SparkMax} motor.
*/
private SparkMaxConfig cfg = new SparkMaxConfig();
/**
* Module Conversion factors to use.
*/
private ConversionFactorsJson moduleConversionFactors;
/**
* After the first post-module config update there will be an error thrown to alert to a possible issue.
*/
private boolean startupInitialized = false;

/**
* Initialize the swerve motor.
Expand Down Expand Up @@ -440,12 +431,6 @@ public void configureIntegratedEncoder(double positionConversionFactor)
}
}

@Override
public void configureConversionFactor(ConversionFactorsJson factorsJson)
{
this.moduleConversionFactors = factorsJson;
}

/**
* Configure the PIDF values for the closed loop controller.
*
Expand Down
15 changes: 0 additions & 15 deletions src/main/java/swervelib/motors/SparkMaxSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
import swervelib.encoders.SparkMaxEncoderSwerve;
import swervelib.encoders.SwerveAbsoluteEncoder;
import swervelib.parser.PIDFConfig;
import swervelib.parser.json.modules.ConversionFactorsJson;
import swervelib.telemetry.SwerveDriveTelemetry;

/**
Expand Down Expand Up @@ -64,14 +63,6 @@ public class SparkMaxSwerve extends SwerveMotor
* Configuration object for {@link SparkMax} motor.
*/
private SparkMaxConfig cfg = new SparkMaxConfig();
/**
* Module Conversion factors to use.
*/
private ConversionFactorsJson moduleConversionFactors;
/**
* After the first post-module config update there will be an error thrown to alert to a possible issue.
*/
private boolean startupInitialized = false;


/**
Expand Down Expand Up @@ -366,12 +357,6 @@ public void configureIntegratedEncoder(double positionConversionFactor)

}

@Override
public void configureConversionFactor(ConversionFactorsJson factorsJson)
{
this.moduleConversionFactors = factorsJson;
}

/**
* Configure the PIDF values for the closed loop controller.
*
Expand Down
8 changes: 0 additions & 8 deletions src/main/java/swervelib/motors/SwerveMotor.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
import edu.wpi.first.math.system.plant.DCMotor;
import swervelib.encoders.SwerveAbsoluteEncoder;
import swervelib.parser.PIDFConfig;
import swervelib.parser.json.modules.ConversionFactorsJson;

/**
* Swerve motor abstraction which defines a standard interface for motors within a swerve module.
Expand Down Expand Up @@ -51,13 +50,6 @@ public abstract class SwerveMotor
*/
public abstract void configureIntegratedEncoder(double positionConversionFactor);

/**
* Configure the motor controller conversion factors based off given ConversionFactors.
*
* @param factorsJson {@link ConversionFactorsJson} from {@link swervelib.parser.SwerveParser}.
*/
public abstract void configureConversionFactor(ConversionFactorsJson factorsJson);

/**
* Configure the PIDF values for the closed loop controller. 0 is disabled or off.
*
Expand Down
11 changes: 0 additions & 11 deletions src/main/java/swervelib/motors/TalonFXSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
import edu.wpi.first.math.system.plant.DCMotor;
import swervelib.encoders.SwerveAbsoluteEncoder;
import swervelib.parser.PIDFConfig;
import swervelib.parser.json.modules.ConversionFactorsJson;
import swervelib.telemetry.SwerveDriveTelemetry;

/**
Expand Down Expand Up @@ -52,10 +51,6 @@ public class TalonFXSwerve extends SwerveMotor
* Conversion factor for the motor.
*/
private double conversionFactor;
/**
* Module Conversion factors to use.
*/
private ConversionFactorsJson moduleConversionFactors;
/**
* Current TalonFX configuration.
*/
Expand Down Expand Up @@ -196,12 +191,6 @@ public void configureIntegratedEncoder(double positionConversionFactor)
cfg.apply(configuration);
}

@Override
public void configureConversionFactor(ConversionFactorsJson factorsJson)
{
this.moduleConversionFactors = factorsJson;
}

/**
* Configure the PIDF values for the closed loop controller. 0 is disabled or off.
*
Expand Down
6 changes: 0 additions & 6 deletions src/main/java/swervelib/motors/TalonSRXSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -143,12 +143,6 @@ public void configureIntegratedEncoder(double positionConversionFactor)
configureCANStatusFrames(250);
}

@Override
public void configureConversionFactor(ConversionFactorsJson factorsJson)
{
this.moduleConversionFactors = factorsJson;
}

/**
* Set the CAN status frames.
*
Expand Down
Loading

0 comments on commit cc0615c

Please sign in to comment.