Skip to content

Commit

Permalink
Remove Rarely Used Parts of StuyLib (#84)
Browse files Browse the repository at this point in the history
* Remove Fluff

* Spotless
Sam-Belliveau authored Jan 17, 2024

Verified

This commit was created on GitHub.com and signed with GitHub’s verified signature.
1 parent 7edb3cd commit f3d75b1
Showing 54 changed files with 8 additions and 6,524 deletions.

This file was deleted.

Original file line number Diff line number Diff line change
@@ -190,15 +190,4 @@ public AnglePIDController setDerivativeFilter(IFilter... derivativeFilter) {
mDFilter = IFilter.create(derivativeFilter);
return this;
}

/** @return information about this PIDController */
public String toString() {
return "(P: "
+ SLMath.round(getP(), 4)
+ ", I: "
+ SLMath.round(getI(), 4)
+ ", D: "
+ SLMath.round(getD(), 4)
+ ")";
}
}
195 changes: 0 additions & 195 deletions src/com/stuypulse/stuylib/control/feedback/PIDCalculator.java

This file was deleted.

11 changes: 0 additions & 11 deletions src/com/stuypulse/stuylib/control/feedback/PIDController.java
Original file line number Diff line number Diff line change
@@ -196,15 +196,4 @@ public PIDController setDerivativeFilter(IFilter... derivativeFilter) {
mDFilter = IFilter.create(derivativeFilter);
return this;
}

/** @return information about this PIDController */
public String toString() {
return "(P: "
+ SLMath.round(getP(), 4)
+ ", I: "
+ SLMath.round(getI(), 4)
+ ", D: "
+ SLMath.round(getD(), 4)
+ ")";
}
}
209 changes: 0 additions & 209 deletions src/com/stuypulse/stuylib/input/GamepadState.java

This file was deleted.

123 changes: 0 additions & 123 deletions src/com/stuypulse/stuylib/input/gamepads/keyboard/KeyGamepad.java

This file was deleted.

This file was deleted.

This file was deleted.

108 changes: 0 additions & 108 deletions src/com/stuypulse/stuylib/input/keyboard/NetKeyboard.java

This file was deleted.

This file was deleted.

This file was deleted.

3 changes: 0 additions & 3 deletions src/com/stuypulse/stuylib/input/keyboard/readme.md

This file was deleted.

