Skip to content
This repository has been archived by the owner on Nov 2, 2024. It is now read-only.

Commit

Permalink
finished just need to be tested
Browse files Browse the repository at this point in the history
  • Loading branch information
gvaldez7206 committed Jan 25, 2024
1 parent 5e0ea52 commit 20e362c
Show file tree
Hide file tree
Showing 8 changed files with 211 additions and 328 deletions.
102 changes: 29 additions & 73 deletions src/main/java/frc/lib/math/Conversions.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,93 +3,39 @@
import edu.wpi.first.math.MathUtil;

/**
* Mathematical conversions for swerve calculations
* Static Conversion functions
*/
public class Conversions {

/**
* @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);
}

/**
* @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
*/
public static double falconToMPS(double velocitycounts, double circumference,
double gearRatio) {
double wheelRPM = falconToRPM(velocitycounts, gearRatio);
double wheelMPS = (wheelRPM * circumference) / 60;
public static double RPSToMPS(double wheelRPS, double circumference) {

Check warning on line 15 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#L15 <com.puppycrawl.tools.checkstyle.checks.naming.MethodNameCheck>

Method name 'RPSToMPS' must match pattern '^[_a-z][_a-zA-Z0-9_]*$'.
Raw output
/github/workspace/./src/main/java/frc/lib/math/Conversions.java:15:26: warning: Method name 'RPSToMPS' must match pattern '^[_a-z][_a-zA-Z0-9_]*$'. (com.puppycrawl.tools.checkstyle.checks.naming.MethodNameCheck)
double wheelMPS = wheelRPS * circumference;
return wheelMPS;
}

/**
* @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 wheelMPS Wheel Velocity: (in Meters per Second)
* @param circumference Wheel Circumference: (in Meters)
* @return Wheel Velocity: (in Rotations per Second)
*/
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 MPSToRPS(double wheelMPS, double circumference) {

Check warning on line 25 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#L25 <com.puppycrawl.tools.checkstyle.checks.naming.MethodNameCheck>

Method name 'MPSToRPS' must match pattern '^[_a-z][_a-zA-Z0-9_]*$'.
Raw output
/github/workspace/./src/main/java/frc/lib/math/Conversions.java:25:26: warning: Method name 'MPSToRPS' must match pattern '^[_a-z][_a-zA-Z0-9_]*$'. (com.puppycrawl.tools.checkstyle.checks.naming.MethodNameCheck)
double wheelRPS = wheelMPS / circumference;
return wheelRPS;
}

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

/**
Expand All @@ -116,6 +62,16 @@ public static double applySwerveCurve(double input, double deadband) {

}

/**
* @param wheelMeters Wheel Distance: (in Meters)
* @param circumference Wheel Circumference: (in Meters)
* @return Wheel Position: (in Rotations)
*/
public static double metersToRotations(double wheelMeters, double circumference) {
double wheelRotations = wheelMeters / circumference;
return wheelRotations;
}

/**
* Generate a random number between and upper and lower bound
*
Expand Down
65 changes: 0 additions & 65 deletions src/main/java/frc/lib/util/ctre/CTREConfigs.java

This file was deleted.

Loading

0 comments on commit 20e362c

Please sign in to comment.