From 220d9ebf127cbbae20782bba939043adb96d72e4 Mon Sep 17 00:00:00 2001 From: Brian <74162951+codeNinja-1@users.noreply.github.com> Date: Thu, 19 Feb 2026 17:03:49 -0800 Subject: [PATCH 01/18] Add Apache commons --- build.gradle | 1 + 1 file changed, 1 insertion(+) diff --git a/build.gradle b/build.gradle index 964a3875..f86aca9b 100644 --- a/build.gradle +++ b/build.gradle @@ -82,6 +82,7 @@ dependencies { annotationProcessor wpi.java.deps.wpilibAnnotations() implementation wpi.java.deps.wpilib() implementation wpi.java.vendor.java() + implementation 'org.apache.commons:commons-math3:3.6.1' roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio) roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio) From bff9f873ac02b994e2574e5a6c5b277a82c43e09 Mon Sep 17 00:00:00 2001 From: Brian <74162951+codeNinja-1@users.noreply.github.com> Date: Thu, 19 Feb 2026 17:08:05 -0800 Subject: [PATCH 02/18] Add Apache commons io --- build.gradle | 1 + 1 file changed, 1 insertion(+) diff --git a/build.gradle b/build.gradle index f86aca9b..33346d5c 100644 --- a/build.gradle +++ b/build.gradle @@ -83,6 +83,7 @@ dependencies { implementation wpi.java.deps.wpilib() implementation wpi.java.vendor.java() implementation 'org.apache.commons:commons-math3:3.6.1' + implementation("commons-io:commons-io:2.21.0") roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio) roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio) From 184e68cf1c15ad7d55e57f1a3231a2d3017bf11a Mon Sep 17 00:00:00 2001 From: rahul Date: Thu, 19 Feb 2026 17:21:44 -0800 Subject: [PATCH 03/18] added csv loader --- .../java/com/team6962/lib/math/CSVLoader.java | 23 +++++++++++++++++++ 1 file changed, 23 insertions(+) create mode 100644 src/main/java/com/team6962/lib/math/CSVLoader.java diff --git a/src/main/java/com/team6962/lib/math/CSVLoader.java b/src/main/java/com/team6962/lib/math/CSVLoader.java new file mode 100644 index 00000000..bcbd4b2b --- /dev/null +++ b/src/main/java/com/team6962/lib/math/CSVLoader.java @@ -0,0 +1,23 @@ +package com.team6962.lib.math; + +import edu.wpi.first.wpilibj.Filesystem; +import java.io.File; +import java.io.IOException; +import org.apache.commons.io.FileUtils; + +public class CSVLoader { + public static double[][] loadCSV(String path) throws IOException { + path = Filesystem.getDeployDirectory() + "/" + path; + String csv = FileUtils.readFileToString(new File(path), "UTF-8"); // Read the CSV file as a string + String[] lines = csv.split("\n"); // Splits the strings along lines + double[][] data = new double[lines.length][]; + for (int i = 0; i < lines.length; i++) { + String[] values = lines[i].split(","); // Splits each line along commas + data[i] = new double[values.length]; + for (int j = 0; j < values.length; j++) { + data[i][j] = Double.parseDouble(values[j]); + } + } + return data; + } +} From 5d6dae38015e32cd6d976739c67241f4e7208778 Mon Sep 17 00:00:00 2001 From: rahul Date: Thu, 19 Feb 2026 17:47:28 -0800 Subject: [PATCH 04/18] Added the shooter data we collected Distance, Roller Velocity, Hood Angle --- src/main/deploy/shooterdata.csv | 27 +++++++++++++++++++++++++++ 1 file changed, 27 insertions(+) create mode 100644 src/main/deploy/shooterdata.csv diff --git a/src/main/deploy/shooterdata.csv b/src/main/deploy/shooterdata.csv new file mode 100644 index 00000000..a9074c96 --- /dev/null +++ b/src/main/deploy/shooterdata.csv @@ -0,0 +1,27 @@ +57.5,25,18 +57.5,23,23 +57.5,21,26 +85,26.5,18 +85,23.5,28 +85,24.5,23 +107,28,18 +107,24.3,28 +107,23.9,38 +107,23.5,33 +107,25.5,23 +124,28,18 +124,26,23 +124,24,28 +150,32,18 +150,27,28 +150,26.5,38 +214,36,18 +214,30,28 +214,29,38 +214,34,23 +214,29.75,33 +263,42,18 +263,35,28 +263,31.5,38 +263,38.5,23 +263,32.5,33 \ No newline at end of file From c069b71c7ee6ad10b09e33cc6ace211e686652ba Mon Sep 17 00:00:00 2001 From: rahul Date: Fri, 20 Feb 2026 11:31:08 -0800 Subject: [PATCH 05/18] Added flywheel velocity data and ShooterFunctions.java --- src/main/deploy/flywheelvelocitydata.csv | 7 ++ .../{shooterdata.csv => hoodangledata.csv} | 0 .../java/frc/robot/auto/ShooterFunctions.java | 78 +++++++++++++++++++ 3 files changed, 85 insertions(+) create mode 100644 src/main/deploy/flywheelvelocitydata.csv rename src/main/deploy/{shooterdata.csv => hoodangledata.csv} (100%) create mode 100644 src/main/java/frc/robot/auto/ShooterFunctions.java diff --git a/src/main/deploy/flywheelvelocitydata.csv b/src/main/deploy/flywheelvelocitydata.csv new file mode 100644 index 00000000..f959b0c2 --- /dev/null +++ b/src/main/deploy/flywheelvelocitydata.csv @@ -0,0 +1,7 @@ +57.5,23 +85,23.5 +107,24.3 +124,25 +150,27 +214,30 +263,31.5 \ No newline at end of file diff --git a/src/main/deploy/shooterdata.csv b/src/main/deploy/hoodangledata.csv similarity index 100% rename from src/main/deploy/shooterdata.csv rename to src/main/deploy/hoodangledata.csv diff --git a/src/main/java/frc/robot/auto/ShooterFunctions.java b/src/main/java/frc/robot/auto/ShooterFunctions.java new file mode 100644 index 00000000..bb48bda5 --- /dev/null +++ b/src/main/java/frc/robot/auto/ShooterFunctions.java @@ -0,0 +1,78 @@ +package frc.robot.auto; + +import static edu.wpi.first.units.Units.Degrees; +import static edu.wpi.first.units.Units.Inches; +import static edu.wpi.first.units.Units.RotationsPerSecond; + +import java.io.IOException; + +import org.apache.commons.math3.analysis.MultivariateFunction; +import org.apache.commons.math3.analysis.UnivariateFunction; +import org.apache.commons.math3.analysis.interpolation.MicrosphereInterpolator; +import org.apache.commons.math3.analysis.interpolation.SplineInterpolator; + +import com.team6962.lib.math.CSVLoader; + +import edu.wpi.first.units.measure.Angle; +import edu.wpi.first.units.measure.AngularVelocity; +import edu.wpi.first.units.measure.Distance; + +public class ShooterFunctions{ + + private static final String path = "hoodangledata.csv"; + private static final String path2 = "flywheelvelocitydata.csv"; + + private MultivariateFunction shooterFunction; + private UnivariateFunction flywheelFunction; + + public ShooterFunctions() { + try { + this.shooterFunction = loadShooterData(); + this.flywheelFunction = loadFlywheelData(); + } catch (IOException e) { + e.printStackTrace(); + } + } + + private MultivariateFunction loadShooterData() throws IOException { + MicrosphereInterpolator interpolator = new MicrosphereInterpolator(); + double[][] data = CSVLoader.loadCSV(path); + double[][] x = new double[2][data.length]; + for (int i = 0; i < data.length; i++) { + x[0][i] = data[i][0]; + x[1][i] = data[i][1]; + } + double[] y = new double[data.length]; + for (int i = 0; i < data.length; i++) { + y[i] = data[i][2]; + } + return interpolator.interpolate(x, y); + } + + private UnivariateFunction loadFlywheelData() throws IOException { + SplineInterpolator interpolator = new SplineInterpolator(); + double[][] data = CSVLoader.loadCSV(path2); + double[] x = new double[data.length]; + for (int i = 0; i < data.length; i++) { + x[i] = data[i][0]; + } + double[] y = new double[data.length]; + for (int i = 0; i < data.length; i++) { + y[i] = data[i][1]; + } + return interpolator.interpolate(x, y); + } + + public MultivariateFunction getShooterFunction() { + return shooterFunction; + } + + public Angle getHoodAngle(Distance distance, AngularVelocity velocity) { + return Degrees.of(shooterFunction.value(new double[]{distance.in(Inches), velocity.in(RotationsPerSecond)})); + } + + public AngularVelocity getFlywheelVelocity(Distance distance, Angle angle) { + return RotationsPerSecond.of(flywheelFunction.value(distance.in(Inches))); + } + +} From 5d9132f713a13f08f16a9e8c6a33c718917ffb12 Mon Sep 17 00:00:00 2001 From: scotch-tape <156549340+scotch-tape@users.noreply.github.com> Date: Fri, 20 Feb 2026 19:33:33 +0000 Subject: [PATCH 06/18] style: Apply Spotless fixes --- .../java/com/team6962/lib/math/CSVLoader.java | 3 +- .../java/frc/robot/auto/ShooterFunctions.java | 103 +++++++++--------- 2 files changed, 52 insertions(+), 54 deletions(-) diff --git a/src/main/java/com/team6962/lib/math/CSVLoader.java b/src/main/java/com/team6962/lib/math/CSVLoader.java index bcbd4b2b..f10f5848 100644 --- a/src/main/java/com/team6962/lib/math/CSVLoader.java +++ b/src/main/java/com/team6962/lib/math/CSVLoader.java @@ -8,7 +8,8 @@ public class CSVLoader { public static double[][] loadCSV(String path) throws IOException { path = Filesystem.getDeployDirectory() + "/" + path; - String csv = FileUtils.readFileToString(new File(path), "UTF-8"); // Read the CSV file as a string + String csv = + FileUtils.readFileToString(new File(path), "UTF-8"); // Read the CSV file as a string String[] lines = csv.split("\n"); // Splits the strings along lines double[][] data = new double[lines.length][]; for (int i = 0; i < lines.length; i++) { diff --git a/src/main/java/frc/robot/auto/ShooterFunctions.java b/src/main/java/frc/robot/auto/ShooterFunctions.java index bb48bda5..620ff899 100644 --- a/src/main/java/frc/robot/auto/ShooterFunctions.java +++ b/src/main/java/frc/robot/auto/ShooterFunctions.java @@ -4,75 +4,72 @@ import static edu.wpi.first.units.Units.Inches; import static edu.wpi.first.units.Units.RotationsPerSecond; +import com.team6962.lib.math.CSVLoader; +import edu.wpi.first.units.measure.Angle; +import edu.wpi.first.units.measure.AngularVelocity; +import edu.wpi.first.units.measure.Distance; import java.io.IOException; - import org.apache.commons.math3.analysis.MultivariateFunction; import org.apache.commons.math3.analysis.UnivariateFunction; import org.apache.commons.math3.analysis.interpolation.MicrosphereInterpolator; import org.apache.commons.math3.analysis.interpolation.SplineInterpolator; -import com.team6962.lib.math.CSVLoader; - -import edu.wpi.first.units.measure.Angle; -import edu.wpi.first.units.measure.AngularVelocity; -import edu.wpi.first.units.measure.Distance; - -public class ShooterFunctions{ +public class ShooterFunctions { - private static final String path = "hoodangledata.csv"; - private static final String path2 = "flywheelvelocitydata.csv"; + private static final String path = "hoodangledata.csv"; + private static final String path2 = "flywheelvelocitydata.csv"; - private MultivariateFunction shooterFunction; - private UnivariateFunction flywheelFunction; + private MultivariateFunction shooterFunction; + private UnivariateFunction flywheelFunction; - public ShooterFunctions() { - try { - this.shooterFunction = loadShooterData(); - this.flywheelFunction = loadFlywheelData(); - } catch (IOException e) { - e.printStackTrace(); - } + public ShooterFunctions() { + try { + this.shooterFunction = loadShooterData(); + this.flywheelFunction = loadFlywheelData(); + } catch (IOException e) { + e.printStackTrace(); } + } - private MultivariateFunction loadShooterData() throws IOException { - MicrosphereInterpolator interpolator = new MicrosphereInterpolator(); - double[][] data = CSVLoader.loadCSV(path); - double[][] x = new double[2][data.length]; - for (int i = 0; i < data.length; i++) { - x[0][i] = data[i][0]; - x[1][i] = data[i][1]; - } - double[] y = new double[data.length]; - for (int i = 0; i < data.length; i++) { - y[i] = data[i][2]; - } - return interpolator.interpolate(x, y); + private MultivariateFunction loadShooterData() throws IOException { + MicrosphereInterpolator interpolator = new MicrosphereInterpolator(); + double[][] data = CSVLoader.loadCSV(path); + double[][] x = new double[2][data.length]; + for (int i = 0; i < data.length; i++) { + x[0][i] = data[i][0]; + x[1][i] = data[i][1]; } + double[] y = new double[data.length]; + for (int i = 0; i < data.length; i++) { + y[i] = data[i][2]; + } + return interpolator.interpolate(x, y); + } - private UnivariateFunction loadFlywheelData() throws IOException { - SplineInterpolator interpolator = new SplineInterpolator(); - double[][] data = CSVLoader.loadCSV(path2); - double[] x = new double[data.length]; - for (int i = 0; i < data.length; i++) { - x[i] = data[i][0]; - } - double[] y = new double[data.length]; - for (int i = 0; i < data.length; i++) { - y[i] = data[i][1]; - } - return interpolator.interpolate(x, y); + private UnivariateFunction loadFlywheelData() throws IOException { + SplineInterpolator interpolator = new SplineInterpolator(); + double[][] data = CSVLoader.loadCSV(path2); + double[] x = new double[data.length]; + for (int i = 0; i < data.length; i++) { + x[i] = data[i][0]; } - - public MultivariateFunction getShooterFunction() { - return shooterFunction; + double[] y = new double[data.length]; + for (int i = 0; i < data.length; i++) { + y[i] = data[i][1]; } + return interpolator.interpolate(x, y); + } - public Angle getHoodAngle(Distance distance, AngularVelocity velocity) { - return Degrees.of(shooterFunction.value(new double[]{distance.in(Inches), velocity.in(RotationsPerSecond)})); - } + public MultivariateFunction getShooterFunction() { + return shooterFunction; + } - public AngularVelocity getFlywheelVelocity(Distance distance, Angle angle) { - return RotationsPerSecond.of(flywheelFunction.value(distance.in(Inches))); - } + public Angle getHoodAngle(Distance distance, AngularVelocity velocity) { + return Degrees.of( + shooterFunction.value(new double[] {distance.in(Inches), velocity.in(RotationsPerSecond)})); + } + public AngularVelocity getFlywheelVelocity(Distance distance, Angle angle) { + return RotationsPerSecond.of(flywheelFunction.value(distance.in(Inches))); + } } From 6346b2fef502e84646d07020522477cb3344396d Mon Sep 17 00:00:00 2001 From: rahul Date: Fri, 20 Feb 2026 11:51:17 -0800 Subject: [PATCH 07/18] Added javadoc comments and applied spotless --- .../java/com/team6962/lib/math/CSVLoader.java | 20 ++- .../java/frc/robot/auto/ShooterFunctions.java | 159 ++++++++++++------ 2 files changed, 125 insertions(+), 54 deletions(-) diff --git a/src/main/java/com/team6962/lib/math/CSVLoader.java b/src/main/java/com/team6962/lib/math/CSVLoader.java index bcbd4b2b..37c8aa69 100644 --- a/src/main/java/com/team6962/lib/math/CSVLoader.java +++ b/src/main/java/com/team6962/lib/math/CSVLoader.java @@ -6,9 +6,27 @@ import org.apache.commons.io.FileUtils; public class CSVLoader { + + /** + * Loads a CSV file containing floating-point values into a two-dimensional double array. + * + *

The provided path is resolved relative to the deploy directory: + * Filesystem.getDeployDirectory() + "/" + path. The file is read using UTF-8 encoding. The file + * contents are split into rows on the newline character ('\n'), and each row is split into + * columns on the comma (',') character. Each column token is parsed with Double.parseDouble and + * stored in the returned double[][]. The resulting array has one entry per line; rows may be + * ragged (different numbers of columns per line). + * + * @param path the path to the CSV file relative to the deploy directory + * @return a two-dimensional array of doubles where each outer element represents a CSV line and + * each inner element represents a parsed numeric value from that line + * @throws IOException if an I/O error occurs while reading the file + * @throws NumberFormatException if any token cannot be parsed as a double + */ public static double[][] loadCSV(String path) throws IOException { path = Filesystem.getDeployDirectory() + "/" + path; - String csv = FileUtils.readFileToString(new File(path), "UTF-8"); // Read the CSV file as a string + String csv = + FileUtils.readFileToString(new File(path), "UTF-8"); // Read the CSV file as a string String[] lines = csv.split("\n"); // Splits the strings along lines double[][] data = new double[lines.length][]; for (int i = 0; i < lines.length; i++) { diff --git a/src/main/java/frc/robot/auto/ShooterFunctions.java b/src/main/java/frc/robot/auto/ShooterFunctions.java index bb48bda5..377768bb 100644 --- a/src/main/java/frc/robot/auto/ShooterFunctions.java +++ b/src/main/java/frc/robot/auto/ShooterFunctions.java @@ -4,75 +4,128 @@ import static edu.wpi.first.units.Units.Inches; import static edu.wpi.first.units.Units.RotationsPerSecond; +import com.team6962.lib.math.CSVLoader; +import edu.wpi.first.units.measure.Angle; +import edu.wpi.first.units.measure.AngularVelocity; +import edu.wpi.first.units.measure.Distance; import java.io.IOException; - import org.apache.commons.math3.analysis.MultivariateFunction; import org.apache.commons.math3.analysis.UnivariateFunction; import org.apache.commons.math3.analysis.interpolation.MicrosphereInterpolator; import org.apache.commons.math3.analysis.interpolation.SplineInterpolator; -import com.team6962.lib.math.CSVLoader; - -import edu.wpi.first.units.measure.Angle; -import edu.wpi.first.units.measure.AngularVelocity; -import edu.wpi.first.units.measure.Distance; - -public class ShooterFunctions{ +public class ShooterFunctions { - private static final String path = "hoodangledata.csv"; - private static final String path2 = "flywheelvelocitydata.csv"; + private static final String path = "hoodangledata.csv"; + private static final String path2 = "flywheelvelocitydata.csv"; - private MultivariateFunction shooterFunction; - private UnivariateFunction flywheelFunction; + private MultivariateFunction shooterFunction; + private UnivariateFunction flywheelFunction; - public ShooterFunctions() { - try { - this.shooterFunction = loadShooterData(); - this.flywheelFunction = loadFlywheelData(); - } catch (IOException e) { - e.printStackTrace(); - } + public ShooterFunctions() { + try { + this.shooterFunction = loadShooterData(); + this.flywheelFunction = loadFlywheelData(); + } catch (IOException e) { + e.printStackTrace(); } + } - private MultivariateFunction loadShooterData() throws IOException { - MicrosphereInterpolator interpolator = new MicrosphereInterpolator(); - double[][] data = CSVLoader.loadCSV(path); - double[][] x = new double[2][data.length]; - for (int i = 0; i < data.length; i++) { - x[0][i] = data[i][0]; - x[1][i] = data[i][1]; - } - double[] y = new double[data.length]; - for (int i = 0; i < data.length; i++) { - y[i] = data[i][2]; - } - return interpolator.interpolate(x, y); + /** + * Loads shooter calibration data from a CSV file and returns an interpolating function. + * + *

The CSV file referenced by the instance field {@code path} is loaded via {@code + * CSVLoader.loadCSV(path)}. Each row of the CSV is expected to contain at least three numeric + * columns: the first two columns are treated as the independent variables and the third column as + * the dependent variable. The method converts the CSV rows into a 2-by-N input array and an + * N-length output array and uses {@code MicrosphereInterpolator} to create a {@link + * org.apache.commons.math3.analysis.MultivariateFunction} that represents the interpolation of + * the provided data. + * + *

The returned {@code MultivariateFunction} accepts a {@code double[]} of length 2 and returns + * an interpolated scalar value for that 2D input. + * + * @return a {@code MultivariateFunction} that interpolates the 2-dimensional input to a scalar + * output using the data loaded from the CSV file + * @throws IOException if an I/O error occurs while reading the CSV file at {@code path} + */ + private MultivariateFunction loadShooterData() throws IOException { + MicrosphereInterpolator interpolator = new MicrosphereInterpolator(); + double[][] data = CSVLoader.loadCSV(path); + double[][] x = new double[2][data.length]; + for (int i = 0; i < data.length; i++) { + x[0][i] = data[i][0]; + x[1][i] = data[i][1]; } + double[] y = new double[data.length]; + for (int i = 0; i < data.length; i++) { + y[i] = data[i][2]; + } + return interpolator.interpolate(x, y); + } - private UnivariateFunction loadFlywheelData() throws IOException { - SplineInterpolator interpolator = new SplineInterpolator(); - double[][] data = CSVLoader.loadCSV(path2); - double[] x = new double[data.length]; - for (int i = 0; i < data.length; i++) { - x[i] = data[i][0]; - } - double[] y = new double[data.length]; - for (int i = 0; i < data.length; i++) { - y[i] = data[i][1]; - } - return interpolator.interpolate(x, y); + /** + * Loads two-column numeric data from the CSV file referenced by the field {@code path2} and + * returns a spline-based interpolating function. + * + *

The CSV is expected to be parsed by {@code CSVLoader.loadCSV(path2)} into a {@code + * double[][]} where each row contains exactly two values: the first column is the independent + * variable (x) and the second column is the dependent variable (y). The method constructs arrays + * of x and y values and uses {@code SplineInterpolator} to create an {@code UnivariateFunction} + * that interpolates the provided points. + * + * @return an {@code UnivariateFunction} representing the spline interpolation of the CSV data + * (f(x) ≈ y) + * @throws IOException if an I/O error occurs while reading the CSV file at {@code path2} + */ + private UnivariateFunction loadFlywheelData() throws IOException { + SplineInterpolator interpolator = new SplineInterpolator(); + double[][] data = CSVLoader.loadCSV(path2); + double[] x = new double[data.length]; + for (int i = 0; i < data.length; i++) { + x[i] = data[i][0]; } - - public MultivariateFunction getShooterFunction() { - return shooterFunction; + double[] y = new double[data.length]; + for (int i = 0; i < data.length; i++) { + y[i] = data[i][1]; } + return interpolator.interpolate(x, y); + } - public Angle getHoodAngle(Distance distance, AngularVelocity velocity) { - return Degrees.of(shooterFunction.value(new double[]{distance.in(Inches), velocity.in(RotationsPerSecond)})); - } + /** + * Returns the MultivariateFunction used by the shooter subsystem to compute shooter setpoints. + * + * @return the configured MultivariateFunction used to compute shooter setpoints, or {@code null} + * if no function has been configured + */ + public MultivariateFunction getShooterFunction() { + return shooterFunction; + } - public AngularVelocity getFlywheelVelocity(Distance distance, Angle angle) { - return RotationsPerSecond.of(flywheelFunction.value(distance.in(Inches))); - } + /** + * Calculates the hood angle required to score given the current distance to the target and the + * shooter wheel angular velocity. + * + * @param distance the distance to the target (will be converted to inches for the internal + * calculation) + * @param velocity the shooter wheel angular velocity (will be converted to rotations per second + * for the internal calculation) + * @return an Angle representing the hood setpoint in degrees needed for the shot + */ + public Angle getHoodAngle(Distance distance, AngularVelocity velocity) { + return Degrees.of( + shooterFunction.value(new double[] {distance.in(Inches), velocity.in(RotationsPerSecond)})); + } + /** + * Calculates the required flywheel angular velocity to reach a target at the specified distance + * and shooter angle. + * + * @param distance the distance to the target; will be converted to inches before evaluation + * @param angle the shooter/target angle (currently unused by this method) + * @return the required flywheel angular velocity as an AngularVelocity (rotations per second) + */ + public AngularVelocity getFlywheelVelocity(Distance distance, Angle angle) { + return RotationsPerSecond.of(flywheelFunction.value(distance.in(Inches))); + } } From 99e3b6d32cbbba21239c158c351601dfd7a232fe Mon Sep 17 00:00:00 2001 From: rahul Date: Fri, 20 Feb 2026 12:08:08 -0800 Subject: [PATCH 08/18] Made comments more clear --- .../java/com/team6962/lib/math/CSVLoader.java | 9 +---- .../java/frc/robot/auto/ShooterFunctions.java | 39 +++++++------------ 2 files changed, 14 insertions(+), 34 deletions(-) diff --git a/src/main/java/com/team6962/lib/math/CSVLoader.java b/src/main/java/com/team6962/lib/math/CSVLoader.java index 37c8aa69..16bf0e21 100644 --- a/src/main/java/com/team6962/lib/math/CSVLoader.java +++ b/src/main/java/com/team6962/lib/math/CSVLoader.java @@ -10,13 +10,6 @@ public class CSVLoader { /** * Loads a CSV file containing floating-point values into a two-dimensional double array. * - *

The provided path is resolved relative to the deploy directory: - * Filesystem.getDeployDirectory() + "/" + path. The file is read using UTF-8 encoding. The file - * contents are split into rows on the newline character ('\n'), and each row is split into - * columns on the comma (',') character. Each column token is parsed with Double.parseDouble and - * stored in the returned double[][]. The resulting array has one entry per line; rows may be - * ragged (different numbers of columns per line). - * * @param path the path to the CSV file relative to the deploy directory * @return a two-dimensional array of doubles where each outer element represents a CSV line and * each inner element represents a parsed numeric value from that line @@ -27,7 +20,7 @@ public static double[][] loadCSV(String path) throws IOException { path = Filesystem.getDeployDirectory() + "/" + path; String csv = FileUtils.readFileToString(new File(path), "UTF-8"); // Read the CSV file as a string - String[] lines = csv.split("\n"); // Splits the strings along lines + String[] lines = csv.split("\n"); // Splits the data along lines double[][] data = new double[lines.length][]; for (int i = 0; i < lines.length; i++) { String[] values = lines[i].split(","); // Splits each line along commas diff --git a/src/main/java/frc/robot/auto/ShooterFunctions.java b/src/main/java/frc/robot/auto/ShooterFunctions.java index 377768bb..215adb0d 100644 --- a/src/main/java/frc/robot/auto/ShooterFunctions.java +++ b/src/main/java/frc/robot/auto/ShooterFunctions.java @@ -16,16 +16,16 @@ public class ShooterFunctions { - private static final String path = "hoodangledata.csv"; - private static final String path2 = "flywheelvelocitydata.csv"; + private static final String anglePath = "hoodangledata.csv"; + private static final String velocityPath = "flywheelvelocitydata.csv"; - private MultivariateFunction shooterFunction; - private UnivariateFunction flywheelFunction; + private MultivariateFunction hoodAngleFunction; + private UnivariateFunction flywheelVelocityFunction; public ShooterFunctions() { try { - this.shooterFunction = loadShooterData(); - this.flywheelFunction = loadFlywheelData(); + this.hoodAngleFunction = loadShooterData(); + this.flywheelVelocityFunction = loadFlywheelData(); } catch (IOException e) { e.printStackTrace(); } @@ -34,14 +34,6 @@ public ShooterFunctions() { /** * Loads shooter calibration data from a CSV file and returns an interpolating function. * - *

The CSV file referenced by the instance field {@code path} is loaded via {@code - * CSVLoader.loadCSV(path)}. Each row of the CSV is expected to contain at least three numeric - * columns: the first two columns are treated as the independent variables and the third column as - * the dependent variable. The method converts the CSV rows into a 2-by-N input array and an - * N-length output array and uses {@code MicrosphereInterpolator} to create a {@link - * org.apache.commons.math3.analysis.MultivariateFunction} that represents the interpolation of - * the provided data. - * *

The returned {@code MultivariateFunction} accepts a {@code double[]} of length 2 and returns * an interpolated scalar value for that 2D input. * @@ -51,7 +43,7 @@ public ShooterFunctions() { */ private MultivariateFunction loadShooterData() throws IOException { MicrosphereInterpolator interpolator = new MicrosphereInterpolator(); - double[][] data = CSVLoader.loadCSV(path); + double[][] data = CSVLoader.loadCSV(anglePath); double[][] x = new double[2][data.length]; for (int i = 0; i < data.length; i++) { x[0][i] = data[i][0]; @@ -68,19 +60,13 @@ private MultivariateFunction loadShooterData() throws IOException { * Loads two-column numeric data from the CSV file referenced by the field {@code path2} and * returns a spline-based interpolating function. * - *

The CSV is expected to be parsed by {@code CSVLoader.loadCSV(path2)} into a {@code - * double[][]} where each row contains exactly two values: the first column is the independent - * variable (x) and the second column is the dependent variable (y). The method constructs arrays - * of x and y values and uses {@code SplineInterpolator} to create an {@code UnivariateFunction} - * that interpolates the provided points. - * * @return an {@code UnivariateFunction} representing the spline interpolation of the CSV data * (f(x) ≈ y) * @throws IOException if an I/O error occurs while reading the CSV file at {@code path2} */ private UnivariateFunction loadFlywheelData() throws IOException { SplineInterpolator interpolator = new SplineInterpolator(); - double[][] data = CSVLoader.loadCSV(path2); + double[][] data = CSVLoader.loadCSV(velocityPath); double[] x = new double[data.length]; for (int i = 0; i < data.length; i++) { x[i] = data[i][0]; @@ -98,8 +84,8 @@ private UnivariateFunction loadFlywheelData() throws IOException { * @return the configured MultivariateFunction used to compute shooter setpoints, or {@code null} * if no function has been configured */ - public MultivariateFunction getShooterFunction() { - return shooterFunction; + public MultivariateFunction getHoodAngleFunction() { + return hoodAngleFunction; } /** @@ -114,7 +100,8 @@ public MultivariateFunction getShooterFunction() { */ public Angle getHoodAngle(Distance distance, AngularVelocity velocity) { return Degrees.of( - shooterFunction.value(new double[] {distance.in(Inches), velocity.in(RotationsPerSecond)})); + hoodAngleFunction.value( + new double[] {distance.in(Inches), velocity.in(RotationsPerSecond)})); } /** @@ -126,6 +113,6 @@ public Angle getHoodAngle(Distance distance, AngularVelocity velocity) { * @return the required flywheel angular velocity as an AngularVelocity (rotations per second) */ public AngularVelocity getFlywheelVelocity(Distance distance, Angle angle) { - return RotationsPerSecond.of(flywheelFunction.value(distance.in(Inches))); + return RotationsPerSecond.of(flywheelVelocityFunction.value(distance.in(Inches))); } } From 9a446f3b77ef3a24c60e0ce68b34f54bf614cc2d Mon Sep 17 00:00:00 2001 From: rahul Date: Sat, 21 Feb 2026 11:48:42 -0800 Subject: [PATCH 09/18] Fixed ShooterFunctions and added clamping --- src/main/java/frc/robot/RobotContainer.java | 13 +++++ .../java/frc/robot/auto/ShooterFunctions.java | 56 +++++++++++++++---- 2 files changed, 58 insertions(+), 11 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index dec4af2c..9633997d 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -17,6 +17,7 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.auto.DriveStraightAuto; +import frc.robot.auto.ShooterFunctions; import frc.robot.constants.RobotConstants; import frc.robot.controls.TeleopControls; import frc.robot.subsystems.climb.Climb; @@ -42,6 +43,7 @@ public class RobotContainer { private final Climb climb; private final Hopper hopper; private final SendableChooser autoChooser = new SendableChooser<>(); + private final ShooterFunctions shooterFunctions; public RobotContainer() { LoggingUtil.logGitProperties(); @@ -67,6 +69,13 @@ public RobotContainer() { driveStraightAuto = new DriveStraightAuto(this); + try { + shooterFunctions = new ShooterFunctions(); + } catch (Exception e) { + e.printStackTrace(); + throw e; + } + configureAutonomousChooser(); } @@ -145,4 +154,8 @@ public Climb getClimb() { public Hopper getHopper() { return hopper; } + + public ShooterFunctions getShooterFunctions() { + return shooterFunctions; + } } diff --git a/src/main/java/frc/robot/auto/ShooterFunctions.java b/src/main/java/frc/robot/auto/ShooterFunctions.java index 215adb0d..a123cdde 100644 --- a/src/main/java/frc/robot/auto/ShooterFunctions.java +++ b/src/main/java/frc/robot/auto/ShooterFunctions.java @@ -5,6 +5,7 @@ import static edu.wpi.first.units.Units.RotationsPerSecond; import com.team6962.lib.math.CSVLoader; +import edu.wpi.first.math.MathUtil; import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Distance; @@ -18,6 +19,8 @@ public class ShooterFunctions { private static final String anglePath = "hoodangledata.csv"; private static final String velocityPath = "flywheelvelocitydata.csv"; + private static final double minDistance = 57.5; + private static final double maxDistance = 263.0; private MultivariateFunction hoodAngleFunction; private UnivariateFunction flywheelVelocityFunction; @@ -26,6 +29,8 @@ public ShooterFunctions() { try { this.hoodAngleFunction = loadShooterData(); this.flywheelVelocityFunction = loadFlywheelData(); + loadShooterData(); + loadFlywheelData(); } catch (IOException e) { e.printStackTrace(); } @@ -44,10 +49,10 @@ public ShooterFunctions() { private MultivariateFunction loadShooterData() throws IOException { MicrosphereInterpolator interpolator = new MicrosphereInterpolator(); double[][] data = CSVLoader.loadCSV(anglePath); - double[][] x = new double[2][data.length]; + double[][] x = new double[data.length][2]; for (int i = 0; i < data.length; i++) { - x[0][i] = data[i][0]; - x[1][i] = data[i][1]; + x[i][0] = data[i][0]; + x[i][1] = data[i][1]; } double[] y = new double[data.length]; for (int i = 0; i < data.length; i++) { @@ -90,7 +95,8 @@ public MultivariateFunction getHoodAngleFunction() { /** * Calculates the hood angle required to score given the current distance to the target and the - * shooter wheel angular velocity. + * shooter wheel angular velocity. Clamps the output to the maximum and minimum hood angles if the + * input distance is outside the valid range. * * @param distance the distance to the target (will be converted to inches for the internal * calculation) @@ -98,21 +104,49 @@ public MultivariateFunction getHoodAngleFunction() { * for the internal calculation) * @return an Angle representing the hood setpoint in degrees needed for the shot */ - public Angle getHoodAngle(Distance distance, AngularVelocity velocity) { - return Degrees.of( - hoodAngleFunction.value( - new double[] {distance.in(Inches), velocity.in(RotationsPerSecond)})); + public Angle getHoodAngle(Distance distance) { + if (isWithinValidRange(distance)) { + return Degrees.of( + hoodAngleFunction.value( + new double[] { + distance.in(Inches), getFlywheelVelocity(distance).in(RotationsPerSecond) + })); + } else + return Degrees.of( + hoodAngleFunction.value( + new double[] { + MathUtil.clamp(distance.in(Inches), minDistance, maxDistance), + getFlywheelVelocity(distance).in(RotationsPerSecond) + })); } /** * Calculates the required flywheel angular velocity to reach a target at the specified distance - * and shooter angle. + * and shooter angle. Clamps the output to the maximum and minimum flywheel velocities if the + * input distance is outside the valid range. * * @param distance the distance to the target; will be converted to inches before evaluation * @param angle the shooter/target angle (currently unused by this method) * @return the required flywheel angular velocity as an AngularVelocity (rotations per second) */ - public AngularVelocity getFlywheelVelocity(Distance distance, Angle angle) { - return RotationsPerSecond.of(flywheelVelocityFunction.value(distance.in(Inches))); + public AngularVelocity getFlywheelVelocity(Distance distance) { + if (isWithinValidRange(distance)) { + return RotationsPerSecond.of(flywheelVelocityFunction.value(distance.in(Inches))); + } else + return RotationsPerSecond.of( + flywheelVelocityFunction.value( + MathUtil.clamp(distance.in(Inches), minDistance, maxDistance))); + } + + /** + * Determines whether the given distance falls within the configured valid range. + * + * @param distance the Distance to check; will be converted to inches for comparison + * @return true if the distance (in inches) is greater than or equal to minDistance and less than + * or equal to maxDistance + */ + public boolean isWithinValidRange(Distance distance) { + double distanceInInches = distance.in(Inches); + return distanceInInches >= minDistance && distanceInInches <= maxDistance; } } From 2096f819333874fac772dd3c00dd3b0662a05c51 Mon Sep 17 00:00:00 2001 From: scotch-tape <156549340+scotch-tape@users.noreply.github.com> Date: Sat, 21 Feb 2026 19:52:14 +0000 Subject: [PATCH 10/18] style: Apply Spotless fixes --- src/main/java/frc/robot/RobotContainer.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 3eb19c11..6a8395bb 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -162,7 +162,7 @@ public Hopper getHopper() { public ShooterFunctions getShooterFunctions() { return shooterFunctions; } - + public RobotVisualizer getVisualizer() { return visualizer; } From cfc47538785afe216a9a6f75144d84575fb7a5ff Mon Sep 17 00:00:00 2001 From: rahul Date: Sat, 21 Feb 2026 11:53:27 -0800 Subject: [PATCH 11/18] applied spotless --- src/main/java/frc/robot/RobotContainer.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 3eb19c11..6a8395bb 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -162,7 +162,7 @@ public Hopper getHopper() { public ShooterFunctions getShooterFunctions() { return shooterFunctions; } - + public RobotVisualizer getVisualizer() { return visualizer; } From ce021c772a9cf1d27abfaa606b6525924a7d8175 Mon Sep 17 00:00:00 2001 From: rahul Date: Sat, 21 Feb 2026 14:25:25 -0800 Subject: [PATCH 12/18] Added passing to ShooterFunctions --- .../deploy/passingflywheelvelocitydata.csv | 0 src/main/deploy/passinghoodangledata.csv | 0 .../java/frc/robot/auto/ShooterFunctions.java | 199 +++++++++++++++--- 3 files changed, 166 insertions(+), 33 deletions(-) create mode 100644 src/main/deploy/passingflywheelvelocitydata.csv create mode 100644 src/main/deploy/passinghoodangledata.csv diff --git a/src/main/deploy/passingflywheelvelocitydata.csv b/src/main/deploy/passingflywheelvelocitydata.csv new file mode 100644 index 00000000..e69de29b diff --git a/src/main/deploy/passinghoodangledata.csv b/src/main/deploy/passinghoodangledata.csv new file mode 100644 index 00000000..e69de29b diff --git a/src/main/java/frc/robot/auto/ShooterFunctions.java b/src/main/java/frc/robot/auto/ShooterFunctions.java index a123cdde..d77f0bfa 100644 --- a/src/main/java/frc/robot/auto/ShooterFunctions.java +++ b/src/main/java/frc/robot/auto/ShooterFunctions.java @@ -16,21 +16,45 @@ import org.apache.commons.math3.analysis.interpolation.SplineInterpolator; public class ShooterFunctions { + /** Path to the CSV file containing 2D hood angle calibration data for hub shots. */ + private static final String anglePathHub = "hoodangledata.csv"; - private static final String anglePath = "hoodangledata.csv"; - private static final String velocityPath = "flywheelvelocitydata.csv"; - private static final double minDistance = 57.5; - private static final double maxDistance = 263.0; + /** Path to the CSV file containing 2-column flywheel velocity calibration data for hub shots. */ + private static final String velocityPathHub = "flywheelvelocitydata.csv"; - private MultivariateFunction hoodAngleFunction; - private UnivariateFunction flywheelVelocityFunction; + /** Path to the CSV file containing hood angle calibration data for passing. */ + private static final String anglePathPass = "passinghoodangledata.csv"; + + /** Path to the CSV file containing flywheel velocity calibration data for passing. */ + private static final String velocityPathPass = "passingflywheelvelocitydata.csv"; + + /** Minimum valid distance to the target for hub shots, in inches. */ + private static final double minDistanceHub = 57.5; // Calibrated for our shooter A testing + + /** Maximum valid distance to the target for hub shots, in inches. */ + private static final double maxDistanceHub = 263.0; // Calibrated for our shooter A testing + + /** Minimum valid distance to the target for passing, in inches. */ + private static final double minDistancePass = 57.5; // Needs to be changed + + /** Maximum valid distance to the target for passing, in inches. */ + private static final double maxDistancePass = 263.0; // Needs to be changed + + private MultivariateFunction hoodAngleFunctionHub; + private UnivariateFunction flywheelVelocityFunctionHub; + private UnivariateFunction hoodAngleFunctionPass; + private UnivariateFunction flywheelVelocityFunctionPass; public ShooterFunctions() { try { - this.hoodAngleFunction = loadShooterData(); - this.flywheelVelocityFunction = loadFlywheelData(); - loadShooterData(); - loadFlywheelData(); + this.hoodAngleFunctionHub = loadHoodAngleDataHub(); + this.flywheelVelocityFunctionHub = loadFlywheelDataHub(); + this.hoodAngleFunctionPass = loadHoodAngleDataPass(); + this.flywheelVelocityFunctionPass = loadFlywheelDataPass(); + loadHoodAngleDataHub(); + loadFlywheelDataHub(); + loadHoodAngleDataPass(); + loadFlywheelDataPass(); } catch (IOException e) { e.printStackTrace(); } @@ -46,9 +70,9 @@ public ShooterFunctions() { * output using the data loaded from the CSV file * @throws IOException if an I/O error occurs while reading the CSV file at {@code path} */ - private MultivariateFunction loadShooterData() throws IOException { + private MultivariateFunction loadHoodAngleDataHub() throws IOException { MicrosphereInterpolator interpolator = new MicrosphereInterpolator(); - double[][] data = CSVLoader.loadCSV(anglePath); + double[][] data = CSVLoader.loadCSV(anglePathHub); double[][] x = new double[data.length][2]; for (int i = 0; i < data.length; i++) { x[i][0] = data[i][0]; @@ -69,9 +93,9 @@ private MultivariateFunction loadShooterData() throws IOException { * (f(x) ≈ y) * @throws IOException if an I/O error occurs while reading the CSV file at {@code path2} */ - private UnivariateFunction loadFlywheelData() throws IOException { + private UnivariateFunction loadFlywheelDataHub() throws IOException { SplineInterpolator interpolator = new SplineInterpolator(); - double[][] data = CSVLoader.loadCSV(velocityPath); + double[][] data = CSVLoader.loadCSV(velocityPathHub); double[] x = new double[data.length]; for (int i = 0; i < data.length; i++) { x[i] = data[i][0]; @@ -83,14 +107,75 @@ private UnivariateFunction loadFlywheelData() throws IOException { return interpolator.interpolate(x, y); } + private UnivariateFunction loadHoodAngleDataPass() throws IOException { + SplineInterpolator interpolator = new SplineInterpolator(); + double[][] data = CSVLoader.loadCSV(anglePathPass); + double[] x = new double[data.length]; + for (int i = 0; i < data.length; i++) { + x[i] = data[i][0]; + } + double[] y = new double[data.length]; + for (int i = 0; i < data.length; i++) { + y[i] = data[i][2]; + } + return interpolator.interpolate(x, y); + } + + private UnivariateFunction loadFlywheelDataPass() throws IOException { + SplineInterpolator interpolator = new SplineInterpolator(); + double[][] data = CSVLoader.loadCSV(velocityPathPass); + double[] x = new double[data.length]; + for (int i = 0; i < data.length; i++) { + x[i] = data[i][0]; + } + double[] y = new double[data.length]; + for (int i = 0; i < data.length; i++) { + y[i] = data[i][1]; + } + return interpolator.interpolate(x, y); + } + + /** + * Returns the MultivariateFunction used by the shooter subsystem to compute hood angle setpoints. + * + * @return the configured MultivariateFunction used to compute hood angle setpoints, or {@code + * null} if no function has been configured + */ + public MultivariateFunction getHoodAngleFunctionHub() { + return hoodAngleFunctionHub; + } + /** - * Returns the MultivariateFunction used by the shooter subsystem to compute shooter setpoints. + * Returns the UnivariateFunction used by the shooter subsystem to compute flywheel velocity + * setpoints. * - * @return the configured MultivariateFunction used to compute shooter setpoints, or {@code null} - * if no function has been configured + * @return the configured UnivariateFunction used to compute flywheel velocity setpoints, or + * {@code null} if no function has been configured */ - public MultivariateFunction getHoodAngleFunction() { - return hoodAngleFunction; + public UnivariateFunction getFlywheelVelocityFunctionHub() { + return flywheelVelocityFunctionHub; + } + + /** + * Returns the UnivariateFunction used by the shooter subsystem to compute hood angle setpoints + * for passing. + * + * @return the configured UnivariateFunction used to compute hood angle setpoints for passing, or + * {@code null} if no function has been configured + */ + public UnivariateFunction getHoodAngleFunctionPass() { + return hoodAngleFunctionPass; + } + + /** + * Returns the UnivariateFunction used by the shooter subsystem to compute flywheel velocity + * setpoints for passing. + * + * @return the configured UnivariateFunction used to compute flywheel velocity setpoints for + * passing, or {@code null} if no function has been configured + */ + public UnivariateFunction getFlywheelVelocityFunctionPass() { + return flywheelVelocityFunctionPass; } /** @@ -104,19 +189,19 @@ public MultivariateFunction getHoodAngleFunction() { * for the internal calculation) * @return an Angle representing the hood setpoint in degrees needed for the shot */ - public Angle getHoodAngle(Distance distance) { - if (isWithinValidRange(distance)) { + public Angle getHoodAngleHub(Distance distance) { + if (isWithinValidHubRange(distance)) { return Degrees.of( - hoodAngleFunction.value( + hoodAngleFunctionHub.value( new double[] { - distance.in(Inches), getFlywheelVelocity(distance).in(RotationsPerSecond) + distance.in(Inches), getFlywheelVelocityHub(distance).in(RotationsPerSecond) })); } else return Degrees.of( - hoodAngleFunction.value( + hoodAngleFunctionHub.value( new double[] { - MathUtil.clamp(distance.in(Inches), minDistance, maxDistance), - getFlywheelVelocity(distance).in(RotationsPerSecond) + MathUtil.clamp(distance.in(Inches), minDistanceHub, maxDistanceHub), + getFlywheelVelocityHub(distance).in(RotationsPerSecond) })); } @@ -129,13 +214,49 @@ public Angle getHoodAngle(Distance distance) { * @param angle the shooter/target angle (currently unused by this method) * @return the required flywheel angular velocity as an AngularVelocity (rotations per second) */ - public AngularVelocity getFlywheelVelocity(Distance distance) { - if (isWithinValidRange(distance)) { - return RotationsPerSecond.of(flywheelVelocityFunction.value(distance.in(Inches))); + public AngularVelocity getFlywheelVelocityHub(Distance distance) { + if (isWithinValidHubRange(distance)) { + return RotationsPerSecond.of(flywheelVelocityFunctionHub.value(distance.in(Inches))); + } else + return RotationsPerSecond.of( + flywheelVelocityFunctionHub.value( + MathUtil.clamp(distance.in(Inches), minDistanceHub, maxDistanceHub))); + } + + /** + * Calculates the hood angle required for passing given the current distance to the target. Clamps + * the output to the maximum and minimum hood angles if the input distance is outside the valid + * range. + * + * @param distance the distance to the target (will be converted to inches for the internal + * calculation) + * @return an Angle representing the hood setpoint in degrees needed for passing + */ + public Angle getHoodAnglePass(Distance distance) { + if (isWithinValidPassRange(distance)) { + return Degrees.of(hoodAngleFunctionPass.value(distance.in(Inches))); + } else + return Degrees.of( + hoodAngleFunctionPass.value( + MathUtil.clamp(distance.in(Inches), minDistancePass, maxDistancePass))); + } + + /** + * Calculates the required flywheel angular velocity for passing given the current distance to the + * target. Clamps the output to the maximum and minimum flywheel velocities if the input distance + * is outside the valid range. + * + * @param distance the distance to the target; will be converted to inches before evaluation + * @return the required flywheel angular velocity for passing as an AngularVelocity (rotations per + * second) + */ + public AngularVelocity getFlywheelVelocityPass(Distance distance) { + if (isWithinValidPassRange(distance)) { + return RotationsPerSecond.of(flywheelVelocityFunctionPass.value(distance.in(Inches))); } else return RotationsPerSecond.of( - flywheelVelocityFunction.value( - MathUtil.clamp(distance.in(Inches), minDistance, maxDistance))); + flywheelVelocityFunctionPass.value( + MathUtil.clamp(distance.in(Inches), minDistancePass, maxDistancePass))); } /** @@ -145,8 +266,20 @@ public AngularVelocity getFlywheelVelocity(Distance distance) { * @return true if the distance (in inches) is greater than or equal to minDistance and less than * or equal to maxDistance */ - public boolean isWithinValidRange(Distance distance) { + public boolean isWithinValidHubRange(Distance distance) { + double distanceInInches = distance.in(Inches); + return distanceInInches >= minDistanceHub && distanceInInches <= maxDistanceHub; + } + + /** + * Determines whether the given distance falls within the configured valid range for passing. + * + * @param distance the Distance to check; will be converted to inches for comparison + * @return true if the distance (in inches) is greater than or equal to minDistancePass and less + * than or equal to maxDistancePass + */ + public boolean isWithinValidPassRange(Distance distance) { double distanceInInches = distance.in(Inches); - return distanceInInches >= minDistance && distanceInInches <= maxDistance; + return distanceInInches >= minDistancePass && distanceInInches <= maxDistancePass; } } From 37f7a886bba8e7d3e08bf7e45d911fb474033f98 Mon Sep 17 00:00:00 2001 From: rahul Date: Sat, 21 Feb 2026 14:32:23 -0800 Subject: [PATCH 13/18] removed some testing code --- src/main/java/frc/robot/auto/ShooterFunctions.java | 4 ---- 1 file changed, 4 deletions(-) diff --git a/src/main/java/frc/robot/auto/ShooterFunctions.java b/src/main/java/frc/robot/auto/ShooterFunctions.java index d77f0bfa..9b3b2646 100644 --- a/src/main/java/frc/robot/auto/ShooterFunctions.java +++ b/src/main/java/frc/robot/auto/ShooterFunctions.java @@ -51,10 +51,6 @@ public ShooterFunctions() { this.flywheelVelocityFunctionHub = loadFlywheelDataHub(); this.hoodAngleFunctionPass = loadHoodAngleDataPass(); this.flywheelVelocityFunctionPass = loadFlywheelDataPass(); - loadHoodAngleDataHub(); - loadFlywheelDataHub(); - loadHoodAngleDataPass(); - loadFlywheelDataPass(); } catch (IOException e) { e.printStackTrace(); } From 223709db1a57294ef5f367ad224f08df1610b3b8 Mon Sep 17 00:00:00 2001 From: rahul Date: Sat, 21 Feb 2026 14:38:00 -0800 Subject: [PATCH 14/18] Made some fixes --- .../java/frc/robot/auto/ShooterFunctions.java | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/auto/ShooterFunctions.java b/src/main/java/frc/robot/auto/ShooterFunctions.java index 9b3b2646..9afb601b 100644 --- a/src/main/java/frc/robot/auto/ShooterFunctions.java +++ b/src/main/java/frc/robot/auto/ShooterFunctions.java @@ -185,12 +185,12 @@ public UnivariateFunction getFlywheelVelocityFunctionPass() { * for the internal calculation) * @return an Angle representing the hood setpoint in degrees needed for the shot */ - public Angle getHoodAngleHub(Distance distance) { - if (isWithinValidHubRange(distance)) { + public Angle getHoodAngleHub(Distance distance, AngularVelocity velocity) { + if (isDistanceWithinValidHubRange(distance)) { return Degrees.of( hoodAngleFunctionHub.value( new double[] { - distance.in(Inches), getFlywheelVelocityHub(distance).in(RotationsPerSecond) + distance.in(Inches), velocity.in(RotationsPerSecond) })); } else return Degrees.of( @@ -211,7 +211,7 @@ public Angle getHoodAngleHub(Distance distance) { * @return the required flywheel angular velocity as an AngularVelocity (rotations per second) */ public AngularVelocity getFlywheelVelocityHub(Distance distance) { - if (isWithinValidHubRange(distance)) { + if (isDistanceWithinValidHubRange(distance)) { return RotationsPerSecond.of(flywheelVelocityFunctionHub.value(distance.in(Inches))); } else return RotationsPerSecond.of( @@ -229,7 +229,7 @@ public AngularVelocity getFlywheelVelocityHub(Distance distance) { * @return an Angle representing the hood setpoint in degrees needed for passing */ public Angle getHoodAnglePass(Distance distance) { - if (isWithinValidPassRange(distance)) { + if (isDistanceWithinValidPassRange(distance)) { return Degrees.of(hoodAngleFunctionPass.value(distance.in(Inches))); } else return Degrees.of( @@ -247,7 +247,7 @@ public Angle getHoodAnglePass(Distance distance) { * second) */ public AngularVelocity getFlywheelVelocityPass(Distance distance) { - if (isWithinValidPassRange(distance)) { + if (isDistanceWithinValidPassRange(distance)) { return RotationsPerSecond.of(flywheelVelocityFunctionPass.value(distance.in(Inches))); } else return RotationsPerSecond.of( @@ -262,7 +262,7 @@ public AngularVelocity getFlywheelVelocityPass(Distance distance) { * @return true if the distance (in inches) is greater than or equal to minDistance and less than * or equal to maxDistance */ - public boolean isWithinValidHubRange(Distance distance) { + public boolean isDistanceWithinValidHubRange(Distance distance) { double distanceInInches = distance.in(Inches); return distanceInInches >= minDistanceHub && distanceInInches <= maxDistanceHub; } @@ -274,7 +274,7 @@ public boolean isWithinValidHubRange(Distance distance) { * @return true if the distance (in inches) is greater than or equal to minDistancePass and less * than or equal to maxDistancePass */ - public boolean isWithinValidPassRange(Distance distance) { + public boolean isDistanceWithinValidPassRange(Distance distance) { double distanceInInches = distance.in(Inches); return distanceInInches >= minDistancePass && distanceInInches <= maxDistancePass; } From 4085e5833f5d0b1fafec1800f59d5d11f2a0c531 Mon Sep 17 00:00:00 2001 From: rahul Date: Sat, 21 Feb 2026 14:38:34 -0800 Subject: [PATCH 15/18] applied spotless --- src/main/java/frc/robot/auto/ShooterFunctions.java | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/auto/ShooterFunctions.java b/src/main/java/frc/robot/auto/ShooterFunctions.java index 9afb601b..5defd2ae 100644 --- a/src/main/java/frc/robot/auto/ShooterFunctions.java +++ b/src/main/java/frc/robot/auto/ShooterFunctions.java @@ -189,9 +189,7 @@ public Angle getHoodAngleHub(Distance distance, AngularVelocity velocity) { if (isDistanceWithinValidHubRange(distance)) { return Degrees.of( hoodAngleFunctionHub.value( - new double[] { - distance.in(Inches), velocity.in(RotationsPerSecond) - })); + new double[] {distance.in(Inches), velocity.in(RotationsPerSecond)})); } else return Degrees.of( hoodAngleFunctionHub.value( From 51f24f5f389c28dec344935092b0de6f3fd49835 Mon Sep 17 00:00:00 2001 From: rahul Date: Sat, 21 Feb 2026 15:09:43 -0800 Subject: [PATCH 16/18] Added a within velocity range check to shooterfunctions --- ...tydata.csv => flywheelvelocitydatahub.csv} | 0 ...hoodangledata.csv => hoodangledatahub.csv} | 0 src/main/deploy/velocityrangehub.csv | 0 .../java/frc/robot/auto/ShooterFunctions.java | 101 +++++++++++++++--- 4 files changed, 89 insertions(+), 12 deletions(-) rename src/main/deploy/{flywheelvelocitydata.csv => flywheelvelocitydatahub.csv} (100%) rename src/main/deploy/{hoodangledata.csv => hoodangledatahub.csv} (100%) create mode 100644 src/main/deploy/velocityrangehub.csv diff --git a/src/main/deploy/flywheelvelocitydata.csv b/src/main/deploy/flywheelvelocitydatahub.csv similarity index 100% rename from src/main/deploy/flywheelvelocitydata.csv rename to src/main/deploy/flywheelvelocitydatahub.csv diff --git a/src/main/deploy/hoodangledata.csv b/src/main/deploy/hoodangledatahub.csv similarity index 100% rename from src/main/deploy/hoodangledata.csv rename to src/main/deploy/hoodangledatahub.csv diff --git a/src/main/deploy/velocityrangehub.csv b/src/main/deploy/velocityrangehub.csv new file mode 100644 index 00000000..e69de29b diff --git a/src/main/java/frc/robot/auto/ShooterFunctions.java b/src/main/java/frc/robot/auto/ShooterFunctions.java index 5defd2ae..423d0672 100644 --- a/src/main/java/frc/robot/auto/ShooterFunctions.java +++ b/src/main/java/frc/robot/auto/ShooterFunctions.java @@ -16,18 +16,21 @@ import org.apache.commons.math3.analysis.interpolation.SplineInterpolator; public class ShooterFunctions { - /** Path to the CSV file containing 2D hood angle calibration data for hub shots. */ - private static final String anglePathHub = "hoodangledata.csv"; + /** Path to the CSV file containing 2D hood angle calibration data for hub shots. Formatted as Distance, Velocity, Angle */ + private static final String anglePathHub = "hoodangledatahub.csv"; - /** Path to the CSV file containing 2-column flywheel velocity calibration data for hub shots. */ - private static final String velocityPathHub = "flywheelvelocitydata.csv"; + /** Path to the CSV file containing 2-column flywheel velocity calibration data for hub shots. Formatted as Distance, Velocity */ + private static final String velocityPathHub = "flywheelvelocitydatahub.csv"; - /** Path to the CSV file containing hood angle calibration data for passing. */ + /** Path to the CSV file containing hood angle calibration data for passing. Formatted as Distance, Angle */ private static final String anglePathPass = "passinghoodangledata.csv"; - /** Path to the CSV file containing flywheel velocity calibration data for passing. */ + /** Path to the CSV file containing flywheel velocity calibration data for passing. Formatted as Distance, Velocity */ private static final String velocityPathPass = "passingflywheelvelocitydata.csv"; + /** Path to the CSV file containing minimum and maximum velocities to shoot at. Formatted as Distance, Velocity, Angle */ + private static final String velocityRangeHub = "velocityrangehub.csv"; + /** Minimum valid distance to the target for hub shots, in inches. */ private static final double minDistanceHub = 57.5; // Calibrated for our shooter A testing @@ -44,6 +47,8 @@ public class ShooterFunctions { private UnivariateFunction flywheelVelocityFunctionHub; private UnivariateFunction hoodAngleFunctionPass; private UnivariateFunction flywheelVelocityFunctionPass; + private UnivariateFunction minVelocityHub; + private UnivariateFunction maxVelocityHub; public ShooterFunctions() { try { @@ -51,6 +56,8 @@ public ShooterFunctions() { this.flywheelVelocityFunctionHub = loadFlywheelDataHub(); this.hoodAngleFunctionPass = loadHoodAngleDataPass(); this.flywheelVelocityFunctionPass = loadFlywheelDataPass(); + this.minVelocityHub = loadMinVelocityHub(); + this.maxVelocityHub = loadMaxVelocityHub(); } catch (IOException e) { e.printStackTrace(); } @@ -103,6 +110,13 @@ private UnivariateFunction loadFlywheelDataHub() throws IOException { return interpolator.interpolate(x, y); } + /** + * Loads shooter calibration data for passing from a CSV file and returns an interpolating function. + * + * @return a {@code UnivariateFunction} that interpolates the distance to a hood angle setpoint + * using the data loaded from the CSV file + * @throws IOException if an I/O error occurs while reading the CSV file at {@code anglePathPass} + */ private UnivariateFunction loadHoodAngleDataPass() throws IOException { SplineInterpolator interpolator = new SplineInterpolator(); double[][] data = CSVLoader.loadCSV(anglePathPass); @@ -116,7 +130,15 @@ private UnivariateFunction loadHoodAngleDataPass() throws IOException { } return interpolator.interpolate(x, y); } - + + /** + * Loads flywheel velocity calibration data for passing from a CSV file and returns an interpolating + * function. + * + * @return a {@code UnivariateFunction} that interpolates the distance to a flywheel velocity + * setpoint using the data loaded from the CSV file + * @throws IOException if an I/O error occurs while reading the CSV file at {@code velocityPathPass} + */ private UnivariateFunction loadFlywheelDataPass() throws IOException { SplineInterpolator interpolator = new SplineInterpolator(); double[][] data = CSVLoader.loadCSV(velocityPathPass); @@ -130,6 +152,50 @@ private UnivariateFunction loadFlywheelDataPass() throws IOException { } return interpolator.interpolate(x, y); } + + /** + * Loads minimum flywheel velocity data for hub shots from a CSV file and returns an + * interpolating function. + * + * @return a {@code UnivariateFunction} that interpolates the distance to a velocity setpoint + * using the data loaded from the CSV file + * @throws IOException if an I/O error occurs while reading the CSV file at {@code velocityRangeHub} + */ + private UnivariateFunction loadMinVelocityHub() throws IOException { + SplineInterpolator interpolator = new SplineInterpolator(); + double[][] data = CSVLoader.loadCSV(velocityRangeHub); + double[] x = new double[data.length]; + for (int i = 0; i < data.length; i++) { + x[i] = data[i][0]; + } + double[] y = new double[data.length]; + for (int i = 0; i < data.length; i++) { + y[i] = data[i][1]; + } + return interpolator.interpolate(x, y); + } + + /** + * Loads maximum flywheel velocity data for hub shots from a CSV file and returns an + * interpolating function. + * + * @return a {@code UnivariateFunction} that interpolates the distance to a velocity setpoint + * using the data loaded from the CSV file + * @throws IOException if an I/O error occurs while reading the CSV file at {@code velocityRangeHub} + */ + private UnivariateFunction loadMaxVelocityHub() throws IOException { + SplineInterpolator interpolator = new SplineInterpolator(); + double[][] data = CSVLoader.loadCSV(velocityRangeHub); + double[] x = new double[data.length]; + for (int i = 0; i < data.length; i++) { + x[i] = data[i][0]; + } + double[] y = new double[data.length]; + for (int i = 0; i < data.length; i++) { + y[i] = data[i][2]; + } + return interpolator.interpolate(x, y); + } /** * Returns the MultivariateFunction used by the shooter subsystem to compute hood angle setpoints. @@ -186,17 +252,22 @@ public UnivariateFunction getFlywheelVelocityFunctionPass() { * @return an Angle representing the hood setpoint in degrees needed for the shot */ public Angle getHoodAngleHub(Distance distance, AngularVelocity velocity) { - if (isDistanceWithinValidHubRange(distance)) { + if (isDistanceWithinValidHubRange(distance) && isVelocityWithinValidHubRange(distance, velocity)) { return Degrees.of( hoodAngleFunctionHub.value( new double[] {distance.in(Inches), velocity.in(RotationsPerSecond)})); - } else + } else if (isVelocityWithinValidHubRange(distance, velocity)) { return Degrees.of( hoodAngleFunctionHub.value( new double[] { - MathUtil.clamp(distance.in(Inches), minDistanceHub, maxDistanceHub), - getFlywheelVelocityHub(distance).in(RotationsPerSecond) - })); + MathUtil.clamp(distance.in(Inches), minDistanceHub, maxDistanceHub), velocity.in(RotationsPerSecond)})); + } else return Degrees.of( + hoodAngleFunctionHub.value( + new double[] { + MathUtil.clamp(distance.in(Inches), minDistanceHub, maxDistanceHub), + MathUtil.clamp(velocity.in(RotationsPerSecond), minVelocityHub.value(distance.in(Inches)), maxVelocityHub.value(distance.in(Inches))) + })); + } /** @@ -265,6 +336,12 @@ public boolean isDistanceWithinValidHubRange(Distance distance) { return distanceInInches >= minDistanceHub && distanceInInches <= maxDistanceHub; } + public boolean isVelocityWithinValidHubRange(Distance distance, AngularVelocity velocity) { + double velocityInRPS = velocity.in(RotationsPerSecond); + return velocityInRPS >= minVelocityHub.value(distance.in(Inches)) + && velocityInRPS <= maxVelocityHub.value(distance.in(Inches)); + } + /** * Determines whether the given distance falls within the configured valid range for passing. * From 77d7cfc3b6536dd90889a6505f455d86ee94f8e1 Mon Sep 17 00:00:00 2001 From: scotch-tape <156549340+scotch-tape@users.noreply.github.com> Date: Sat, 21 Feb 2026 23:11:13 +0000 Subject: [PATCH 17/18] style: Apply Spotless fixes --- .../java/frc/robot/auto/ShooterFunctions.java | 81 ++++++++++++------- 1 file changed, 53 insertions(+), 28 deletions(-) diff --git a/src/main/java/frc/robot/auto/ShooterFunctions.java b/src/main/java/frc/robot/auto/ShooterFunctions.java index 423d0672..d06d866d 100644 --- a/src/main/java/frc/robot/auto/ShooterFunctions.java +++ b/src/main/java/frc/robot/auto/ShooterFunctions.java @@ -16,20 +16,35 @@ import org.apache.commons.math3.analysis.interpolation.SplineInterpolator; public class ShooterFunctions { - /** Path to the CSV file containing 2D hood angle calibration data for hub shots. Formatted as Distance, Velocity, Angle */ - private static final String anglePathHub = "hoodangledatahub.csv"; + /** + * Path to the CSV file containing 2D hood angle calibration data for hub shots. Formatted as + * Distance, Velocity, Angle + */ + private static final String anglePathHub = "hoodangledatahub.csv"; - /** Path to the CSV file containing 2-column flywheel velocity calibration data for hub shots. Formatted as Distance, Velocity */ + /** + * Path to the CSV file containing 2-column flywheel velocity calibration data for hub shots. + * Formatted as Distance, Velocity + */ private static final String velocityPathHub = "flywheelvelocitydatahub.csv"; - /** Path to the CSV file containing hood angle calibration data for passing. Formatted as Distance, Angle */ + /** + * Path to the CSV file containing hood angle calibration data for passing. Formatted as Distance, + * Angle + */ private static final String anglePathPass = "passinghoodangledata.csv"; - /** Path to the CSV file containing flywheel velocity calibration data for passing. Formatted as Distance, Velocity */ + /** + * Path to the CSV file containing flywheel velocity calibration data for passing. Formatted as + * Distance, Velocity + */ private static final String velocityPathPass = "passingflywheelvelocitydata.csv"; - /** Path to the CSV file containing minimum and maximum velocities to shoot at. Formatted as Distance, Velocity, Angle */ - private static final String velocityRangeHub = "velocityrangehub.csv"; + /** + * Path to the CSV file containing minimum and maximum velocities to shoot at. Formatted as + * Distance, Velocity, Angle + */ + private static final String velocityRangeHub = "velocityrangehub.csv"; /** Minimum valid distance to the target for hub shots, in inches. */ private static final double minDistanceHub = 57.5; // Calibrated for our shooter A testing @@ -111,7 +126,8 @@ private UnivariateFunction loadFlywheelDataHub() throws IOException { } /** - * Loads shooter calibration data for passing from a CSV file and returns an interpolating function. + * Loads shooter calibration data for passing from a CSV file and returns an interpolating + * function. * * @return a {@code UnivariateFunction} that interpolates the distance to a hood angle setpoint * using the data loaded from the CSV file @@ -130,14 +146,15 @@ private UnivariateFunction loadHoodAngleDataPass() throws IOException { } return interpolator.interpolate(x, y); } - + /** - * Loads flywheel velocity calibration data for passing from a CSV file and returns an interpolating - * function. + * Loads flywheel velocity calibration data for passing from a CSV file and returns an + * interpolating function. * * @return a {@code UnivariateFunction} that interpolates the distance to a flywheel velocity * setpoint using the data loaded from the CSV file - * @throws IOException if an I/O error occurs while reading the CSV file at {@code velocityPathPass} + * @throws IOException if an I/O error occurs while reading the CSV file at {@code + * velocityPathPass} */ private UnivariateFunction loadFlywheelDataPass() throws IOException { SplineInterpolator interpolator = new SplineInterpolator(); @@ -152,14 +169,15 @@ private UnivariateFunction loadFlywheelDataPass() throws IOException { } return interpolator.interpolate(x, y); } - + /** - * Loads minimum flywheel velocity data for hub shots from a CSV file and returns an - * interpolating function. + * Loads minimum flywheel velocity data for hub shots from a CSV file and returns an interpolating + * function. * * @return a {@code UnivariateFunction} that interpolates the distance to a velocity setpoint * using the data loaded from the CSV file - * @throws IOException if an I/O error occurs while reading the CSV file at {@code velocityRangeHub} + * @throws IOException if an I/O error occurs while reading the CSV file at {@code + * velocityRangeHub} */ private UnivariateFunction loadMinVelocityHub() throws IOException { SplineInterpolator interpolator = new SplineInterpolator(); @@ -176,12 +194,13 @@ private UnivariateFunction loadMinVelocityHub() throws IOException { } /** - * Loads maximum flywheel velocity data for hub shots from a CSV file and returns an - * interpolating function. + * Loads maximum flywheel velocity data for hub shots from a CSV file and returns an interpolating + * function. * * @return a {@code UnivariateFunction} that interpolates the distance to a velocity setpoint * using the data loaded from the CSV file - * @throws IOException if an I/O error occurs while reading the CSV file at {@code velocityRangeHub} + * @throws IOException if an I/O error occurs while reading the CSV file at {@code + * velocityRangeHub} */ private UnivariateFunction loadMaxVelocityHub() throws IOException { SplineInterpolator interpolator = new SplineInterpolator(); @@ -252,7 +271,8 @@ public UnivariateFunction getFlywheelVelocityFunctionPass() { * @return an Angle representing the hood setpoint in degrees needed for the shot */ public Angle getHoodAngleHub(Distance distance, AngularVelocity velocity) { - if (isDistanceWithinValidHubRange(distance) && isVelocityWithinValidHubRange(distance, velocity)) { + if (isDistanceWithinValidHubRange(distance) + && isVelocityWithinValidHubRange(distance, velocity)) { return Degrees.of( hoodAngleFunctionHub.value( new double[] {distance.in(Inches), velocity.in(RotationsPerSecond)})); @@ -260,14 +280,19 @@ public Angle getHoodAngleHub(Distance distance, AngularVelocity velocity) { return Degrees.of( hoodAngleFunctionHub.value( new double[] { - MathUtil.clamp(distance.in(Inches), minDistanceHub, maxDistanceHub), velocity.in(RotationsPerSecond)})); - } else return Degrees.of( - hoodAngleFunctionHub.value( - new double[] { - MathUtil.clamp(distance.in(Inches), minDistanceHub, maxDistanceHub), - MathUtil.clamp(velocity.in(RotationsPerSecond), minVelocityHub.value(distance.in(Inches)), maxVelocityHub.value(distance.in(Inches))) - })); - + MathUtil.clamp(distance.in(Inches), minDistanceHub, maxDistanceHub), + velocity.in(RotationsPerSecond) + })); + } else + return Degrees.of( + hoodAngleFunctionHub.value( + new double[] { + MathUtil.clamp(distance.in(Inches), minDistanceHub, maxDistanceHub), + MathUtil.clamp( + velocity.in(RotationsPerSecond), + minVelocityHub.value(distance.in(Inches)), + maxVelocityHub.value(distance.in(Inches))) + })); } /** From b3ce106da730ab214e1f00a6aa189cfb185f89c8 Mon Sep 17 00:00:00 2001 From: Brian <74162951+codeNinja-1@users.noreply.github.com> Date: Sat, 21 Feb 2026 15:14:01 -0800 Subject: [PATCH 18/18] Empty commit