19 changes: 0 additions & 19 deletions src/com/stuypulse/stuylib/math/Angle.java
Original file line number Diff line number Diff line change
@@ -15,10 +15,6 @@
*/
public final class Angle {

// Configuration for toString() function
private static final boolean STRING_RADIANS = false;
private static final int STRING_SIGFIGS = 5;

/******************************************************/
/*** CONSTANT ANGLE VALUES, SET AT BENCHMARK VALUES ***/
/******************************************************/
@@ -494,19 +490,4 @@ public boolean equals(Object other) {
public int hashCode() {
return Double.hashCode(this.toRadians());
}

/** @return the string representation of the angle */
@Override
public String toString() {
StringBuilder out = new StringBuilder();
out.append("Angle(");

if (STRING_RADIANS) {
out.append(SLMath.round(this.toRadians(), STRING_SIGFIGS)).append("pi, ");
}

out.append(SLMath.round(this.toDegrees(), STRING_SIGFIGS)).append("deg)");

return out.toString();
}
}
155 changes: 0 additions & 155 deletions src/com/stuypulse/stuylib/math/Polar2D.java

This file was deleted.

132 changes: 0 additions & 132 deletions src/com/stuypulse/stuylib/math/SLMath.java
Original file line number Diff line number Diff line change
@@ -16,37 +16,6 @@ public final class SLMath {
// Prevent the class from being extended at all
private SLMath() {}

/*********************/
/*** INTERPOLATION ***/
/*********************/

/**
* Linear Interpolation from start to end using value t [0...1]
*
* @param start value of linear interpolation when t = 0
* @param end value of linear interpolation when t = 1
* @param t time value for linear interpolation [0...1]
* @return interpolated value
*/
public static double lerp(double start, double end, double t) {
return start + (end - start) * clamp(t, 0.0, 1.0);
}

/**
* Maps an input in one range to an output in another range
*
* @param input value to map
* @param minInput minimum value of input
* @param maxInput maximum value of input
* @param minOutput minimum value of output
* @param maxOutput maximum value of output
* @return the mapped value
*/
public static double map(
double input, double minInput, double maxInput, double minOutput, double maxOutput) {
return lerp(minOutput, maxOutput, (input - minInput) / (maxInput - minInput));
}

/**************/
/*** LIMITS ***/
/**************/
@@ -116,26 +85,6 @@ public static double deadband(double x, double window) {
/*** RAISE TO POWER WHILE KEEPING SIGN ***/
/*****************************************/

/**
* [WARNING! THIS WILL KEEP THE SIGN OF THE INPUT NUMBER] Square number and keep sign
*
* @param x input
* @return squared input with the same sign
*/
public static double square(double x) {
return clamp(x * x * Math.signum(x));
}

/**
* Cube a number
*
* @param x input
* @return cubed input that
*/
public static double cube(double x) {
return x * x * x;
}

/**
* spow (signless pow), raises a number to a power without affecting the sign of the number
*
@@ -146,85 +95,4 @@ public static double cube(double x) {
public static double spow(double x, double power) {
return Math.pow(Math.abs(x), power) * Math.signum(x);
}

/*****************/
/*** MISC MATH ***/
/*****************/

/**
* fpow (fast pow), is a pow function that takes in an integer for the exponent. This allows it
* to be much faster on repeated calls due to the fact that it does not need to deal with
* fractional exponents.
*
* @param base base of the power
* @param exp integer exponent of power
* @return result of calculation
*/
public static double fpow(double base, int exp) {
// Output of the fpow function
double out = 1.0;

// If the exponent is negative, divide instead of multiply
if (exp < 0) {
// Flip exponent to make calculations easier
exp = -exp;

// Fast integer power algorithm
while (exp > 0) {
if ((exp & 1) == 1) {
out /= base;
}
base *= base;
exp >>= 1;
}
} else {
// Fast integer power algorithm
while (exp > 0) {
if ((exp & 1) == 1) {
out *= base;
}
base *= base;
exp >>= 1;
}
}

// Return
return out;
}

/**
* Round a double by a certain amount of sigfigs in base 10
*
* @param n number to round
* @param sigfigs amount of sigfigs to round it to
* @return rounded number
*/
public static double round(double n, int sigfigs) {
// The value 0 returns nan if not accounted for
if (n == 0.0) {
return 0.0;
}

// Digit place that number starts at
int digits = (int) Math.floor(Math.log10(Math.abs(n)));

// Amount to multiply before multiplying based on
// the sigfigs and digits in the number
double mul = fpow(10.0, sigfigs - digits);

// Round number by the multiplier calculated
return Math.round(n * mul) / mul;
}

private static final double FLT_ELIPSON = fpow(0.5, 32);

/**
* Compare a double to zero using a Elipson
*
* @param num number to compare to zero
* @return if the number equals a number close to zero
*/
public static boolean isZero(double num) {
return Math.abs(num) < FLT_ELIPSON;
}
}
1,102 changes: 0 additions & 1,102 deletions src/com/stuypulse/stuylib/math/Swizzler.java

This file was deleted.

33 changes: 1 addition & 32 deletions src/com/stuypulse/stuylib/math/Vector2D.java
Original file line number Diff line number Diff line change
@@ -4,8 +4,6 @@

package com.stuypulse.stuylib.math;

import com.stuypulse.stuylib.util.HashBuilder;

import edu.wpi.first.math.geometry.Translation2d;

/**
@@ -17,9 +15,6 @@
*/
public final class Vector2D {

// Configuration for toString() function
private static final int STRING_SIGFIGS = 5;

// Vector Constnants
public static final Vector2D kOrigin = new Vector2D(0, 0);
public static final Vector2D kI = new Vector2D(1, 0);
@@ -103,11 +98,6 @@ public Angle getAngle() {
return Angle.fromVector(this);
}

/** @return polar coordinates created from this vector */
public Polar2D getPolar() {
return new Polar2D(this);
}

/**
* @param angle angle to rotate by
* @param origin point to rotate around
@@ -196,7 +186,7 @@ public double cross(Vector2D other) {
/** @return result of normalizing the Vector2D so that the magnitude is 1.0 */
public Vector2D normalize() {
final double magnitude = this.distance();
if (SLMath.isZero(magnitude)) {
if (magnitude <= 1e-9) {
return Vector2D.kI;
} else {
return this.div(magnitude);
@@ -243,25 +233,4 @@ public boolean equals(Object other) {

return false;
}

/**
* @see com.stuypulse.stuylib.util.HashBuilder#combineHash(int, int)
* @return hashCode generated by combining the hashes of the x and y components
*/
@Override
public int hashCode() {
return HashBuilder.combineHash(Double.hashCode(x), Double.hashCode(y));
}

/** @return string representation of Vector2D */
@Override
public String toString() {
StringBuilder out = new StringBuilder();
out.append("Vector2D(");
out.append(SLMath.round(x, STRING_SIGFIGS));
out.append(", ");
out.append(SLMath.round(y, STRING_SIGFIGS));
out.append(")");
return out.toString();
}
}
247 changes: 0 additions & 247 deletions src/com/stuypulse/stuylib/math/Vector3D.java

This file was deleted.

126 changes: 0 additions & 126 deletions src/com/stuypulse/stuylib/math/interpolation/CubicInterpolator.java

This file was deleted.

74 changes: 0 additions & 74 deletions src/com/stuypulse/stuylib/math/interpolation/Interpolator.java

This file was deleted.

This file was deleted.

This file was deleted.

118 changes: 0 additions & 118 deletions src/com/stuypulse/stuylib/math/interpolation/NearestInterpolator.java

This file was deleted.

138 changes: 0 additions & 138 deletions src/com/stuypulse/stuylib/math/interpolation/PolyInterpolator.java

This file was deleted.

276 changes: 0 additions & 276 deletions src/com/stuypulse/stuylib/network/SLNetworkTable.java

This file was deleted.

513 changes: 0 additions & 513 deletions src/com/stuypulse/stuylib/network/limelight/Limelight.java

This file was deleted.

This file was deleted.

147 changes: 0 additions & 147 deletions src/com/stuypulse/stuylib/network/limelight/LimelightTable.java

This file was deleted.

108 changes: 0 additions & 108 deletions src/com/stuypulse/stuylib/network/limelight/Solve3DResult.java

This file was deleted.

3 changes: 0 additions & 3 deletions src/com/stuypulse/stuylib/network/limelight/readme.md

This file was deleted.

70 changes: 0 additions & 70 deletions src/com/stuypulse/stuylib/streams/angles/AFuser.java

This file was deleted.

27 changes: 0 additions & 27 deletions src/com/stuypulse/stuylib/streams/numbers/filters/Integral.java

This file was deleted.

Original file line number Diff line number Diff line change
@@ -4,7 +4,6 @@

package com.stuypulse.stuylib.streams.numbers.filters;

import com.stuypulse.stuylib.math.SLMath;
import com.stuypulse.stuylib.util.StopWatch;

/**
@@ -38,10 +37,10 @@ public double get(double next) {
}

// Get a constant, which is determined based on dt and the mRC constant
double a = Math.exp(-mTimer.reset() / mRC.doubleValue());
double a = 1.0 - Math.exp(-mTimer.reset() / mRC.doubleValue());

// Based on the value of a (which is determined by dt), the next value
// could either change a lot, or not by much. (smaller dt = smaller change)
return mLastValue = SLMath.lerp(next, mLastValue, a);
return mLastValue += a * (next - mLastValue);
}
}

This file was deleted.

This file was deleted.

Loading

0 comments on commit f3d75b1

Please sign in to comment.