Skip to content

Commit

Permalink
Fix docs errors
Browse files Browse the repository at this point in the history
  • Loading branch information
KangarooKoala committed Apr 28, 2024
1 parent 5a2b1d1 commit 8e54736
Show file tree
Hide file tree
Showing 5 changed files with 34 additions and 1 deletion.
3 changes: 3 additions & 0 deletions docs/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<N2, N2, N2> 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;

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit 8e54736

Please sign in to comment.