Skip to content

Commit

Permalink
IT WORKS!!!!!!!!!!! Next time just steal from the creators originally
Browse files Browse the repository at this point in the history
  • Loading branch information
legoguy1000 committed Jan 20, 2024
1 parent 1b1819e commit 41959a1
Show file tree
Hide file tree
Showing 11 changed files with 648 additions and 737 deletions.
97 changes: 24 additions & 73 deletions src/main/java/frc/lib/math/Conversions.java
Original file line number Diff line number Diff line change
@@ -1,93 +1,44 @@
package frc.lib.math;

/**
* Mathematical conversions for swerve calculations
*/
public class Conversions {

Check warning on line 3 in src/main/java/frc/lib/math/Conversions.java

View workflow job for this annotation

GitHub Actions / testtool

[testtool] src/main/java/frc/lib/math/Conversions.java#L3 <com.puppycrawl.tools.checkstyle.checks.javadoc.MissingJavadocTypeCheck>

Missing a Javadoc comment.
Raw output
/github/workspace/./src/main/java/frc/lib/math/Conversions.java:3:1: warning: Missing a Javadoc comment. (com.puppycrawl.tools.checkstyle.checks.javadoc.MissingJavadocTypeCheck)

/**
* @param counts Falcon Counts
* @param gearRatio Gear Ratio between Falcon and Mechanism
* @return Degrees of Rotation of Mechanism falconToDegrees
* @param wheelRPS Wheel Velocity: (in Rotations per Second)
* @param circumference Wheel Circumference: (in Meters)
* @return Wheel Velocity: (in Meters per Second)
*/
public static double falconToDegrees(double counts, double gearRatio) {
return counts * (360.0 / (gearRatio * 2048.0));
}

/**
* @param degrees Degrees of rotation of Mechanism
* @param gearRatio Gear Ratio between Falcon and Mechanism
* @return Falcon Counts degreesToFalcon
*/
public static double degreesToFalcon(double degrees, double gearRatio) {
double ticks = degrees / (360.0 / (gearRatio * 2048.0));
return ticks;
}

/**
* @param velocityCounts Falcon Velocity Counts
* @param gearRatio Gear Ratio between Falcon and Mechanism (set to 1 for Falcon RPM)
* @return RPM of Mechanism
*/
public static double falconToRPM(double velocityCounts, double gearRatio) {
double motorRPM = velocityCounts * (600.0 / 2048.0);
double mechRPM = motorRPM / gearRatio;
return mechRPM;
}

/**
* @param rpm RPM of mechanism
* @param gearRatio Gear Ratio between Falcon and Mechanism (set to 1 for Falcon RPM)
* @return RPM of Mechanism
*/
public static double rpmToFalcon(double rpm, double gearRatio) {
double motorRPM = rpm * gearRatio;
double sensorCounts = motorRPM * (2048.0 / 600.0);
return sensorCounts;
}

/**
* @param counts Falcon Counts
* @param gearRatio Gear Ratio between Falcon and Mechanism
* @return Degrees of Rotation of Mechanism falconToDegrees
*/
public static double falconToMeters(double counts, double gearRatio, double circumference) {
return counts * circumference / (gearRatio * 2048.0);
public static double RPSToMPS(double wheelRPS, double circumference) {
double wheelMPS = wheelRPS * circumference;
return wheelMPS;
}

/**
* @param velocitycounts Falcon Velocity Counts
* @param circumference Circumference of Wheel
* @param gearRatio Gear Ratio between Falcon and Mechanism (set to 1 for Falcon RPM)
* @return Falcon Velocity Counts
* @param wheelMPS Wheel Velocity: (in Meters per Second)
* @param circumference Wheel Circumference: (in Meters)
* @return Wheel Velocity: (in Rotations per Second)
*/
public static double falconToMPS(double velocitycounts, double circumference,
double gearRatio) {
double wheelRPM = falconToRPM(velocitycounts, gearRatio);
double wheelMPS = (wheelRPM * circumference) / 60;
return wheelMPS;
public static double MPSToRPS(double wheelMPS, double circumference) {
double wheelRPS = wheelMPS / circumference;
return wheelRPS;
}

/**
* @param velocity Velocity MPS
* @param circumference Circumference of Wheel
* @param gearRatio Gear Ratio between Falcon and Mechanism (set to 1 for Falcon RPM)
* @return Falcon Velocity Counts
* @param wheelRotations Wheel Position: (in Rotations)
* @param circumference Wheel Circumference: (in Meters)
* @return Wheel Distance: (in Meters)
*/
public static double mpsToFalcon(double velocity, double circumference, double gearRatio) {
double wheelRPM = ((velocity * 60) / circumference);
double wheelVelocity = rpmToFalcon(wheelRPM, gearRatio);
return wheelVelocity;
public static double rotationsToMeters(double wheelRotations, double circumference) {
double wheelMeters = wheelRotations * circumference;
return wheelMeters;
}

/**
* Normalize angle to between 0 to 360
*
* @param goal initial angle
* @return normalized angle
* @param wheelMeters Wheel Distance: (in Meters)
* @param circumference Wheel Circumference: (in Meters)
* @return Wheel Position: (in Rotations)
*/
public static double reduceTo0_360(double goal) {
return goal % 360;
public static double metersToRotations(double wheelMeters, double circumference) {
double wheelRotations = wheelMeters / circumference;
return wheelRotations;
}

}
114 changes: 62 additions & 52 deletions src/main/java/frc/lib/util/ctre/CTREConfigs.java
Original file line number Diff line number Diff line change
@@ -1,61 +1,71 @@
package frc.lib.util.ctre;

import com.ctre.phoenix.motorcontrol.SupplyCurrentLimitConfiguration;
import com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration;
import com.ctre.phoenix.sensors.AbsoluteSensorRange;
import com.ctre.phoenix.sensors.CANCoderConfiguration;
import com.ctre.phoenix.sensors.SensorInitializationStrategy;
import com.ctre.phoenix.sensors.SensorTimeBase;
import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import frc.robot.Constants;

/**
* CTRE config constants
*/
public final class CTREConfigs {

Check warning on line 7 in src/main/java/frc/lib/util/ctre/CTREConfigs.java

View workflow job for this annotation

GitHub Actions / testtool

[testtool] src/main/java/frc/lib/util/ctre/CTREConfigs.java#L7 <com.puppycrawl.tools.checkstyle.checks.javadoc.MissingJavadocTypeCheck>

Missing a Javadoc comment.
Raw output
/github/workspace/./src/main/java/frc/lib/util/ctre/CTREConfigs.java:7:1: warning: Missing a Javadoc comment. (com.puppycrawl.tools.checkstyle.checks.javadoc.MissingJavadocTypeCheck)
public TalonFXConfiguration swerveAngleFXConfig;
public TalonFXConfiguration swerveDriveFXConfig;
public CANCoderConfiguration swerveCanCoderConfig;
public TalonFXConfiguration swerveAngleFXConfig = new TalonFXConfiguration();
public TalonFXConfiguration swerveDriveFXConfig = new TalonFXConfiguration();
public CANcoderConfiguration swerveCANcoderConfig = new CANcoderConfiguration();

/**
* CTRE config constants
*/
public CTREConfigs() {

Check warning on line 12 in src/main/java/frc/lib/util/ctre/CTREConfigs.java

View workflow job for this annotation

GitHub Actions / testtool

[testtool] src/main/java/frc/lib/util/ctre/CTREConfigs.java#L12 <com.puppycrawl.tools.checkstyle.checks.javadoc.MissingJavadocMethodCheck>

Missing a Javadoc comment.
Raw output
/github/workspace/./src/main/java/frc/lib/util/ctre/CTREConfigs.java:12:5: warning: Missing a Javadoc comment. (com.puppycrawl.tools.checkstyle.checks.javadoc.MissingJavadocMethodCheck)
swerveAngleFXConfig = new TalonFXConfiguration();
swerveDriveFXConfig = new TalonFXConfiguration();
swerveCanCoderConfig = new CANCoderConfiguration();

/* Swerve Angle Motor Configurations */
SupplyCurrentLimitConfiguration angleSupplyLimit = new SupplyCurrentLimitConfiguration(
Constants.Swerve.angleEnableCurrentLimit, Constants.Swerve.angleContinuousCurrentLimit,
Constants.Swerve.anglePeakCurrentLimit, Constants.Swerve.anglePeakCurrentDuration);

swerveAngleFXConfig.slot0.kP = Constants.Swerve.angleKP;
swerveAngleFXConfig.slot0.kI = Constants.Swerve.angleKI;
swerveAngleFXConfig.slot0.kD = Constants.Swerve.angleKD;
swerveAngleFXConfig.slot0.kF = Constants.Swerve.angleKF;
swerveAngleFXConfig.supplyCurrLimit = angleSupplyLimit;
swerveAngleFXConfig.initializationStrategy = SensorInitializationStrategy.BootToZero;

/* Swerve Drive Motor Configuration */
SupplyCurrentLimitConfiguration driveSupplyLimit = new SupplyCurrentLimitConfiguration(
Constants.Swerve.driveEnableCurrentLimit, Constants.Swerve.driveContinuousCurrentLimit,
Constants.Swerve.drivePeakCurrentLimit, Constants.Swerve.drivePeakCurrentDuration);

swerveDriveFXConfig.slot0.kP = Constants.Swerve.driveKP;
swerveDriveFXConfig.slot0.kI = Constants.Swerve.driveKI;
swerveDriveFXConfig.slot0.kD = Constants.Swerve.driveKD;
swerveDriveFXConfig.slot0.kF = Constants.Swerve.driveKF;
swerveDriveFXConfig.supplyCurrLimit = driveSupplyLimit;
swerveDriveFXConfig.initializationStrategy = SensorInitializationStrategy.BootToZero;
swerveDriveFXConfig.openloopRamp = Constants.Swerve.openLoopRamp;
swerveDriveFXConfig.closedloopRamp = Constants.Swerve.closedLoopRamp;

/* Swerve CANCoder Configuration */
swerveCanCoderConfig.absoluteSensorRange = AbsoluteSensorRange.Unsigned_0_to_360;
swerveCanCoderConfig.sensorDirection = Constants.Swerve.canCoderInvert;
swerveCanCoderConfig.initializationStrategy =
SensorInitializationStrategy.BootToAbsolutePosition;
swerveCanCoderConfig.sensorTimeBase = SensorTimeBase.PerSecond;
}
/** Swerve CANCoder Configuration */

Check warning on line 13 in src/main/java/frc/lib/util/ctre/CTREConfigs.java

View workflow job for this annotation

GitHub Actions / testtool

[testtool] src/main/java/frc/lib/util/ctre/CTREConfigs.java#L13 <com.puppycrawl.tools.checkstyle.checks.javadoc.InvalidJavadocPositionCheck>

Javadoc comment is placed in the wrong location.
Raw output
/github/workspace/./src/main/java/frc/lib/util/ctre/CTREConfigs.java:13:9: warning: Javadoc comment is placed in the wrong location. (com.puppycrawl.tools.checkstyle.checks.javadoc.InvalidJavadocPositionCheck)
swerveCANcoderConfig.MagnetSensor.SensorDirection = Constants.Swerve.cancoderInvert;

/** Swerve Angle Motor Configurations */

Check warning on line 16 in src/main/java/frc/lib/util/ctre/CTREConfigs.java

View workflow job for this annotation

GitHub Actions / testtool

[testtool] src/main/java/frc/lib/util/ctre/CTREConfigs.java#L16 <com.puppycrawl.tools.checkstyle.checks.javadoc.InvalidJavadocPositionCheck>

Javadoc comment is placed in the wrong location.
Raw output
/github/workspace/./src/main/java/frc/lib/util/ctre/CTREConfigs.java:16:9: warning: Javadoc comment is placed in the wrong location. (com.puppycrawl.tools.checkstyle.checks.javadoc.InvalidJavadocPositionCheck)
/* Motor Inverts and Neutral Mode */
swerveAngleFXConfig.MotorOutput.Inverted = Constants.Swerve.angleMotorInvert;
swerveAngleFXConfig.MotorOutput.NeutralMode = Constants.Swerve.angleNeutralMode;

/* Gear Ratio and Wrapping Config */
swerveAngleFXConfig.Feedback.SensorToMechanismRatio = Constants.Swerve.angleGearRatio;
swerveAngleFXConfig.ClosedLoopGeneral.ContinuousWrap = true;

/* Current Limiting */
swerveAngleFXConfig.CurrentLimits.SupplyCurrentLimitEnable =
Constants.Swerve.angleEnableCurrentLimit;
swerveAngleFXConfig.CurrentLimits.SupplyCurrentLimit = Constants.Swerve.angleCurrentLimit;
swerveAngleFXConfig.CurrentLimits.SupplyCurrentThreshold =
Constants.Swerve.angleCurrentThreshold;
swerveAngleFXConfig.CurrentLimits.SupplyTimeThreshold =
Constants.Swerve.angleCurrentThresholdTime;

/* PID Config */
swerveAngleFXConfig.Slot0.kP = Constants.Swerve.angleKP;
swerveAngleFXConfig.Slot0.kI = Constants.Swerve.angleKI;
swerveAngleFXConfig.Slot0.kD = Constants.Swerve.angleKD;

/** Swerve Drive Motor Configuration */

Check warning on line 39 in src/main/java/frc/lib/util/ctre/CTREConfigs.java

View workflow job for this annotation

GitHub Actions / testtool

[testtool] src/main/java/frc/lib/util/ctre/CTREConfigs.java#L39 <com.puppycrawl.tools.checkstyle.checks.javadoc.InvalidJavadocPositionCheck>

Javadoc comment is placed in the wrong location.
Raw output
/github/workspace/./src/main/java/frc/lib/util/ctre/CTREConfigs.java:39:9: warning: Javadoc comment is placed in the wrong location. (com.puppycrawl.tools.checkstyle.checks.javadoc.InvalidJavadocPositionCheck)
/* Motor Inverts and Neutral Mode */
swerveDriveFXConfig.MotorOutput.Inverted = Constants.Swerve.driveMotorInvert;
swerveDriveFXConfig.MotorOutput.NeutralMode = Constants.Swerve.driveNeutralMode;

/* Gear Ratio Config */
swerveDriveFXConfig.Feedback.SensorToMechanismRatio = Constants.Swerve.driveGearRatio;

/* Current Limiting */
swerveDriveFXConfig.CurrentLimits.SupplyCurrentLimitEnable =
Constants.Swerve.driveEnableCurrentLimit;
swerveDriveFXConfig.CurrentLimits.SupplyCurrentLimit = Constants.Swerve.driveCurrentLimit;
swerveDriveFXConfig.CurrentLimits.SupplyCurrentThreshold =
Constants.Swerve.driveCurrentThreshold;
swerveDriveFXConfig.CurrentLimits.SupplyTimeThreshold =
Constants.Swerve.driveCurrentThresholdTime;

/* PID Config */
swerveDriveFXConfig.Slot0.kP = Constants.Swerve.driveKP;
swerveDriveFXConfig.Slot0.kI = Constants.Swerve.driveKI;
swerveDriveFXConfig.Slot0.kD = Constants.Swerve.driveKD;

/* Open and Closed Loop Ramping */
swerveDriveFXConfig.OpenLoopRamps.DutyCycleOpenLoopRampPeriod =
Constants.Swerve.openLoopRamp;
swerveDriveFXConfig.OpenLoopRamps.VoltageOpenLoopRampPeriod = Constants.Swerve.openLoopRamp;

swerveDriveFXConfig.ClosedLoopRamps.DutyCycleClosedLoopRampPeriod =
Constants.Swerve.closedLoopRamp;
swerveDriveFXConfig.ClosedLoopRamps.VoltageClosedLoopRampPeriod =
Constants.Swerve.closedLoopRamp;
}
}
61 changes: 0 additions & 61 deletions src/main/java/frc/lib/util/ctre/CTREModuleState.java

This file was deleted.

Loading

0 comments on commit 41959a1

Please sign in to comment.