From 8e54736b396f89d079148f01ea527266c4f60708 Mon Sep 17 00:00:00 2001 From: Joseph Eng Date: Sat, 27 Apr 2024 18:12:50 -0700 Subject: [PATCH] Fix docs errors --- docs/build.gradle | 3 +++ .../math/controller/DifferentialDriveFeedforward.java | 8 ++++++++ .../first/math/kinematics/SwerveDriveKinematics.java | 6 ++++++ .../edu/wpi/first/math/spline/CubicHermiteSpline.java | 8 ++++++++ .../wpi/first/math/spline/QuinticHermiteSpline.java | 10 +++++++++- 5 files changed, 34 insertions(+), 1 deletion(-) diff --git a/docs/build.gradle b/docs/build.gradle index 932ee3a4b4e..ed093fcfb3f 100644 --- a/docs/build.gradle +++ b/docs/build.gradle @@ -224,6 +224,9 @@ task generateJavaDocs(type: Javadoc) { "-edu.wpi.first.math.geometry.struct," + "-edu.wpi.first.math.kinematics.proto," + "-edu.wpi.first.math.kinematics.struct," + + "-edu.wpi.first.math.spline.proto," + + "-edu.wpi.first.math.spline.struct," + + "-edu.wpi.first.math.system.proto," + "-edu.wpi.first.math.system.plant.proto," + "-edu.wpi.first.math.system.plant.struct," + "-edu.wpi.first.math.trajectory.proto", true) diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveFeedforward.java index 62d5f0a1bdd..15be9f62f9b 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveFeedforward.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveFeedforward.java @@ -16,9 +16,17 @@ /** A helper class which computes the feedforward outputs for a differential drive drivetrain. */ public class DifferentialDriveFeedforward implements ProtobufSerializable, StructSerializable { private final LinearSystem m_plant; + + /** The linear velocity gain in volts per (meters per second). */ public final double m_kVLinear; + + /** The linear acceleration gain in volts per (meters per second squared). */ public final double m_kALinear; + + /** The angular velocity gain in volts per (radians per second). */ public final double m_kVAngular; + + /** The angular acceleration gain in volts per (radians per second squared). */ public final double m_kAAngular; /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java index 26bc3cf261d..f0a1eaa56fe 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java @@ -412,6 +412,12 @@ public static void desaturateWheelSpeeds( attainableMaxRotationalVelocity.in(RadiansPerSecond)); } + /** + * Gets the locations of the modules relative to the center of rotation. + * + * @return The locations of the modules relative to the center of rotation. This array should not + * be modified. + */ @SuppressWarnings("PMD.MethodReturnsInternalArray") public Translation2d[] getModules() { return m_modules; diff --git a/wpimath/src/main/java/edu/wpi/first/math/spline/CubicHermiteSpline.java b/wpimath/src/main/java/edu/wpi/first/math/spline/CubicHermiteSpline.java index d50f126f0d2..6ccb553c077 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/spline/CubicHermiteSpline.java +++ b/wpimath/src/main/java/edu/wpi/first/math/spline/CubicHermiteSpline.java @@ -14,9 +14,17 @@ public class CubicHermiteSpline extends Spline implements ProtobufSerializable, StructSerializable { private static SimpleMatrix hermiteBasis; private final SimpleMatrix m_coefficients; + + /** The control vector for the initial point in the x dimension. DO NOT MODIFY THIS ARRAY! */ public final double[] xInitialControlVector; + + /** The control vector for the final point in the x dimension. DO NOT MODIFY THIS ARRAY! */ public final double[] xFinalControlVector; + + /** The control vector for the initial point in the y dimension. DO NOT MODIFY THIS ARRAY! */ public final double[] yInitialControlVector; + + /** The control vector for the final point in the y dimension. DO NOT MODIFY THIS ARRAY! */ public final double[] yFinalControlVector; private final ControlVector m_initialControlVector; diff --git a/wpimath/src/main/java/edu/wpi/first/math/spline/QuinticHermiteSpline.java b/wpimath/src/main/java/edu/wpi/first/math/spline/QuinticHermiteSpline.java index 5b5641c8c78..e8cb7f874f0 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/spline/QuinticHermiteSpline.java +++ b/wpimath/src/main/java/edu/wpi/first/math/spline/QuinticHermiteSpline.java @@ -15,9 +15,17 @@ public class QuinticHermiteSpline extends Spline implements ProtobufSerializable, StructSerializable { private static SimpleMatrix hermiteBasis; private final SimpleMatrix m_coefficients; + + /** The control vector for the initial point in the x dimension. DO NOT MODIFY THIS ARRAY! */ public final double[] xInitialControlVector; - public final double[] yInitialControlVector; + + /** The control vector for the final point in the x dimension. DO NOT MODIFY THIS ARRAY! */ public final double[] xFinalControlVector; + + /** The control vector for the initial point in the y dimension. DO NOT MODIFY THIS ARRAY! */ + public final double[] yInitialControlVector; + + /** The control vector for the final point in the y dimension. DO NOT MODIFY THIS ARRAY! */ public final double[] yFinalControlVector; private final ControlVector m_initialControlVector;