Clean up Java warning suppressions (#4433)

Checkstyle naming conventions were changed to allow most of what's in
wpimath. Naming rules were disabled completely in wpimath since almost
all suppressions are for math notation.
This commit is contained in:
Tyler Veness
2022-09-24 00:13:55 -07:00
committed by GitHub
parent 17f504f548
commit a791470de7
233 changed files with 282 additions and 881 deletions

View File

@@ -18,7 +18,6 @@ public final class Drake {
* @param R Input cost matrix.
* @return Solution of DARE.
*/
@SuppressWarnings({"LocalVariableName", "ParameterName"})
public static SimpleMatrix discreteAlgebraicRiccatiEquation(
SimpleMatrix A, SimpleMatrix B, SimpleMatrix Q, SimpleMatrix R) {
var S = new SimpleMatrix(A.numRows(), A.numCols());
@@ -44,7 +43,6 @@ public final class Drake {
* @param R Input cost matrix.
* @return Solution of DARE.
*/
@SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
public static <States extends Num, Inputs extends Num>
Matrix<States, States> discreteAlgebraicRiccatiEquation(
Matrix<States, States> A,
@@ -66,7 +64,6 @@ public final class Drake {
* @param N State-input cross-term cost matrix.
* @return Solution of DARE.
*/
@SuppressWarnings({"LocalVariableName", "ParameterName"})
public static SimpleMatrix discreteAlgebraicRiccatiEquation(
SimpleMatrix A, SimpleMatrix B, SimpleMatrix Q, SimpleMatrix R, SimpleMatrix N) {
// See
@@ -99,7 +96,6 @@ public final class Drake {
* @param N State-input cross-term cost matrix.
* @return Solution of DARE.
*/
@SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
public static <States extends Num, Inputs extends Num>
Matrix<States, States> discreteAlgebraicRiccatiEquation(
Matrix<States, States> A,

View File

@@ -24,7 +24,6 @@ public class MatBuilder<R extends Num, C extends Num> {
* @param data The data to fill the matrix with.
* @return The constructed matrix.
*/
@SuppressWarnings("LineLength")
public final Matrix<R, C> fill(double... data) {
if (Objects.requireNonNull(data).length != this.m_rows.getNum() * this.m_cols.getNum()) {
throw new IllegalArgumentException(

View File

@@ -142,7 +142,6 @@ public final class MathUtil {
* @param t How far between the two values to interpolate. This is clamped to [0, 1].
* @return The interpolated value.
*/
@SuppressWarnings("ParameterName")
public static double interpolate(double startValue, double endValue, double t) {
return startValue + (endValue - startValue) * MathUtil.clamp(t, 0, 1);
}

View File

@@ -331,7 +331,6 @@ public class Matrix<R extends Num, C extends Num> {
* @param b The right-hand side of the equation to solve.
* @return The solution to the linear system.
*/
@SuppressWarnings("ParameterName")
public final <C2 extends Num> Matrix<C, C2> solve(Matrix<R, C2> b) {
return new Matrix<>(this.m_storage.solve(Objects.requireNonNull(b).m_storage));
}
@@ -464,7 +463,6 @@ public class Matrix<R extends Num, C extends Num> {
* @param b Scalar.
* @return The element by element power of "this" and b.
*/
@SuppressWarnings("ParameterName")
public final Matrix<R, C> elementPower(double b) {
return new Matrix<>(this.m_storage.elementPower(b));
}
@@ -477,7 +475,6 @@ public class Matrix<R extends Num, C extends Num> {
* @param b Scalar.
* @return The element by element power of "this" and b.
*/
@SuppressWarnings("ParameterName")
public final Matrix<R, C> elementPower(int b) {
return new Matrix<>(this.m_storage.elementPower((double) b));
}

View File

@@ -21,7 +21,6 @@ public class Pair<A, B> {
return m_second;
}
@SuppressWarnings("ParameterName")
public static <A, B> Pair<A, B> of(A a, B b) {
return new Pair<>(a, b);
}

View File

@@ -21,36 +21,34 @@ public final class SimpleMatrixUtils {
* @param matrix The matrix to compute the exponential of.
* @return The resultant matrix.
*/
@SuppressWarnings({"LocalVariableName", "LineLength"})
public static SimpleMatrix expm(SimpleMatrix matrix) {
BiFunction<SimpleMatrix, SimpleMatrix, SimpleMatrix> solveProvider = SimpleBase::solve;
SimpleMatrix A = matrix;
double A_L1 = NormOps_DDRM.inducedP1(matrix.getDDRM());
int n_squarings = 0;
int nSquarings = 0;
if (A_L1 < 1.495585217958292e-002) {
Pair<SimpleMatrix, SimpleMatrix> pair = _pade3(A);
return dispatchPade(pair.getFirst(), pair.getSecond(), n_squarings, solveProvider);
Pair<SimpleMatrix, SimpleMatrix> pair = pade3(A);
return dispatchPade(pair.getFirst(), pair.getSecond(), nSquarings, solveProvider);
} else if (A_L1 < 2.539398330063230e-001) {
Pair<SimpleMatrix, SimpleMatrix> pair = _pade5(A);
return dispatchPade(pair.getFirst(), pair.getSecond(), n_squarings, solveProvider);
Pair<SimpleMatrix, SimpleMatrix> pair = pade5(A);
return dispatchPade(pair.getFirst(), pair.getSecond(), nSquarings, solveProvider);
} else if (A_L1 < 9.504178996162932e-001) {
Pair<SimpleMatrix, SimpleMatrix> pair = _pade7(A);
return dispatchPade(pair.getFirst(), pair.getSecond(), n_squarings, solveProvider);
Pair<SimpleMatrix, SimpleMatrix> pair = pade7(A);
return dispatchPade(pair.getFirst(), pair.getSecond(), nSquarings, solveProvider);
} else if (A_L1 < 2.097847961257068e+000) {
Pair<SimpleMatrix, SimpleMatrix> pair = _pade9(A);
return dispatchPade(pair.getFirst(), pair.getSecond(), n_squarings, solveProvider);
Pair<SimpleMatrix, SimpleMatrix> pair = pade9(A);
return dispatchPade(pair.getFirst(), pair.getSecond(), nSquarings, solveProvider);
} else {
double maxNorm = 5.371920351148152;
double log = Math.log(A_L1 / maxNorm) / Math.log(2); // logb(2, arg)
n_squarings = (int) Math.max(0, Math.ceil(log));
A = A.divide(Math.pow(2.0, n_squarings));
Pair<SimpleMatrix, SimpleMatrix> pair = _pade13(A);
return dispatchPade(pair.getFirst(), pair.getSecond(), n_squarings, solveProvider);
nSquarings = (int) Math.max(0, Math.ceil(log));
A = A.divide(Math.pow(2.0, nSquarings));
Pair<SimpleMatrix, SimpleMatrix> pair = pade13(A);
return dispatchPade(pair.getFirst(), pair.getSecond(), nSquarings, solveProvider);
}
}
@SuppressWarnings({"LocalVariableName", "ParameterName", "LineLength"})
private static SimpleMatrix dispatchPade(
SimpleMatrix U,
SimpleMatrix V,
@@ -68,8 +66,7 @@ public final class SimpleMatrixUtils {
return R;
}
@SuppressWarnings({"MethodName", "LocalVariableName", "ParameterName"})
private static Pair<SimpleMatrix, SimpleMatrix> _pade3(SimpleMatrix A) {
private static Pair<SimpleMatrix, SimpleMatrix> pade3(SimpleMatrix A) {
double[] b = new double[] {120, 60, 12, 1};
SimpleMatrix ident = eye(A.numRows(), A.numCols());
@@ -79,8 +76,7 @@ public final class SimpleMatrixUtils {
return new Pair<>(U, V);
}
@SuppressWarnings({"MethodName", "LocalVariableName", "ParameterName"})
private static Pair<SimpleMatrix, SimpleMatrix> _pade5(SimpleMatrix A) {
private static Pair<SimpleMatrix, SimpleMatrix> pade5(SimpleMatrix A) {
double[] b = new double[] {30240, 15120, 3360, 420, 30, 1};
SimpleMatrix ident = eye(A.numRows(), A.numCols());
SimpleMatrix A2 = A.mult(A);
@@ -92,8 +88,7 @@ public final class SimpleMatrixUtils {
return new Pair<>(U, V);
}
@SuppressWarnings({"MethodName", "LocalVariableName", "LineLength", "ParameterName"})
private static Pair<SimpleMatrix, SimpleMatrix> _pade7(SimpleMatrix A) {
private static Pair<SimpleMatrix, SimpleMatrix> pade7(SimpleMatrix A) {
double[] b = new double[] {17297280, 8648640, 1995840, 277200, 25200, 1512, 56, 1};
SimpleMatrix ident = eye(A.numRows(), A.numCols());
SimpleMatrix A2 = A.mult(A);
@@ -108,8 +103,7 @@ public final class SimpleMatrixUtils {
return new Pair<>(U, V);
}
@SuppressWarnings({"MethodName", "LocalVariableName", "ParameterName", "LineLength"})
private static Pair<SimpleMatrix, SimpleMatrix> _pade9(SimpleMatrix A) {
private static Pair<SimpleMatrix, SimpleMatrix> pade9(SimpleMatrix A) {
double[] b =
new double[] {
17643225600.0, 8821612800.0, 2075673600, 302702400, 30270240, 2162160, 110880, 3960, 90, 1
@@ -137,8 +131,7 @@ public final class SimpleMatrixUtils {
return new Pair<>(U, V);
}
@SuppressWarnings({"MethodName", "LocalVariableName", "LineLength", "ParameterName"})
private static Pair<SimpleMatrix, SimpleMatrix> _pade13(SimpleMatrix A) {
private static Pair<SimpleMatrix, SimpleMatrix> pade13(SimpleMatrix A) {
double[] b =
new double[] {
64764752532480000.0,
@@ -245,7 +238,6 @@ public final class SimpleMatrixUtils {
* @param A the matrix to exponentiate.
* @return the exponential of A.
*/
@SuppressWarnings("ParameterName")
public static SimpleMatrix exp(SimpleMatrix A) {
SimpleMatrix toReturn = new SimpleMatrix(A.numRows(), A.numRows());
WPIMathJNI.exp(A.getDDRM().getData(), A.numRows(), toReturn.getDDRM().getData());

View File

@@ -11,7 +11,6 @@ import edu.wpi.first.math.numbers.N4;
import java.util.Random;
import org.ejml.simple.SimpleMatrix;
@SuppressWarnings("ParameterName")
public final class StateSpaceUtil {
private static Random rand = new Random();
@@ -31,7 +30,6 @@ public final class StateSpaceUtil {
* output measurement.
* @return Process noise or measurement noise covariance matrix.
*/
@SuppressWarnings("MethodTypeParameterName")
public static <States extends Num> Matrix<States, States> makeCovarianceMatrix(
Nat<States> states, Matrix<States, N1> stdDevs) {
var result = new Matrix<>(states, states);
@@ -71,7 +69,6 @@ public final class StateSpaceUtil {
* excursions of the control inputs from no actuation.
* @return State excursion or control effort cost matrix.
*/
@SuppressWarnings("MethodTypeParameterName")
public static <Elements extends Num> Matrix<Elements, Elements> makeCostMatrix(
Matrix<Elements, N1> tolerances) {
Matrix<Elements, Elements> result =
@@ -102,7 +99,6 @@ public final class StateSpaceUtil {
* @param B Input matrix.
* @return If the system is stabilizable.
*/
@SuppressWarnings("MethodTypeParameterName")
public static <States extends Num, Inputs extends Num> boolean isStabilizable(
Matrix<States, States> A, Matrix<States, Inputs> B) {
return WPIMathJNI.isStabilizable(A.getNumRows(), B.getNumCols(), A.getData(), B.getData());
@@ -121,7 +117,6 @@ public final class StateSpaceUtil {
* @param C Output matrix.
* @return If the system is detectable.
*/
@SuppressWarnings("MethodTypeParameterName")
public static <States extends Num, Outputs extends Num> boolean isDetectable(
Matrix<States, States> A, Matrix<Outputs, States> C) {
return WPIMathJNI.isStabilizable(
@@ -147,7 +142,6 @@ public final class StateSpaceUtil {
* @param <I> The number of inputs.
* @return The clamped input.
*/
@SuppressWarnings({"ParameterName", "LocalVariableName"})
public static <I extends Num> Matrix<I, N1> clampInputMaxMagnitude(
Matrix<I, N1> u, Matrix<I, N1> umin, Matrix<I, N1> umax) {
var result = new Matrix<I, N1>(new SimpleMatrix(u.getNumRows(), 1));

View File

@@ -8,7 +8,6 @@ package edu.wpi.first.math.controller;
* A helper class that computes feedforward outputs for a simple arm (modeled as a motor acting
* against the force of gravity on a beam suspended at an angle).
*/
@SuppressWarnings("MemberName")
public class ArmFeedforward {
public final double ks;
public final double kcos;

View File

@@ -29,16 +29,13 @@ import java.util.function.Function;
* <p>For more on the underlying math, read
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
*/
@SuppressWarnings({"ParameterName", "LocalVariableName", "MemberName", "ClassTypeParameterName"})
public class ControlAffinePlantInversionFeedforward<States extends Num, Inputs extends Num> {
/** The current reference state. */
@SuppressWarnings("MemberName")
private Matrix<States, N1> m_r;
/** The computed feedforward. */
private Matrix<Inputs, N1> m_uff;
@SuppressWarnings("MemberName")
private final Matrix<States, Inputs> m_B;
private final Nat<Inputs> m_inputs;
@@ -181,7 +178,6 @@ public class ControlAffinePlantInversionFeedforward<States extends Num, Inputs e
* @param nextR The reference state of the future timestep (k + dt).
* @return The calculated feedforward.
*/
@SuppressWarnings({"ParameterName", "LocalVariableName"})
public Matrix<Inputs, N1> calculate(Matrix<States, N1> r, Matrix<States, N1> nextR) {
var rDot = (nextR.minus(r)).div(m_dt);

View File

@@ -50,7 +50,6 @@ public class DifferentialDriveAccelerationLimiter {
* @param rightVoltage The unconstrained right motor voltage.
* @return The constrained wheel voltages.
*/
@SuppressWarnings("LocalVariableName")
public DifferentialDriveWheelVoltages calculate(
double leftVelocity, double rightVelocity, double leftVoltage, double rightVoltage) {
var u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(leftVoltage, rightVoltage);

View File

@@ -5,7 +5,6 @@
package edu.wpi.first.math.controller;
/** Motor voltages for a differential drive. */
@SuppressWarnings("MemberName")
public class DifferentialDriveWheelVoltages {
public double left;
public double right;

View File

@@ -8,7 +8,6 @@ package edu.wpi.first.math.controller;
* A helper class that computes feedforward outputs for a simple elevator (modeled as a motor acting
* against the force of gravity).
*/
@SuppressWarnings("MemberName")
public class ElevatorFeedforward {
public final double ks;
public final double kg;

View File

@@ -20,7 +20,6 @@ import edu.wpi.first.math.trajectory.Trajectory;
* are decoupled from translations, users can specify a custom heading that the drivetrain should
* point toward. This heading reference is profiled for smoothness.
*/
@SuppressWarnings("MemberName")
public class HolonomicDriveController {
private Pose2d m_poseError = new Pose2d();
private Rotation2d m_rotationError = new Rotation2d();
@@ -40,7 +39,6 @@ public class HolonomicDriveController {
* @param yController A PID Controller to respond to error in the field-relative y direction.
* @param thetaController A profiled PID controller to respond to error in angle.
*/
@SuppressWarnings("ParameterName")
public HolonomicDriveController(
PIDController xController, PIDController yController, ProfiledPIDController thetaController) {
m_xController = xController;
@@ -81,7 +79,6 @@ public class HolonomicDriveController {
* @param angleRef The angular reference.
* @return The next output of the holonomic drive controller.
*/
@SuppressWarnings("LocalVariableName")
public ChassisSpeeds calculate(
Pose2d currentPose, Pose2d poseRef, double linearVelocityRefMeters, Rotation2d angleRef) {
// If this is the first run, then we need to reset the theta controller to the current pose's

View File

@@ -20,18 +20,14 @@ import org.ejml.simple.SimpleMatrix;
* <p>For more on the underlying math, read appendix B.3 in
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
*/
@SuppressWarnings("ClassTypeParameterName")
public class ImplicitModelFollower<States extends Num, Inputs extends Num, Outputs extends Num> {
// Computed controller output
@SuppressWarnings("MemberName")
private Matrix<Inputs, N1> m_u;
// State space conversion gain
@SuppressWarnings("MemberName")
private Matrix<Inputs, States> m_A;
// Input space conversion gain
@SuppressWarnings("MemberName")
private Matrix<Inputs, Inputs> m_B;
/**
@@ -53,7 +49,6 @@ public class ImplicitModelFollower<States extends Num, Inputs extends Num, Outpu
* @param Aref Continuous system matrix whose dynamics should be followed.
* @param Bref Continuous input matrix whose dynamics should be followed.
*/
@SuppressWarnings("ParameterName")
public ImplicitModelFollower(
Matrix<States, States> A,
Matrix<States, Inputs> B,

View File

@@ -45,10 +45,8 @@ public class LTVDifferentialDriveController {
kLeftVelocity(3),
kRightVelocity(4);
@SuppressWarnings("MemberName")
public final int value;
@SuppressWarnings("ParameterName")
State(int i) {
this.value = i;
}
@@ -64,7 +62,6 @@ public class LTVDifferentialDriveController {
* @param relems The maximum desired control effort for each input.
* @param dt Discretization timestep in seconds.
*/
@SuppressWarnings("LocalVariableName")
public LTVDifferentialDriveController(
LinearSystem<N2, N2, N2> plant,
double trackwidth,
@@ -188,7 +185,6 @@ public class LTVDifferentialDriveController {
* @param rightVelocityRef The desired right velocity in meters per second.
* @return Left and right output voltages of the LTV controller.
*/
@SuppressWarnings("LocalVariableName")
public DifferentialDriveWheelVoltages calculate(
Pose2d currentPose,
double leftVelocity,

View File

@@ -25,7 +25,6 @@ import edu.wpi.first.math.trajectory.Trajectory;
* <p>See section 8.9 in Controls Engineering in FRC for a derivation of the control law we used
* shown in theorem 8.9.1.
*/
@SuppressWarnings("MemberName")
public class LTVUnicycleController {
// LUT from drivetrain linear velocity to LQR gain
private final InterpolatingMatrixTreeMap<Double, N2, N3> m_table =
@@ -41,10 +40,8 @@ public class LTVUnicycleController {
kY(1),
kHeading(2);
@SuppressWarnings("MemberName")
public final int value;
@SuppressWarnings("ParameterName")
State(int i) {
this.value = i;
}
@@ -94,7 +91,6 @@ public class LTVUnicycleController {
* @param maxVelocity The maximum velocity in meters per second for the controller gain lookup
* table. The default is 9 m/s.
*/
@SuppressWarnings("LocalVariableName")
public LTVUnicycleController(
Vector<N3> qelems, Vector<N2> relems, double dt, double maxVelocity) {
// The change in global pose for a unicycle is defined by the following
@@ -191,7 +187,6 @@ public class LTVUnicycleController {
m_poseError = poseRef.relativeTo(currentPose);
@SuppressWarnings("LocalVariableName")
var K = m_table.get(linearVelocityRef);
var e =
new MatBuilder<>(Nat.N3(), Nat.N1())

View File

@@ -20,20 +20,16 @@ import org.ejml.simple.SimpleMatrix;
* <p>For more on the underlying math, read
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
*/
@SuppressWarnings({"ParameterName", "LocalVariableName", "MemberName", "ClassTypeParameterName"})
public class LinearPlantInversionFeedforward<
States extends Num, Inputs extends Num, Outputs extends Num> {
/** The current reference state. */
@SuppressWarnings("MemberName")
private Matrix<States, N1> m_r;
/** The computed feedforward. */
private Matrix<Inputs, N1> m_uff;
@SuppressWarnings("MemberName")
private final Matrix<States, Inputs> m_B;
@SuppressWarnings("MemberName")
private final Matrix<States, States> m_A;
/**
@@ -54,7 +50,6 @@ public class LinearPlantInversionFeedforward<
* @param B Continuous input matrix of the plant being controlled.
* @param dtSeconds Discretization timestep.
*/
@SuppressWarnings({"ParameterName", "LocalVariableName"})
public LinearPlantInversionFeedforward(
Matrix<States, States> A, Matrix<States, Inputs> B, double dtSeconds) {
var discABPair = Discretization.discretizeAB(A, B, dtSeconds);
@@ -143,7 +138,6 @@ public class LinearPlantInversionFeedforward<
* @param nextR The reference state of the future timestep (k + dt).
* @return The calculated feedforward.
*/
@SuppressWarnings({"ParameterName", "LocalVariableName"})
public Matrix<Inputs, N1> calculate(Matrix<States, N1> r, Matrix<States, N1> nextR) {
m_uff = new Matrix<>(m_B.solve(nextR.minus(m_A.times(r))));

View File

@@ -22,18 +22,14 @@ import org.ejml.simple.SimpleMatrix;
* <p>For more on the underlying math, read
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
*/
@SuppressWarnings("ClassTypeParameterName")
public class LinearQuadraticRegulator<States extends Num, Inputs extends Num, Outputs extends Num> {
/** The current reference state. */
@SuppressWarnings("MemberName")
private Matrix<States, N1> m_r;
/** The computed and capped controller output. */
@SuppressWarnings("MemberName")
private Matrix<Inputs, N1> m_u;
// Controller gain.
@SuppressWarnings("MemberName")
private Matrix<Inputs, States> m_K;
/**
@@ -68,7 +64,6 @@ public class LinearQuadraticRegulator<States extends Num, Inputs extends Num, Ou
* @param dtSeconds Discretization timestep.
* @throws IllegalArgumentException If the system is uncontrollable.
*/
@SuppressWarnings({"ParameterName", "LocalVariableName"})
public LinearQuadraticRegulator(
Matrix<States, States> A,
Matrix<States, Inputs> B,
@@ -93,7 +88,6 @@ public class LinearQuadraticRegulator<States extends Num, Inputs extends Num, Ou
* @param dtSeconds Discretization timestep.
* @throws IllegalArgumentException If the system is uncontrollable.
*/
@SuppressWarnings({"LocalVariableName", "ParameterName"})
public LinearQuadraticRegulator(
Matrix<States, States> A,
Matrix<States, Inputs> B,
@@ -145,7 +139,6 @@ public class LinearQuadraticRegulator<States extends Num, Inputs extends Num, Ou
* @param dtSeconds Discretization timestep.
* @throws IllegalArgumentException If the system is uncontrollable.
*/
@SuppressWarnings({"ParameterName", "LocalVariableName"})
public LinearQuadraticRegulator(
Matrix<States, States> A,
Matrix<States, Inputs> B,
@@ -233,7 +226,6 @@ public class LinearQuadraticRegulator<States extends Num, Inputs extends Num, Ou
* @param x The current state x.
* @return The next controller output.
*/
@SuppressWarnings("ParameterName")
public Matrix<Inputs, N1> calculate(Matrix<States, N1> x) {
m_u = m_K.times(m_r.minus(x));
return m_u;
@@ -246,7 +238,6 @@ public class LinearQuadraticRegulator<States extends Num, Inputs extends Num, Ou
* @param nextR the next reference vector r.
* @return The next controller output.
*/
@SuppressWarnings("ParameterName")
public Matrix<Inputs, N1> calculate(Matrix<States, N1> x, Matrix<States, N1> nextR) {
m_r = nextR;
return calculate(x);

View File

@@ -33,7 +33,6 @@ public class ProfiledPIDController implements Sendable {
* @param Kd The derivative coefficient.
* @param constraints Velocity and acceleration constraints for goal.
*/
@SuppressWarnings("ParameterName")
public ProfiledPIDController(
double Kp, double Ki, double Kd, TrapezoidProfile.Constraints constraints) {
this(Kp, Ki, Kd, constraints, 0.02);
@@ -48,7 +47,6 @@ public class ProfiledPIDController implements Sendable {
* @param constraints Velocity and acceleration constraints for goal.
* @param period The period between controller updates in seconds. The default is 0.02 seconds.
*/
@SuppressWarnings("ParameterName")
public ProfiledPIDController(
double Kp, double Ki, double Kd, TrapezoidProfile.Constraints constraints, double period) {
m_controller = new PIDController(Kp, Ki, Kd, period);
@@ -66,7 +64,6 @@ public class ProfiledPIDController implements Sendable {
* @param Ki Integral coefficient
* @param Kd Differential coefficient
*/
@SuppressWarnings("ParameterName")
public void setPID(double Kp, double Ki, double Kd) {
m_controller.setPID(Kp, Ki, Kd);
}
@@ -76,7 +73,6 @@ public class ProfiledPIDController implements Sendable {
*
* @param Kp proportional coefficient
*/
@SuppressWarnings("ParameterName")
public void setP(double Kp) {
m_controller.setP(Kp);
}
@@ -86,7 +82,6 @@ public class ProfiledPIDController implements Sendable {
*
* @param Ki integral coefficient
*/
@SuppressWarnings("ParameterName")
public void setI(double Ki) {
m_controller.setI(Ki);
}
@@ -96,7 +91,6 @@ public class ProfiledPIDController implements Sendable {
*
* @param Kd differential coefficient
*/
@SuppressWarnings("ParameterName")
public void setD(double Kd) {
m_controller.setD(Kd);
}

View File

@@ -33,10 +33,8 @@ import edu.wpi.first.math.trajectory.Trajectory;
* derivation and analysis.
*/
public class RamseteController {
@SuppressWarnings("MemberName")
private final double m_b;
@SuppressWarnings("MemberName")
private final double m_zeta;
private Pose2d m_poseError = new Pose2d();
@@ -51,7 +49,6 @@ public class RamseteController {
* @param zeta Tuning parameter (0 rad⁻¹ &lt; zeta &lt; 1 rad⁻¹) for which larger values provide
* more damping in response.
*/
@SuppressWarnings("ParameterName")
public RamseteController(double b, double zeta) {
m_b = b;
m_zeta = zeta;
@@ -101,7 +98,6 @@ public class RamseteController {
* @param angularVelocityRefRadiansPerSecond The desired angular velocity in radians per second.
* @return The next controller output.
*/
@SuppressWarnings("LocalVariableName")
public ChassisSpeeds calculate(
Pose2d currentPose,
Pose2d poseRef,
@@ -141,7 +137,6 @@ public class RamseteController {
* @param desiredState The desired pose, linear velocity, and angular velocity from a trajectory.
* @return The next controller output.
*/
@SuppressWarnings("LocalVariableName")
public ChassisSpeeds calculate(Pose2d currentPose, Trajectory.State desiredState) {
return calculate(
currentPose,
@@ -164,7 +159,6 @@ public class RamseteController {
*
* @param x Value of which to take sinc(x).
*/
@SuppressWarnings("ParameterName")
private static double sinc(double x) {
if (Math.abs(x) < 1e-9) {
return 1.0 - 1.0 / 6.0 * x * x;

View File

@@ -9,7 +9,6 @@ import edu.wpi.first.math.Nat;
import edu.wpi.first.math.system.plant.LinearSystemId;
/** A helper class that computes feedforward outputs for a simple permanent-magnet DC motor. */
@SuppressWarnings("MemberName")
public class SimpleMotorFeedforward {
public final double ks;
public final double kv;

View File

@@ -87,7 +87,6 @@ public final class AngleStatistics {
* @param angleStateIdx The row containing the angles.
* @return Mean of sigma points.
*/
@SuppressWarnings("checkstyle:ParameterName")
public static <S extends Num> Matrix<S, N1> angleMean(
Matrix<S, ?> sigmas, Matrix<?, N1> Wm, int angleStateIdx) {
double[] angleSigmas = sigmas.extractRowVector(angleStateIdx).getData();
@@ -115,7 +114,6 @@ public final class AngleStatistics {
* @param angleStateIdx The row containing the angles.
* @return Function returning mean of sigma points.
*/
@SuppressWarnings("LambdaParameterName")
public static <S extends Num> BiFunction<Matrix<S, ?>, Matrix<?, N1>, Matrix<S, N1>> angleMean(
int angleStateIdx) {
return (sigmas, Wm) -> angleMean(sigmas, Wm, angleStateIdx);

View File

@@ -112,7 +112,6 @@ public class DifferentialDrivePoseEstimator {
* theta]ᵀ, with units in meters and radians.
* @param nominalDtSeconds The time in seconds between each robot loop.
*/
@SuppressWarnings("ParameterName")
public DifferentialDrivePoseEstimator(
Rotation2d gyroAngle,
Pose2d initialPoseMeters,
@@ -172,7 +171,6 @@ public class DifferentialDrivePoseEstimator {
m_visionContR = StateSpaceUtil.makeCovarianceMatrix(Nat.N3(), visionMeasurementStdDevs);
}
@SuppressWarnings({"ParameterName", "MethodName"})
private Matrix<N5, N1> f(Matrix<N5, N1> x, Matrix<N3, N1> u) {
// Apply a rotation matrix. Note that we do *not* add x--Runge-Kutta does that for us.
var theta = x.get(2, 0);
@@ -343,7 +341,6 @@ public class DifferentialDrivePoseEstimator {
* last time you called {@link DifferentialDrivePoseEstimator#resetPosition}.
* @return The estimated pose of the robot in meters.
*/
@SuppressWarnings({"LocalVariableName", "ParameterName"})
public Pose2d updateWithTime(
double currentTimeSeconds,
Rotation2d gyroAngle,

View File

@@ -34,16 +34,13 @@ import java.util.function.BiFunction;
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9 "Stochastic control
* theory".
*/
@SuppressWarnings("ClassTypeParameterName")
public class ExtendedKalmanFilter<States extends Num, Inputs extends Num, Outputs extends Num>
implements KalmanTypeFilter<States, Inputs, Outputs> {
private final Nat<States> m_states;
private final Nat<Outputs> m_outputs;
@SuppressWarnings("MemberName")
private final BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> m_f;
@SuppressWarnings("MemberName")
private final BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<Outputs, N1>> m_h;
private BiFunction<Matrix<Outputs, N1>, Matrix<Outputs, N1>, Matrix<Outputs, N1>> m_residualFuncY;
@@ -53,10 +50,8 @@ public class ExtendedKalmanFilter<States extends Num, Inputs extends Num, Output
private final Matrix<States, States> m_initP;
private final Matrix<Outputs, Outputs> m_contR;
@SuppressWarnings("MemberName")
private Matrix<States, N1> m_xHat;
@SuppressWarnings("MemberName")
private Matrix<States, States> m_P;
private double m_dtSeconds;
@@ -73,7 +68,6 @@ public class ExtendedKalmanFilter<States extends Num, Inputs extends Num, Output
* @param measurementStdDevs Standard deviations of measurements.
* @param dtSeconds Nominal discretization timestep.
*/
@SuppressWarnings("ParameterName")
public ExtendedKalmanFilter(
Nat<States> states,
Nat<Inputs> inputs,
@@ -111,7 +105,6 @@ public class ExtendedKalmanFilter<States extends Num, Inputs extends Num, Output
* @param addFuncX A function that adds two state vectors.
* @param dtSeconds Nominal discretization timestep.
*/
@SuppressWarnings("ParameterName")
public ExtendedKalmanFilter(
Nat<States> states,
Nat<Inputs> inputs,
@@ -219,7 +212,6 @@ public class ExtendedKalmanFilter<States extends Num, Inputs extends Num, Output
*
* @param xHat The state estimate x-hat.
*/
@SuppressWarnings("ParameterName")
@Override
public void setXhat(Matrix<States, N1> xHat) {
m_xHat = xHat;
@@ -248,7 +240,6 @@ public class ExtendedKalmanFilter<States extends Num, Inputs extends Num, Output
* @param u New control input from controller.
* @param dtSeconds Timestep for prediction.
*/
@SuppressWarnings("ParameterName")
@Override
public void predict(Matrix<Inputs, N1> u, double dtSeconds) {
predict(u, m_f, dtSeconds);
@@ -261,7 +252,6 @@ public class ExtendedKalmanFilter<States extends Num, Inputs extends Num, Output
* @param f The function used to linearlize the model.
* @param dtSeconds Timestep for prediction.
*/
@SuppressWarnings("ParameterName")
public void predict(
Matrix<Inputs, N1> u,
BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> f,
@@ -288,7 +278,6 @@ public class ExtendedKalmanFilter<States extends Num, Inputs extends Num, Output
* @param u Same control input used in the predict step.
* @param y Measurement vector.
*/
@SuppressWarnings("ParameterName")
@Override
public void correct(Matrix<Inputs, N1> u, Matrix<Outputs, N1> y) {
correct(m_outputs, u, y, m_h, m_contR, m_residualFuncY, m_addFuncX);
@@ -306,16 +295,15 @@ public class ExtendedKalmanFilter<States extends Num, Inputs extends Num, Output
* @param u Same control input used in the predict step.
* @param y Measurement vector.
* @param h A vector-valued function of x and u that returns the measurement vector.
* @param R Discrete measurement noise covariance matrix.
* @param contR Continuous measurement noise covariance matrix.
*/
@SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
public <Rows extends Num> void correct(
Nat<Rows> rows,
Matrix<Inputs, N1> u,
Matrix<Rows, N1> y,
BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<Rows, N1>> h,
Matrix<Rows, Rows> R) {
correct(rows, u, y, h, R, Matrix::minus, Matrix::plus);
Matrix<Rows, Rows> contR) {
correct(rows, u, y, h, contR, Matrix::minus, Matrix::plus);
}
/**
@@ -330,22 +318,21 @@ public class ExtendedKalmanFilter<States extends Num, Inputs extends Num, Output
* @param u Same control input used in the predict step.
* @param y Measurement vector.
* @param h A vector-valued function of x and u that returns the measurement vector.
* @param R Discrete measurement noise covariance matrix.
* @param contR Continuous measurement noise covariance matrix.
* @param residualFuncY A function that computes the residual of two measurement vectors (i.e. it
* subtracts them.)
* @param addFuncX A function that adds two state vectors.
*/
@SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
public <Rows extends Num> void correct(
Nat<Rows> rows,
Matrix<Inputs, N1> u,
Matrix<Rows, N1> y,
BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<Rows, N1>> h,
Matrix<Rows, Rows> R,
Matrix<Rows, Rows> contR,
BiFunction<Matrix<Rows, N1>, Matrix<Rows, N1>, Matrix<Rows, N1>> residualFuncY,
BiFunction<Matrix<States, N1>, Matrix<States, N1>, Matrix<States, N1>> addFuncX) {
final var C = NumericalJacobian.numericalJacobianX(rows, m_states, h, m_xHat, u);
final var discR = Discretization.discretizeR(R, m_dtSeconds);
final var discR = Discretization.discretizeR(contR, m_dtSeconds);
final var S = C.times(m_P).times(C.transpose()).plus(discR);

View File

@@ -29,18 +29,15 @@ import edu.wpi.first.math.system.LinearSystem;
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9 "Stochastic control
* theory".
*/
@SuppressWarnings("ClassTypeParameterName")
public class KalmanFilter<States extends Num, Inputs extends Num, Outputs extends Num> {
private final Nat<States> m_states;
private final LinearSystem<States, Inputs, Outputs> m_plant;
/** The steady-state Kalman gain matrix. */
@SuppressWarnings("MemberName")
private final Matrix<States, Outputs> m_K;
/** The state estimate. */
@SuppressWarnings("MemberName")
private Matrix<States, N1> m_xHat;
/**
@@ -54,7 +51,6 @@ public class KalmanFilter<States extends Num, Inputs extends Num, Outputs extend
* @param dtSeconds Nominal discretization timestep.
* @throws IllegalArgumentException If the system is unobservable.
*/
@SuppressWarnings("LocalVariableName")
public KalmanFilter(
Nat<States> states,
Nat<Outputs> outputs,
@@ -185,7 +181,6 @@ public class KalmanFilter<States extends Num, Inputs extends Num, Outputs extend
* @param u New control input from controller.
* @param dtSeconds Timestep for prediction.
*/
@SuppressWarnings("ParameterName")
public void predict(Matrix<Inputs, N1> u, double dtSeconds) {
this.m_xHat = m_plant.calculateX(m_xHat, u, dtSeconds);
}
@@ -196,7 +191,6 @@ public class KalmanFilter<States extends Num, Inputs extends Num, Outputs extend
* @param u Same control input used in the last predict step.
* @param y Measurement vector.
*/
@SuppressWarnings("ParameterName")
public void correct(Matrix<Inputs, N1> u, Matrix<Outputs, N1> y) {
final var C = m_plant.getC();
final var D = m_plant.getD();

View File

@@ -35,7 +35,6 @@ public class KalmanFilterLatencyCompensator<S extends Num, I extends Num, O exte
* @param localY The local output at the timestamp
* @param timestampSeconds The timesnap of the state.
*/
@SuppressWarnings("ParameterName")
public void addObserverState(
KalmanTypeFilter<S, I, O> observer,
Matrix<I, N1> u,
@@ -60,7 +59,6 @@ public class KalmanFilterLatencyCompensator<S extends Num, I extends Num, O exte
* @param globalMeasurementCorrect The function take calls correct() on the observer.
* @param timestampSeconds The timestamp of the measurement.
*/
@SuppressWarnings("ParameterName")
public <R extends Num> void applyPastGlobalMeasurement(
Nat<R> rows,
KalmanTypeFilter<S, I, O> observer,
@@ -165,14 +163,12 @@ public class KalmanFilterLatencyCompensator<S extends Num, I extends Num, O exte
}
/** This class contains all the information about our observer at a given time. */
@SuppressWarnings("MemberName")
public class ObserverSnapshot {
public final Matrix<S, N1> xHat;
public final Matrix<S, S> errorCovariances;
public final Matrix<I, N1> inputs;
public final Matrix<O, N1> localMeasurements;
@SuppressWarnings("ParameterName")
private ObserverSnapshot(
KalmanTypeFilter<S, I, O> observer, Matrix<I, N1> u, Matrix<O, N1> localY) {
this.xHat = observer.getXhat();

View File

@@ -8,7 +8,6 @@ import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.Num;
import edu.wpi.first.math.numbers.N1;
@SuppressWarnings({"ParameterName", "InterfaceTypeParameterName"})
interface KalmanTypeFilter<States extends Num, Inputs extends Num, Outputs extends Num> {
Matrix<States, States> getP();

View File

@@ -110,7 +110,6 @@ public class MecanumDrivePoseEstimator {
* theta]ᵀ, with units in meters and radians.
* @param nominalDtSeconds The time in seconds between each robot loop.
*/
@SuppressWarnings("ParameterName")
public MecanumDrivePoseEstimator(
Rotation2d gyroAngle,
Pose2d initialPoseMeters,
@@ -290,7 +289,6 @@ public class MecanumDrivePoseEstimator {
* @param wheelSpeeds The current speeds of the mecanum drive wheels.
* @return The estimated pose of the robot in meters.
*/
@SuppressWarnings("LocalVariableName")
public Pose2d updateWithTime(
double currentTimeSeconds, Rotation2d gyroAngle, MecanumDriveWheelSpeeds wheelSpeeds) {
double dt = m_prevTimeSeconds >= 0 ? currentTimeSeconds - m_prevTimeSeconds : m_nominalDt;

View File

@@ -75,7 +75,6 @@ public class MerweScaledSigmaPoints<S extends Num> {
* @return Two dimensional array of sigma points. Each column contains all of the sigmas for one
* dimension in the problem space. Ordered by Xi_0, Xi_{1..n}, Xi_{n+1..2n}.
*/
@SuppressWarnings({"ParameterName", "LocalVariableName"})
public Matrix<S, ?> squareRootSigmaPoints(Matrix<S, N1> x, Matrix<S, S> s) {
double lambda = Math.pow(m_alpha, 2) * (m_states.getNum() + m_kappa) - m_states.getNum();
double eta = Math.sqrt(lambda + m_states.getNum());
@@ -101,7 +100,6 @@ public class MerweScaledSigmaPoints<S extends Num> {
*
* @param beta Incorporates prior knowledge of the distribution of the mean.
*/
@SuppressWarnings("LocalVariableName")
private void computeWeights(double beta) {
double lambda = Math.pow(m_alpha, 2) * (m_states.getNum() + m_kappa) - m_states.getNum();
double c = 0.5 / (m_states.getNum() + lambda);

View File

@@ -110,7 +110,6 @@ public class SwerveDrivePoseEstimator {
* theta]ᵀ, with units in meters and radians.
* @param nominalDtSeconds The time in seconds between each robot loop.
*/
@SuppressWarnings("ParameterName")
public SwerveDrivePoseEstimator(
Rotation2d gyroAngle,
Pose2d initialPoseMeters,
@@ -288,7 +287,6 @@ public class SwerveDrivePoseEstimator {
* @param moduleStates The current velocities and rotations of the swerve modules.
* @return The estimated pose of the robot in meters.
*/
@SuppressWarnings("LocalVariableName")
public Pose2d updateWithTime(
double currentTimeSeconds, Rotation2d gyroAngle, SwerveModuleState... moduleStates) {
double dt = m_prevTimeSeconds >= 0 ? currentTimeSeconds - m_prevTimeSeconds : m_nominalDt;

View File

@@ -38,7 +38,6 @@ import org.ejml.simple.SimpleMatrix;
* <p>This class implements a square-root-form unscented Kalman filter (SR-UKF). For more
* information about the SR-UKF, see https://www.researchgate.net/publication/3908304.
*/
@SuppressWarnings({"MemberName", "ClassTypeParameterName"})
public class UnscentedKalmanFilter<States extends Num, Inputs extends Num, Outputs extends Num>
implements KalmanTypeFilter<States, Inputs, Outputs> {
private final Nat<States> m_states;
@@ -73,7 +72,6 @@ public class UnscentedKalmanFilter<States extends Num, Inputs extends Num, Outpu
* @param measurementStdDevs Standard deviations of measurements.
* @param nominalDtSeconds Nominal discretization timestep.
*/
@SuppressWarnings("LambdaParameterName")
public UnscentedKalmanFilter(
Nat<States> states,
Nat<Outputs> outputs,
@@ -119,7 +117,6 @@ public class UnscentedKalmanFilter<States extends Num, Inputs extends Num, Outpu
* @param addFuncX A function that adds two state vectors.
* @param nominalDtSeconds Nominal discretization timestep.
*/
@SuppressWarnings("ParameterName")
public UnscentedKalmanFilter(
Nat<States> states,
Nat<Outputs> outputs,
@@ -155,7 +152,6 @@ public class UnscentedKalmanFilter<States extends Num, Inputs extends Num, Outpu
reset();
}
@SuppressWarnings({"ParameterName", "LocalVariableName"})
static <S extends Num, C extends Num>
Pair<Matrix<C, N1>, Matrix<C, C>> squareRootUnscentedTransform(
Nat<S> s,
@@ -300,7 +296,6 @@ public class UnscentedKalmanFilter<States extends Num, Inputs extends Num, Outpu
*
* @param xHat The state estimate x-hat.
*/
@SuppressWarnings("ParameterName")
@Override
public void setXhat(Matrix<States, N1> xHat) {
m_xHat = xHat;
@@ -331,7 +326,6 @@ public class UnscentedKalmanFilter<States extends Num, Inputs extends Num, Outpu
* @param u New control input from controller.
* @param dtSeconds Timestep for prediction.
*/
@SuppressWarnings({"LocalVariableName", "ParameterName"})
@Override
public void predict(Matrix<Inputs, N1> u, double dtSeconds) {
// Discretize Q before projecting mean and covariance forward
@@ -370,7 +364,6 @@ public class UnscentedKalmanFilter<States extends Num, Inputs extends Num, Outpu
* @param u Same control input used in the predict step.
* @param y Measurement vector.
*/
@SuppressWarnings("ParameterName")
@Override
public void correct(Matrix<Inputs, N1> u, Matrix<Outputs, N1> y) {
correct(
@@ -391,7 +384,6 @@ public class UnscentedKalmanFilter<States extends Num, Inputs extends Num, Outpu
* @param h A vector-valued function of x and u that returns the measurement vector.
* @param R Measurement noise covariance matrix (continuous-time).
*/
@SuppressWarnings({"ParameterName", "LambdaParameterName", "LocalVariableName"})
public <R extends Num> void correct(
Nat<R> rows,
Matrix<Inputs, N1> u,
@@ -428,7 +420,6 @@ public class UnscentedKalmanFilter<States extends Num, Inputs extends Num, Outpu
* subtracts them.)
* @param addFuncX A function that adds two state vectors.
*/
@SuppressWarnings({"ParameterName", "LocalVariableName"})
public <R extends Num> void correct(
Nat<R> rows,
Matrix<Inputs, N1> u,

View File

@@ -154,7 +154,6 @@ public class LinearFilter {
* @throws IllegalArgumentException if derivative &lt; 1, samples &lt;= 0, or derivative &gt;=
* samples.
*/
@SuppressWarnings("LocalVariableName")
public static LinearFilter finiteDifference(int derivative, int[] stencil, double period) {
// See
// https://en.wikipedia.org/wiki/Finite_difference_coefficient#Arbitrary_stencil_points

View File

@@ -36,7 +36,6 @@ public class CoordinateAxis {
*
* @return A coordinate axis corresponding to +X in the NWU coordinate system.
*/
@SuppressWarnings("MethodName")
public static CoordinateAxis N() {
return m_n;
}
@@ -46,7 +45,6 @@ public class CoordinateAxis {
*
* @return A coordinate axis corresponding to -X in the NWU coordinate system.
*/
@SuppressWarnings("MethodName")
public static CoordinateAxis S() {
return m_s;
}
@@ -56,7 +54,6 @@ public class CoordinateAxis {
*
* @return A coordinate axis corresponding to -Y in the NWU coordinate system.
*/
@SuppressWarnings("MethodName")
public static CoordinateAxis E() {
return m_e;
}
@@ -66,7 +63,6 @@ public class CoordinateAxis {
*
* @return A coordinate axis corresponding to +Y in the NWU coordinate system.
*/
@SuppressWarnings("MethodName")
public static CoordinateAxis W() {
return m_w;
}
@@ -76,7 +72,6 @@ public class CoordinateAxis {
*
* @return A coordinate axis corresponding to +Z in the NWU coordinate system.
*/
@SuppressWarnings("MethodName")
public static CoordinateAxis U() {
return m_u;
}
@@ -86,7 +81,6 @@ public class CoordinateAxis {
*
* @return A coordinate axis corresponding to -Z in the NWU coordinate system.
*/
@SuppressWarnings("MethodName")
public static CoordinateAxis D() {
return m_d;
}

View File

@@ -32,7 +32,6 @@ public class CoordinateSystem {
// Construct a change of basis matrix from the source coordinate system to the
// NWU coordinate system. Each column vector in the change of basis matrix is
// one of the old basis vectors mapped to its representation in the new basis.
@SuppressWarnings("LocalVariableName")
var R = new Matrix<>(Nat.N3(), Nat.N3());
R.assignBlock(0, 0, positiveX.m_axis);
R.assignBlock(0, 1, positiveY.m_axis);
@@ -50,7 +49,6 @@ public class CoordinateSystem {
*
* @return An instance of the North-West-Up (NWU) coordinate system.
*/
@SuppressWarnings("MethodName")
public static CoordinateSystem NWU() {
return m_nwu;
}
@@ -62,7 +60,6 @@ public class CoordinateSystem {
*
* @return An instance of the East-Down-North (EDN) coordinate system.
*/
@SuppressWarnings("MethodName")
public static CoordinateSystem EDN() {
return m_edn;
}
@@ -74,7 +71,6 @@ public class CoordinateSystem {
*
* @return An instance of the North-East-Down (NED) coordinate system.
*/
@SuppressWarnings("MethodName")
public static CoordinateSystem NED() {
return m_ned;
}

View File

@@ -244,7 +244,6 @@ public class Pose2d implements Interpolatable<Pose2d> {
}
@Override
@SuppressWarnings("ParameterName")
public Pose2d interpolate(Pose2d endValue, double t) {
if (t < 0) {
return this;

View File

@@ -158,7 +158,6 @@ public class Pose3d implements Interpolatable<Pose3d> {
* Rotation3d(0.0, 0.0, Units.degreesToRadians(0.5))).
* @return The new pose of the robot.
*/
@SuppressWarnings("LocalVariableName")
public Pose3d exp(Twist3d twist) {
final var Omega = rotationVectorToMatrix(VecBuilder.fill(twist.rx, twist.ry, twist.rz));
final var OmegaSq = Omega.times(Omega);
@@ -199,7 +198,6 @@ public class Pose3d implements Interpolatable<Pose3d> {
* @param end The end pose for the transformation.
* @return The twist that maps this to end.
*/
@SuppressWarnings("LocalVariableName")
public Twist3d log(Pose3d end) {
final var transform = end.relativeTo(this);
@@ -282,7 +280,6 @@ public class Pose3d implements Interpolatable<Pose3d> {
}
@Override
@SuppressWarnings("ParameterName")
public Pose3d interpolate(Pose3d endValue, double t) {
if (t < 0) {
return this;

View File

@@ -236,7 +236,6 @@ public class Rotation2d implements Interpolatable<Rotation2d> {
}
@Override
@SuppressWarnings("ParameterName")
public Rotation2d interpolate(Rotation2d endValue, double t) {
return plus(endValue.minus(this).times(MathUtil.clamp(t, 0, 1)));
}

View File

@@ -170,7 +170,6 @@ public class Rotation3d implements Interpolatable<Rotation3d> {
// so a 180 degree rotation is required. Any orthogonal vector can be used
// for it. Q in the QR decomposition is an orthonormal basis, so it
// contains orthogonal unit vectors.
@SuppressWarnings("LocalVariableName")
var X =
new MatBuilder<>(Nat.N3(), Nat.N1())
.fill(initial.get(0, 0), initial.get(1, 0), initial.get(2, 0));
@@ -376,7 +375,6 @@ public class Rotation3d implements Interpolatable<Rotation3d> {
}
@Override
@SuppressWarnings("ParameterName")
public Rotation3d interpolate(Rotation3d endValue, double t) {
return plus(endValue.minus(this).times(MathUtil.clamp(t, 0, 1)));
}

View File

@@ -18,7 +18,6 @@ import java.util.Objects;
* <p>This assumes that you are using conventional mathematical axes. When the robot is at the
* origin facing in the positive X direction, forward is positive X and left is positive Y.
*/
@SuppressWarnings({"ParameterName", "MemberName"})
@JsonIgnoreProperties(ignoreUnknown = true)
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
public class Translation2d implements Interpolatable<Translation2d> {

View File

@@ -15,7 +15,6 @@ import java.util.Objects;
* origin facing in the positive X direction, forward is positive X, left is positive Y, and up is
* positive Z.
*/
@SuppressWarnings({"ParameterName", "MemberName"})
public class Translation3d implements Interpolatable<Translation3d> {
private final double m_x;
private final double m_y;

View File

@@ -12,7 +12,6 @@ import java.util.Objects;
*
* <p>A Twist can be used to represent a difference between two poses.
*/
@SuppressWarnings("MemberName")
public class Twist2d {
/** Linear "dx" component. */
public double dx;

View File

@@ -12,7 +12,6 @@ import java.util.Objects;
*
* <p>A Twist can be used to represent a difference between two poses.
*/
@SuppressWarnings("MemberName")
public class Twist3d {
/** Linear "dx" component. */
public double dx;

View File

@@ -20,6 +20,5 @@ public interface Interpolatable<T> {
* @param t How far between the lower and upper bound we are. This should be bounded in [0, 1].
* @return The interpolated value.
*/
@SuppressWarnings("ParameterName")
T interpolate(T endValue, double t);
}

View File

@@ -101,7 +101,6 @@ public final class TimeInterpolatableBuffer<T> {
* @param timeSeconds The time at which to sample.
* @return The interpolated value at that timestamp or an empty Optional.
*/
@SuppressWarnings("UnnecessaryParentheses")
public Optional<T> getSample(double timeSeconds) {
if (m_pastSnapshots.isEmpty()) {
return Optional.empty();
@@ -131,7 +130,7 @@ public final class TimeInterpolatableBuffer<T> {
m_interpolatingFunc.interpolate(
bottomBound.getValue(),
topBound.getValue(),
((timeSeconds - bottomBound.getKey()) / (topBound.getKey() - bottomBound.getKey()))));
(timeSeconds - bottomBound.getKey()) / (topBound.getKey() - bottomBound.getKey())));
}
}
@@ -145,7 +144,6 @@ public final class TimeInterpolatableBuffer<T> {
* @param t How far between the lower and upper bound we are. This should be bounded in [0, 1].
* @return The interpolated value.
*/
@SuppressWarnings("ParameterName")
T interpolate(T start, T end, double t);
}
}

View File

@@ -16,7 +16,6 @@ import edu.wpi.first.math.geometry.Rotation2d;
* component because it can never move sideways. Holonomic drivetrains such as swerve and mecanum
* will often have all three components.
*/
@SuppressWarnings("MemberName")
public class ChassisSpeeds {
/** Represents forward velocity w.r.t the robot frame of reference. (Fwd is +) */
public double vxMetersPerSecond;

View File

@@ -15,7 +15,6 @@ import edu.wpi.first.math.MathUsageId;
* whereas forward kinematics converts left and right component velocities into a linear and angular
* chassis speed.
*/
@SuppressWarnings("MemberName")
public class DifferentialDriveKinematics {
public final double trackWidthMeters;

View File

@@ -5,7 +5,6 @@
package edu.wpi.first.math.kinematics;
/** Represents the wheel speeds for a differential drive drivetrain. */
@SuppressWarnings("MemberName")
public class DifferentialDriveWheelSpeeds {
/** Speed of the left side of the robot. */
public double leftMetersPerSecond;

View File

@@ -5,7 +5,6 @@
package edu.wpi.first.math.kinematics;
/** Represents the motor voltages for a mecanum drive drivetrain. */
@SuppressWarnings("MemberName")
public class MecanumDriveMotorVoltages {
/** Voltage of the front left motor. */
public double frontLeftVoltage;

View File

@@ -6,7 +6,6 @@ package edu.wpi.first.math.kinematics;
import java.util.stream.DoubleStream;
@SuppressWarnings("MemberName")
public class MecanumDriveWheelSpeeds {
/** Speed of the front left wheel. */
public double frontLeftMetersPerSecond;

View File

@@ -89,7 +89,7 @@ public class SwerveDriveKinematics {
* attainable max velocity. Use the {@link #desaturateWheelSpeeds(SwerveModuleState[], double)
* DesaturateWheelSpeeds} function to rectify this issue.
*/
@SuppressWarnings({"LocalVariableName", "PMD.MethodReturnsInternalArray"})
@SuppressWarnings("PMD.MethodReturnsInternalArray")
public SwerveModuleState[] toSwerveModuleStates(
ChassisSpeeds chassisSpeeds, Translation2d centerOfRotationMeters) {
if (chassisSpeeds.vxMetersPerSecond == 0.0

View File

@@ -8,7 +8,6 @@ import edu.wpi.first.math.geometry.Rotation2d;
import java.util.Objects;
/** Represents the state of one swerve module. */
@SuppressWarnings("MemberName")
public class SwerveModuleState implements Comparable<SwerveModuleState> {
/** Speed of the wheel of the module. */
public double speedMetersPerSecond;

View File

@@ -19,7 +19,6 @@ public class CubicHermiteSpline extends Spline {
* @param yInitialControlVector The control vector for the initial point in the y dimension.
* @param yFinalControlVector The control vector for the final point in the y dimension.
*/
@SuppressWarnings("ParameterName")
public CubicHermiteSpline(
double[] xInitialControlVector,
double[] xFinalControlVector,

View File

@@ -7,7 +7,6 @@ package edu.wpi.first.math.spline;
import edu.wpi.first.math.geometry.Pose2d;
/** Represents a pair of a pose and a curvature. */
@SuppressWarnings("MemberName")
public class PoseWithCurvature {
// Represents the pose.
public Pose2d poseMeters;

View File

@@ -19,7 +19,6 @@ public class QuinticHermiteSpline extends Spline {
* @param yInitialControlVector The control vector for the initial point in the y dimension.
* @param yFinalControlVector The control vector for the final point in the y dimension.
*/
@SuppressWarnings("ParameterName")
public QuinticHermiteSpline(
double[] xInitialControlVector,
double[] xFinalControlVector,

View File

@@ -35,7 +35,6 @@ public abstract class Spline {
* @param t The point t
* @return The pose and curvature at that point.
*/
@SuppressWarnings("ParameterName")
public PoseWithCurvature getPoint(double t) {
SimpleMatrix polynomialBases = new SimpleMatrix(m_degree + 1, 1);
final var coefficients = getCoefficients();
@@ -85,7 +84,6 @@ public abstract class Spline {
* <p>Each element in each array represents the value of the derivative at the index. For example,
* the value of x[2] is the second derivative in the x dimension.
*/
@SuppressWarnings("MemberName")
public static class ControlVector {
public double[] x;
public double[] y;
@@ -96,7 +94,6 @@ public abstract class Spline {
* @param x The x dimension of the control vector.
* @param y The y dimension of the control vector.
*/
@SuppressWarnings("ParameterName")
public ControlVector(double[] x, double[] y) {
this.x = Arrays.copyOf(x, x.length);
this.y = Arrays.copyOf(y, y.length);

View File

@@ -78,7 +78,6 @@ public final class SplineHelper {
* @return A vector of cubic hermite splines that interpolate through the provided waypoints and
* control vectors.
*/
@SuppressWarnings("LocalVariableName")
public static CubicHermiteSpline[] getCubicSplinesFromControlVectors(
Spline.ControlVector start, Translation2d[] waypoints, Spline.ControlVector end) {
CubicHermiteSpline[] splines = new CubicHermiteSpline[waypoints.length + 1];
@@ -202,7 +201,6 @@ public final class SplineHelper {
* @param controlVectors The control vectors.
* @return A vector of quintic hermite splines that interpolate through the provided waypoints.
*/
@SuppressWarnings("LocalVariableName")
public static QuinticHermiteSpline[] getQuinticSplinesFromControlVectors(
Spline.ControlVector[] controlVectors) {
QuinticHermiteSpline[] splines = new QuinticHermiteSpline[controlVectors.length - 1];
@@ -228,7 +226,6 @@ public final class SplineHelper {
* @param d the vector on the rhs
* @param solutionVector the unknown (solution) vector, modified in-place
*/
@SuppressWarnings({"ParameterName", "LocalVariableName"})
private static void thomasAlgorithm(
double[] a, double[] b, double[] c, double[] d, double[] solutionVector) {
int N = d.length;

View File

@@ -46,7 +46,6 @@ public final class SplineParameterizer {
*/
private static final int kMaxIterations = 5000;
@SuppressWarnings("MemberName")
private static class StackContents {
final double t1;
final double t0;

View File

@@ -9,7 +9,6 @@ import edu.wpi.first.math.Num;
import edu.wpi.first.math.Pair;
import org.ejml.simple.SimpleMatrix;
@SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
public final class Discretization {
private Discretization() {
// Utility class
@@ -39,7 +38,6 @@ public final class Discretization {
* @param dtSeconds Discretization timestep.
* @return a Pair representing discA and diskB.
*/
@SuppressWarnings("LocalVariableName")
public static <States extends Num, Inputs extends Num>
Pair<Matrix<States, States>, Matrix<States, Inputs>> discretizeAB(
Matrix<States, States> contA, Matrix<States, Inputs> contB, double dtSeconds) {
@@ -74,7 +72,6 @@ public final class Discretization {
* @param dtSeconds Discretization timestep.
* @return a pair representing the discrete system matrix and process noise covariance matrix.
*/
@SuppressWarnings("LocalVariableName")
public static <States extends Num>
Pair<Matrix<States, States>, Matrix<States, States>> discretizeAQ(
Matrix<States, States> contA, Matrix<States, States> contQ, double dtSeconds) {
@@ -130,7 +127,6 @@ public final class Discretization {
* @param dtSeconds Discretization timestep.
* @return a pair representing the discrete system matrix and process noise covariance matrix.
*/
@SuppressWarnings("LocalVariableName")
public static <States extends Num>
Pair<Matrix<States, States>, Matrix<States, States>> discretizeAQTaylor(
Matrix<States, States> contA, Matrix<States, States> contQ, double dtSeconds) {
@@ -204,12 +200,12 @@ public final class Discretization {
* Note that dt=0.0 divides R by zero.
*
* @param <O> Nat representing the number of outputs.
* @param R Continuous measurement noise covariance matrix.
* @param contR Continuous measurement noise covariance matrix.
* @param dtSeconds Discretization timestep.
* @return Discretized version of the provided continuous measurement noise covariance matrix.
*/
public static <O extends Num> Matrix<O, O> discretizeR(Matrix<O, O> R, double dtSeconds) {
public static <O extends Num> Matrix<O, O> discretizeR(Matrix<O, O> contR, double dtSeconds) {
// R_d = 1/T R
return R.div(dtSeconds);
return contR.div(dtSeconds);
}
}

View File

@@ -8,76 +8,70 @@ import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.Num;
import edu.wpi.first.math.numbers.N1;
@SuppressWarnings("ClassTypeParameterName")
public class LinearSystem<States extends Num, Inputs extends Num, Outputs extends Num> {
/** Continuous system matrix. */
@SuppressWarnings("MemberName")
private final Matrix<States, States> m_A;
/** Continuous input matrix. */
@SuppressWarnings("MemberName")
private final Matrix<States, Inputs> m_B;
/** Output matrix. */
@SuppressWarnings("MemberName")
private final Matrix<Outputs, States> m_C;
/** Feedthrough matrix. */
@SuppressWarnings("MemberName")
private final Matrix<Outputs, Inputs> m_D;
/**
* Construct a new LinearSystem from the four system matrices.
*
* @param a The system matrix A.
* @param b The input matrix B.
* @param c The output matrix C.
* @param d The feedthrough matrix D.
* @param A The system matrix A.
* @param B The input matrix B.
* @param C The output matrix C.
* @param D The feedthrough matrix D.
* @throws IllegalArgumentException if any matrix element isn't finite.
*/
@SuppressWarnings("ParameterName")
public LinearSystem(
Matrix<States, States> a,
Matrix<States, Inputs> b,
Matrix<Outputs, States> c,
Matrix<Outputs, Inputs> d) {
for (int row = 0; row < a.getNumRows(); ++row) {
for (int col = 0; col < a.getNumCols(); ++col) {
if (!Double.isFinite(a.get(row, col))) {
Matrix<States, States> A,
Matrix<States, Inputs> B,
Matrix<Outputs, States> C,
Matrix<Outputs, Inputs> D) {
for (int row = 0; row < A.getNumRows(); ++row) {
for (int col = 0; col < A.getNumCols(); ++col) {
if (!Double.isFinite(A.get(row, col))) {
throw new IllegalArgumentException(
"Elements of A aren't finite. This is usually due to model implementation errors.");
}
}
}
for (int row = 0; row < b.getNumRows(); ++row) {
for (int col = 0; col < b.getNumCols(); ++col) {
if (!Double.isFinite(b.get(row, col))) {
for (int row = 0; row < B.getNumRows(); ++row) {
for (int col = 0; col < B.getNumCols(); ++col) {
if (!Double.isFinite(B.get(row, col))) {
throw new IllegalArgumentException(
"Elements of B aren't finite. This is usually due to model implementation errors.");
}
}
}
for (int row = 0; row < c.getNumRows(); ++row) {
for (int col = 0; col < c.getNumCols(); ++col) {
if (!Double.isFinite(c.get(row, col))) {
for (int row = 0; row < C.getNumRows(); ++row) {
for (int col = 0; col < C.getNumCols(); ++col) {
if (!Double.isFinite(C.get(row, col))) {
throw new IllegalArgumentException(
"Elements of C aren't finite. This is usually due to model implementation errors.");
}
}
}
for (int row = 0; row < d.getNumRows(); ++row) {
for (int col = 0; col < d.getNumCols(); ++col) {
if (!Double.isFinite(d.get(row, col))) {
for (int row = 0; row < D.getNumRows(); ++row) {
for (int col = 0; col < D.getNumCols(); ++col) {
if (!Double.isFinite(D.get(row, col))) {
throw new IllegalArgumentException(
"Elements of D aren't finite. This is usually due to model implementation errors.");
}
}
}
this.m_A = a;
this.m_B = b;
this.m_C = c;
this.m_D = d;
this.m_A = A;
this.m_B = B;
this.m_C = C;
this.m_D = D;
}
/**
@@ -170,7 +164,6 @@ public class LinearSystem<States extends Num, Inputs extends Num, Outputs extend
* @param dtSeconds Timestep for model update.
* @return the updated x.
*/
@SuppressWarnings("ParameterName")
public Matrix<States, N1> calculateX(
Matrix<States, N1> x, Matrix<Inputs, N1> clampedU, double dtSeconds) {
var discABpair = Discretization.discretizeAB(m_A, m_B, dtSeconds);
@@ -187,7 +180,6 @@ public class LinearSystem<States extends Num, Inputs extends Num, Outputs extend
* @param clampedU The control input.
* @return the updated output matrix Y.
*/
@SuppressWarnings("ParameterName")
public Matrix<Outputs, N1> calculateY(Matrix<States, N1> x, Matrix<Inputs, N1> clampedU) {
return m_C.times(x).plus(m_D.times(clampedU));
}

View File

@@ -28,7 +28,6 @@ import org.ejml.simple.SimpleMatrix;
* <p>For more on the underlying math, read
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
*/
@SuppressWarnings("ClassTypeParameterName")
public class LinearSystemLoop<States extends Num, Inputs extends Num, Outputs extends Num> {
private final LinearQuadraticRegulator<States, Inputs, Outputs> m_controller;
private final LinearPlantInversionFeedforward<States, Inputs, Outputs> m_feedforward;
@@ -315,7 +314,6 @@ public class LinearSystemLoop<States extends Num, Inputs extends Num, Outputs ex
*
* @param y Measurement vector.
*/
@SuppressWarnings("ParameterName")
public void correct(Matrix<Outputs, N1> y) {
getObserver().correct(getU(), y);
}
@@ -327,7 +325,6 @@ public class LinearSystemLoop<States extends Num, Inputs extends Num, Outputs ex
*
* @param dtSeconds Timestep for model update.
*/
@SuppressWarnings("LocalVariableName")
public void predict(double dtSeconds) {
var u =
clampInput(

View File

@@ -24,7 +24,7 @@ public final class NumericalIntegration {
* @param dtSeconds The time over which to integrate.
* @return the integration of dx/dt = f(x) for dt.
*/
@SuppressWarnings({"ParameterName", "overloads"})
@SuppressWarnings("overloads")
public static double rk4(DoubleFunction<Double> f, double x, double dtSeconds) {
final var h = dtSeconds;
final var k1 = f.apply(x);
@@ -44,7 +44,7 @@ public final class NumericalIntegration {
* @param dtSeconds The time over which to integrate.
* @return The result of Runge Kutta integration (4th order).
*/
@SuppressWarnings({"ParameterName", "overloads"})
@SuppressWarnings("overloads")
public static double rk4(
BiFunction<Double, Double, Double> f, double x, Double u, double dtSeconds) {
final var h = dtSeconds;
@@ -68,7 +68,7 @@ public final class NumericalIntegration {
* @param dtSeconds The time over which to integrate.
* @return the integration of dx/dt = f(x, u) for dt.
*/
@SuppressWarnings({"ParameterName", "MethodTypeParameterName", "overloads"})
@SuppressWarnings("overloads")
public static <States extends Num, Inputs extends Num> Matrix<States, N1> rk4(
BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> f,
Matrix<States, N1> x,
@@ -93,7 +93,7 @@ public final class NumericalIntegration {
* @param dtSeconds The time over which to integrate.
* @return 4th order Runge-Kutta integration of dx/dt = f(x) for dt.
*/
@SuppressWarnings({"ParameterName", "MethodTypeParameterName", "overloads"})
@SuppressWarnings("overloads")
public static <States extends Num> Matrix<States, N1> rk4(
Function<Matrix<States, N1>, Matrix<States, N1>> f, Matrix<States, N1> x, double dtSeconds) {
final var h = dtSeconds;
@@ -119,7 +119,7 @@ public final class NumericalIntegration {
* @param dtSeconds The time over which to integrate.
* @return the integration of dx/dt = f(x, u) for dt.
*/
@SuppressWarnings("MethodTypeParameterName")
@SuppressWarnings("overloads")
public static <States extends Num, Inputs extends Num> Matrix<States, N1> rkf45(
BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> f,
Matrix<States, N1> x,
@@ -141,7 +141,7 @@ public final class NumericalIntegration {
* @param maxError The maximum acceptable truncation error. Usually a small number like 1e-6.
* @return the integration of dx/dt = f(x, u) for dt.
*/
@SuppressWarnings("MethodTypeParameterName")
@SuppressWarnings("overloads")
public static <States extends Num, Inputs extends Num> Matrix<States, N1> rkf45(
BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> f,
Matrix<States, N1> x,
@@ -251,7 +251,7 @@ public final class NumericalIntegration {
* @param dtSeconds The time over which to integrate.
* @return the integration of dx/dt = f(x, u) for dt.
*/
@SuppressWarnings("MethodTypeParameterName")
@SuppressWarnings("overloads")
public static <States extends Num, Inputs extends Num> Matrix<States, N1> rkdp(
BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> f,
Matrix<States, N1> x,
@@ -272,7 +272,7 @@ public final class NumericalIntegration {
* @param maxError The maximum acceptable truncation error. Usually a small number like 1e-6.
* @return the integration of dx/dt = f(x, u) for dt.
*/
@SuppressWarnings("MethodTypeParameterName")
@SuppressWarnings("overloads")
public static <States extends Num, Inputs extends Num> Matrix<States, N1> rkdp(
BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> f,
Matrix<States, N1> x,

View File

@@ -30,7 +30,6 @@ public final class NumericalJacobian {
* @param x Vector argument.
* @return The numerical Jacobian with respect to x for f(x, u, ...).
*/
@SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
public static <Rows extends Num, Cols extends Num, States extends Num>
Matrix<Rows, Cols> numericalJacobian(
Nat<Rows> rows,
@@ -44,7 +43,6 @@ public final class NumericalJacobian {
var dxMinus = x.copy();
dxPlus.set(i, 0, dxPlus.get(i, 0) + kEpsilon);
dxMinus.set(i, 0, dxMinus.get(i, 0) - kEpsilon);
@SuppressWarnings("LocalVariableName")
var dF = f.apply(dxPlus).minus(f.apply(dxMinus)).div(2 * kEpsilon);
result.setColumn(i, Matrix.changeBoundsUnchecked(dF));
@@ -67,7 +65,6 @@ public final class NumericalJacobian {
* @param u Input vector.
* @return The numerical Jacobian with respect to x for f(x, u, ...).
*/
@SuppressWarnings({"LambdaParameterName", "MethodTypeParameterName"})
public static <Rows extends Num, States extends Num, Inputs extends Num, Outputs extends Num>
Matrix<Rows, States> numericalJacobianX(
Nat<Rows> rows,
@@ -91,7 +88,6 @@ public final class NumericalJacobian {
* @param u Input vector.
* @return the numerical Jacobian with respect to u for f(x, u).
*/
@SuppressWarnings({"LambdaParameterName", "MethodTypeParameterName"})
public static <Rows extends Num, States extends Num, Inputs extends Num>
Matrix<Rows, Inputs> numericalJacobianU(
Nat<Rows> rows,

View File

@@ -8,28 +8,13 @@ import edu.wpi.first.math.util.Units;
/** Holds the constants for a DC motor. */
public class DCMotor {
@SuppressWarnings("MemberName")
public final double nominalVoltageVolts;
@SuppressWarnings("MemberName")
public final double stallTorqueNewtonMeters;
@SuppressWarnings("MemberName")
public final double stallCurrentAmps;
@SuppressWarnings("MemberName")
public final double freeCurrentAmps;
@SuppressWarnings("MemberName")
public final double freeSpeedRadPerSec;
@SuppressWarnings("MemberName")
public final double rOhms;
@SuppressWarnings("MemberName")
public final double KvRadPerSecPerVolt;
@SuppressWarnings("MemberName")
public final double KtNMPerAmp;
/**

View File

@@ -27,7 +27,6 @@ public final class LinearSystemId {
* @return A LinearSystem representing the given characterized constants.
* @throws IllegalArgumentException if massKg &lt;= 0, radiusMeters &lt;= 0, or G &lt;= 0.
*/
@SuppressWarnings("ParameterName")
public static LinearSystem<N2, N1, N1> createElevatorSystem(
DCMotor motor, double massKg, double radiusMeters, double G) {
if (massKg <= 0.0) {
@@ -68,7 +67,6 @@ public final class LinearSystemId {
* @return A LinearSystem representing the given characterized constants.
* @throws IllegalArgumentException if JKgMetersSquared &lt;= 0 or G &lt;= 0.
*/
@SuppressWarnings("ParameterName")
public static LinearSystem<N1, N1, N1> createFlywheelSystem(
DCMotor motor, double JKgMetersSquared, double G) {
if (JKgMetersSquared <= 0.0) {
@@ -100,7 +98,6 @@ public final class LinearSystemId {
* @return A LinearSystem representing the given characterized constants.
* @throws IllegalArgumentException if JKgMetersSquared &lt;= 0 or G &lt;= 0.
*/
@SuppressWarnings("ParameterName")
public static LinearSystem<N2, N1, N2> createDCMotorSystem(
DCMotor motor, double JKgMetersSquared, double G) {
if (JKgMetersSquared <= 0.0) {
@@ -139,7 +136,6 @@ public final class LinearSystemId {
* @return A LinearSystem representing a differential drivetrain.
* @throws IllegalArgumentException if m &lt;= 0, r &lt;= 0, rb &lt;= 0, J &lt;= 0, or G &lt;= 0.
*/
@SuppressWarnings({"LocalVariableName", "ParameterName"})
public static LinearSystem<N2, N2, N2> createDrivetrainVelocitySystem(
DCMotor motor,
double massKg,
@@ -187,7 +183,6 @@ public final class LinearSystemId {
* will be greater than 1.
* @return A LinearSystem representing the given characterized constants.
*/
@SuppressWarnings("ParameterName")
public static LinearSystem<N2, N1, N1> createSingleJointedArmSystem(
DCMotor motor, double JKgSquaredMeters, double G) {
if (JKgSquaredMeters <= 0.0) {
@@ -229,7 +224,6 @@ public final class LinearSystemId {
* @throws IllegalArgumentException if kV &lt;= 0 or kA &lt;= 0.
* @see <a href="https://github.com/wpilibsuite/sysid">https://github.com/wpilibsuite/sysid</a>
*/
@SuppressWarnings("ParameterName")
public static LinearSystem<N1, N1, N1> identifyVelocitySystem(double kV, double kA) {
if (kV <= 0.0) {
throw new IllegalArgumentException("Kv must be greater than zero.");
@@ -263,7 +257,6 @@ public final class LinearSystemId {
* @throws IllegalArgumentException if kV &lt;= 0 or kA &lt;= 0.
* @see <a href="https://github.com/wpilibsuite/sysid">https://github.com/wpilibsuite/sysid</a>
*/
@SuppressWarnings("ParameterName")
public static LinearSystem<N2, N1, N1> identifyPositionSystem(double kV, double kA) {
if (kV <= 0.0) {
throw new IllegalArgumentException("Kv must be greater than zero.");
@@ -297,7 +290,6 @@ public final class LinearSystemId {
* kAAngular &lt;= 0.
* @see <a href="https://github.com/wpilibsuite/sysid">https://github.com/wpilibsuite/sysid</a>
*/
@SuppressWarnings("ParameterName")
public static LinearSystem<N2, N2, N2> identifyDrivetrainSystem(
double kVLinear, double kALinear, double kVAngular, double kAAngular) {
if (kVLinear <= 0.0) {
@@ -345,7 +337,6 @@ public final class LinearSystemId {
* kAAngular &lt;= 0, or trackwidth &lt;= 0.
* @see <a href="https://github.com/wpilibsuite/sysid">https://github.com/wpilibsuite/sysid</a>
*/
@SuppressWarnings("ParameterName")
public static LinearSystem<N2, N2, N2> identifyDrivetrainSystem(
double kVLinear, double kALinear, double kVAngular, double kAAngular, double trackwidth) {
if (kVLinear <= 0.0) {

View File

@@ -44,7 +44,6 @@ public class Trajectory {
* @param t The fraction for interpolation.
* @return The interpolated value.
*/
@SuppressWarnings("ParameterName")
private static double lerp(double startValue, double endValue, double t) {
return startValue + (endValue - startValue) * t;
}
@@ -57,7 +56,6 @@ public class Trajectory {
* @param t The fraction for interpolation.
* @return The interpolated pose.
*/
@SuppressWarnings("ParameterName")
private static Pose2d lerp(Pose2d startValue, Pose2d endValue, double t) {
return startValue.plus((endValue.minus(startValue)).times(t));
}
@@ -254,7 +252,6 @@ public class Trajectory {
* Represents a time-parameterized trajectory. The trajectory contains of various States that
* represent the pose, curvature, time elapsed, velocity, and acceleration at that point.
*/
@SuppressWarnings("MemberName")
public static class State {
// The time elapsed since the beginning of the trajectory.
@JsonProperty("time")
@@ -309,7 +306,6 @@ public class Trajectory {
* @param i The interpolant (fraction).
* @return The interpolated state.
*/
@SuppressWarnings("ParameterName")
State interpolate(State endValue, double i) {
// Find the new t value.
final double newT = lerp(timeSeconds, endValue.timeSeconds, i);

View File

@@ -193,7 +193,6 @@ public final class TrajectoryGenerator {
* @param config The configuration for the trajectory.
* @return The generated trajectory.
*/
@SuppressWarnings("LocalVariableName")
public static Trajectory generateTrajectory(List<Pose2d> waypoints, TrajectoryConfig config) {
final var flip = new Transform2d(new Translation2d(), Rotation2d.fromDegrees(180.0));

View File

@@ -294,7 +294,6 @@ public final class TrajectoryParameterizer {
}
}
@SuppressWarnings("MemberName")
private static class ConstrainedState {
PoseWithCurvature pose;
double distanceMeters;

View File

@@ -51,10 +51,8 @@ public class TrapezoidProfile {
private double m_endDeccel;
public static class Constraints {
@SuppressWarnings("MemberName")
public final double maxVelocity;
@SuppressWarnings("MemberName")
public final double maxAcceleration;
/**
@@ -71,10 +69,8 @@ public class TrapezoidProfile {
}
public static class State {
@SuppressWarnings("MemberName")
public double position;
@SuppressWarnings("MemberName")
public double velocity;
public State() {}

View File

@@ -23,7 +23,6 @@ public class EllipticalRegionConstraint implements TrajectoryConstraint {
* @param rotation The rotation to apply to all radii around the origin.
* @param constraint The constraint to enforce when the robot is within the region.
*/
@SuppressWarnings("ParameterName")
public EllipticalRegionConstraint(
Translation2d center,
double xWidth,

View File

@@ -36,7 +36,6 @@ public interface TrajectoryConstraint {
Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond);
/** Represents a minimum and maximum acceleration. */
@SuppressWarnings("MemberName")
class MinMax {
public double minAccelerationMetersPerSecondSq = -Double.MAX_VALUE;
public double maxAccelerationMetersPerSecondSq = +Double.MAX_VALUE;