mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
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:
@@ -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;
|
||||
|
||||
@@ -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);
|
||||
|
||||
|
||||
@@ -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);
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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,
|
||||
|
||||
@@ -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,
|
||||
|
||||
@@ -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())
|
||||
|
||||
@@ -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))));
|
||||
|
||||
|
||||
@@ -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);
|
||||
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
@@ -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⁻¹ < zeta < 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;
|
||||
|
||||
@@ -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;
|
||||
|
||||
Reference in New Issue
Block a user