Clean up Java style (#5990)

Also make equivalent changes in C++ where applicable.

Co-authored-by: Sriman Achanta <68172138+srimanachanta@users.noreply.github.com>
This commit is contained in:
Tyler Veness
2023-12-03 16:21:32 -08:00
committed by GitHub
parent 66172ab288
commit 2bb1409b82
113 changed files with 426 additions and 617 deletions

View File

@@ -288,7 +288,7 @@ public class Matrix<R extends Num, C extends Num> {
* @return The resultant matrix.
*/
public Matrix<R, C> div(int value) {
return new Matrix<>(this.m_storage.divide((double) value));
return new Matrix<>(this.m_storage.divide(value));
}
/**
@@ -488,7 +488,7 @@ public class Matrix<R extends Num, C extends Num> {
* @return The element by element power of "this" and b.
*/
public final Matrix<R, C> elementPower(int b) {
return new Matrix<>(this.m_storage.elementPower((double) b));
return new Matrix<>(this.m_storage.elementPower(b));
}
/**
@@ -545,7 +545,7 @@ public class Matrix<R extends Num, C extends Num> {
*/
public final <R2 extends Num, C2 extends Num> Matrix<R2, C2> block(
int height, int width, int startingRow, int startingCol) {
return new Matrix<R2, C2>(
return new Matrix<>(
this.m_storage.extractMatrix(
startingRow, startingRow + height, startingCol, startingCol + width));
}
@@ -607,8 +607,7 @@ public class Matrix<R extends Num, C extends Num> {
return new Matrix<>(new SimpleMatrix(temp.getNumRows(), temp.getNumCols()));
}
throw new RuntimeException(
"Cholesky decomposition failed! Input matrix:\n" + m_storage.toString());
throw new RuntimeException("Cholesky decomposition failed! Input matrix:\n" + m_storage);
}
return new Matrix<>(SimpleMatrix.wrap(chol.getT(null)));

View File

@@ -16,9 +16,8 @@ import java.util.function.Function;
* Constructs a control-affine plant inversion model-based feedforward from given model dynamics.
*
* <p>If given the vector valued function as f(x, u) where x is the state vector and u is the input
* vector, the B matrix(continuous input matrix) is calculated through a {@link
* edu.wpi.first.math.system.NumericalJacobian}. In this case f has to be control-affine (of the
* form f(x) + Bu).
* vector, the B matrix(continuous input matrix) is calculated through a {@link NumericalJacobian}.
* In this case f has to be control-affine (of the form f(x) + Bu).
*
* <p>The feedforward is calculated as <strong> u_ff = B<sup>+</sup> (rDot - f(x))</strong>, where
* <strong> B<sup>+</sup> </strong> is the pseudoinverse of B.
@@ -26,8 +25,8 @@ import java.util.function.Function;
* <p>This feedforward does not account for a dynamic B matrix, B is either determined or supplied
* when the feedforward is created and remains constant.
*
* <p>For more on the underlying math, read
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
* <p>For more on the underlying math, read <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">https://file.tavsys.net/control/controls-engineering-in-frc.pdf</a>.
*/
public class ControlAffinePlantInversionFeedforward<States extends Num, Inputs extends Num> {
/** The current reference state. */

View File

@@ -17,8 +17,8 @@ import org.ejml.simple.SimpleMatrix;
* system and makes it behave like some other system. This can be used to make a drivetrain more
* controllable during teleop driving by making it behave like a slower or more benign drivetrain.
*
* <p>For more on the underlying math, read appendix B.3 in
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
* <p>For more on the underlying math, read appendix B.3 in <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">https://file.tavsys.net/control/controls-engineering-in-frc.pdf</a>.
*/
public class ImplicitModelFollower<States extends Num, Inputs extends Num, Outputs extends Num> {
// Computed controller output

View File

@@ -65,8 +65,8 @@ public class LTVDifferentialDriveController {
/**
* Constructs a linear time-varying differential drive controller.
*
* <p>See
* https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning
* <p>See <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning">https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning</a>
* for how to select the tolerances.
*
* @param plant The differential drive velocity plant.

View File

@@ -80,8 +80,8 @@ public class LTVUnicycleController {
/**
* Constructs a linear time-varying unicycle controller.
*
* <p>See
* https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning
* <p>See <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning">https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning</a>
* for how to select the tolerances.
*
* @param qelems The maximum desired error tolerance for each state.
@@ -95,8 +95,8 @@ public class LTVUnicycleController {
/**
* Constructs a linear time-varying unicycle controller.
*
* <p>See
* https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning
* <p>See <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning">https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning</a>
* for how to select the tolerances.
*
* @param qelems The maximum desired error tolerance for each state.

View File

@@ -17,8 +17,8 @@ import org.ejml.simple.SimpleMatrix;
* <p>The feedforward is calculated as <strong> u_ff = B<sup>+</sup> (r_k+1 - A r_k) </strong>,
* where <strong> B<sup>+</sup> </strong> is the pseudoinverse of B.
*
* <p>For more on the underlying math, read
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
* <p>For more on the underlying math, read <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">https://file.tavsys.net/control/controls-engineering-in-frc.pdf</a>.
*/
public class LinearPlantInversionFeedforward<
States extends Num, Inputs extends Num, Outputs extends Num> {

View File

@@ -19,8 +19,8 @@ import org.ejml.simple.SimpleMatrix;
* Contains the controller coefficients and logic for a linear-quadratic regulator (LQR). LQRs use
* the control law u = K(r - x).
*
* <p>For more on the underlying math, read
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
* <p>For more on the underlying math, read <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">https://file.tavsys.net/control/controls-engineering-in-frc.pdf</a>.
*/
public class LinearQuadraticRegulator<States extends Num, Inputs extends Num, Outputs extends Num> {
/** The current reference state. */
@@ -35,8 +35,8 @@ public class LinearQuadraticRegulator<States extends Num, Inputs extends Num, Ou
/**
* Constructs a controller with the given coefficients and plant. Rho is defaulted to 1.
*
* <p>See
* https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning
* <p>See <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning">https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning</a>
* for how to select the tolerances.
*
* @param plant The plant being controlled.
@@ -61,8 +61,8 @@ public class LinearQuadraticRegulator<States extends Num, Inputs extends Num, Ou
/**
* Constructs a controller with the given coefficients and plant.
*
* <p>See
* https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning
* <p>See <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning">https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning</a>
* for how to select the tolerances.
*
* @param A Continuous system matrix of the plant being controlled.
@@ -107,14 +107,12 @@ public class LinearQuadraticRegulator<States extends Num, Inputs extends Num, Ou
var discB = discABPair.getSecond();
if (!StateSpaceUtil.isStabilizable(discA, discB)) {
var builder = new StringBuilder("The system passed to the LQR is uncontrollable!\n\nA =\n");
builder
.append(discA.getStorage().toString())
.append("\nB =\n")
.append(discB.getStorage().toString())
.append('\n');
var msg = builder.toString();
var msg =
"The system passed to the LQR is uncontrollable!\n\nA =\n"
+ discA.getStorage().toString()
+ "\nB =\n"
+ discB.getStorage().toString()
+ '\n';
MathSharedStore.reportError(msg, Thread.currentThread().getStackTrace());
throw new IllegalArgumentException(msg);
}
@@ -258,8 +256,9 @@ public class LinearQuadraticRegulator<States extends Num, Inputs extends Num, Ou
* are time-delayed too long, the LQR may be unstable. However, if we know the amount of delay, we
* can compute the control based on where the system will be after the time delay.
*
* <p>See https://file.tavsys.net/control/controls-engineering-in-frc.pdf appendix C.4 for a
* derivation.
* <p>See <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">https://file.tavsys.net/control/controls-engineering-in-frc.pdf</a>
* appendix C.4 for a derivation.
*
* @param plant The plant being controlled.
* @param dtSeconds Discretization timestep in seconds.

View File

@@ -30,9 +30,9 @@ import java.util.function.BiFunction;
* error covariance by linearizing the models around the state estimate, then applying the linear
* Kalman filter equations.
*
* <p>For more on the underlying math, read
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9 "Stochastic control
* theory".
* <p>For more on the underlying math, read <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">https://file.tavsys.net/control/controls-engineering-in-frc.pdf</a>
* chapter 9 "Stochastic control theory".
*/
public class ExtendedKalmanFilter<States extends Num, Inputs extends Num, Outputs extends Num>
implements KalmanTypeFilter<States, Inputs, Outputs> {
@@ -59,8 +59,8 @@ public class ExtendedKalmanFilter<States extends Num, Inputs extends Num, Output
/**
* Constructs an extended Kalman filter.
*
* <p>See
* https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices
* <p>See <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices">https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices</a>
* for how to select the standard deviations.
*
* @param states a Nat representing the number of states.
@@ -97,8 +97,8 @@ public class ExtendedKalmanFilter<States extends Num, Inputs extends Num, Output
/**
* Constructs an extended Kalman filter.
*
* <p>See
* https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices
* <p>See <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices">https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices</a>
* for how to select the standard deviations.
*
* @param states a Nat representing the number of states.

View File

@@ -25,9 +25,9 @@ import edu.wpi.first.math.system.LinearSystem;
* amount of the difference between the actual measurements and the measurements predicted by the
* model.
*
* <p>For more on the underlying math, read
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9 "Stochastic control
* theory".
* <p>For more on the underlying math, read <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">https://file.tavsys.net/control/controls-engineering-in-frc.pdf</a>
* chapter 9 "Stochastic control theory".
*/
public class KalmanFilter<States extends Num, Inputs extends Num, Outputs extends Num>
implements KalmanTypeFilter<States, Inputs, Outputs> {
@@ -45,8 +45,8 @@ public class KalmanFilter<States extends Num, Inputs extends Num, Outputs extend
/**
* Constructs a Kalman filter with the given plant.
*
* <p>See
* https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices
* <p>See <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices">https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices</a>
* for how to select the standard deviations.
*
* @param states A Nat representing the states of the system.
@@ -82,15 +82,12 @@ public class KalmanFilter<States extends Num, Inputs extends Num, Outputs extend
var C = plant.getC();
if (!StateSpaceUtil.isDetectable(discA, C)) {
var builder =
new StringBuilder("The system passed to the Kalman filter is unobservable!\n\nA =\n");
builder
.append(discA.getStorage().toString())
.append("\nC =\n")
.append(C.getStorage().toString())
.append('\n');
var msg = builder.toString();
var msg =
"The system passed to the Kalman filter is unobservable!\n\nA =\n"
+ discA.getStorage().toString()
+ "\nC =\n"
+ C.getStorage().toString()
+ '\n';
MathSharedStore.reportError(msg, Thread.currentThread().getStackTrace());
throw new IllegalArgumentException(msg);
}

View File

@@ -28,9 +28,9 @@ import edu.wpi.first.math.system.LinearSystem;
* <p>This class assumes predict() and correct() are called in pairs, so the Kalman gain converges
* to a steady-state value. If they aren't, use {@link KalmanFilter} instead.
*
* <p>For more on the underlying math, read
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9 "Stochastic control
* theory".
* <p>For more on the underlying math, read <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">https://file.tavsys.net/control/controls-engineering-in-frc.pdf</a>
* chapter 9 "Stochastic control theory".
*/
public class SteadyStateKalmanFilter<States extends Num, Inputs extends Num, Outputs extends Num> {
private final Nat<States> m_states;
@@ -46,8 +46,8 @@ public class SteadyStateKalmanFilter<States extends Num, Inputs extends Num, Out
/**
* Constructs a steady-state Kalman filter with the given plant.
*
* <p>See
* https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices
* <p>See <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices">https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices</a>
* for how to select the standard deviations.
*
* @param states A Nat representing the states of the system.
@@ -81,15 +81,12 @@ public class SteadyStateKalmanFilter<States extends Num, Inputs extends Num, Out
var C = plant.getC();
if (!StateSpaceUtil.isDetectable(discA, C)) {
var builder =
new StringBuilder("The system passed to the Kalman filter is unobservable!\n\nA =\n");
builder
.append(discA.getStorage().toString())
.append("\nC =\n")
.append(C.getStorage().toString())
.append('\n');
var msg = builder.toString();
var msg =
"The system passed to the Kalman filter is unobservable!\n\nA =\n"
+ discA.getStorage().toString()
+ "\nC =\n"
+ C.getStorage().toString()
+ '\n';
MathSharedStore.reportError(msg, Thread.currentThread().getStackTrace());
throw new IllegalArgumentException(msg);
}

View File

@@ -31,12 +31,13 @@ import org.ejml.simple.SimpleMatrix;
* <p>An unscented Kalman filter uses nonlinear state and measurement models. It propagates the
* error covariance using sigma points chosen to approximate the true probability distribution.
*
* <p>For more on the underlying math, read
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9 "Stochastic control
* theory".
* <p>For more on the underlying math, read <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">https://file.tavsys.net/control/controls-engineering-in-frc.pdf</a>
* chapter 9 "Stochastic control theory".
*
* <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.
* information about the SR-UKF, see <a
* href="https://www.researchgate.net/publication/3908304">https://www.researchgate.net/publication/3908304</a>.
*/
public class UnscentedKalmanFilter<States extends Num, Inputs extends Num, Outputs extends Num>
implements KalmanTypeFilter<States, Inputs, Outputs> {
@@ -64,8 +65,8 @@ public class UnscentedKalmanFilter<States extends Num, Inputs extends Num, Outpu
/**
* Constructs an Unscented Kalman Filter.
*
* <p>See
* https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices
* <p>See <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices">https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices</a>
* for how to select the standard deviations.
*
* @param states A Nat representing the number of states.
@@ -104,8 +105,8 @@ public class UnscentedKalmanFilter<States extends Num, Inputs extends Num, Outpu
* custom functions for arithmetic can be useful if you have angles in the state or measurements,
* because they allow you to correctly account for the modular nature of angle arithmetic.
*
* <p>See
* https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices
* <p>See <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices">https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices</a>
* for how to select the standard deviations.
*
* @param states A Nat representing the number of states.
@@ -206,7 +207,7 @@ public class UnscentedKalmanFilter<States extends Num, Inputs extends Num, Outpu
var qrStorage = Sbar.transpose().getStorage();
if (!qr.decompose(qrStorage.getDDRM())) {
throw new RuntimeException("QR decomposition failed! Input matrix:\n" + qrStorage.toString());
throw new RuntimeException("QR decomposition failed! Input matrix:\n" + qrStorage);
}
Matrix<C, C> newS = new Matrix<>(new SimpleMatrix(qr.getR(null, true)));

View File

@@ -35,9 +35,13 @@ import org.ejml.simple.SimpleMatrix;
* PID controller out of this class!
*
* <p>For more on filters, we highly recommend the following articles:<br>
* https://en.wikipedia.org/wiki/Linear_filter<br>
* https://en.wikipedia.org/wiki/Iir_filter<br>
* https://en.wikipedia.org/wiki/Fir_filter<br>
* <a
* href="https://en.wikipedia.org/wiki/Linear_filter">https://en.wikipedia.org/wiki/Linear_filter</a>
* <br>
* <a href="https://en.wikipedia.org/wiki/Iir_filter">https://en.wikipedia.org/wiki/Iir_filter</a>
* <br>
* <a href="https://en.wikipedia.org/wiki/Fir_filter">https://en.wikipedia.org/wiki/Fir_filter</a>
* <br>
*
* <p>Note 1: calculate() should be called by the user on a known, regular period. You can use a
* Notifier for this or do it "inline" with code in a periodic function.

View File

@@ -117,19 +117,15 @@ public class Rotation3d implements Interpolatable<Rotation3d> {
// Require that the rotation matrix is special orthogonal. This is true if
// the matrix is orthogonal (RRᵀ = I) and normalized (determinant is 1).
if (R.times(R.transpose()).minus(Matrix.eye(Nat.N3())).normF() > 1e-9) {
var builder = new StringBuilder("Rotation matrix isn't orthogonal\n\nR =\n");
builder.append(R.getStorage().toString()).append('\n');
var msg = builder.toString();
var msg = "Rotation matrix isn't orthogonal\n\nR =\n" + R.getStorage().toString() + '\n';
MathSharedStore.reportError(msg, Thread.currentThread().getStackTrace());
throw new IllegalArgumentException(msg);
}
if (Math.abs(R.det() - 1.0) > 1e-9) {
var builder =
new StringBuilder("Rotation matrix is orthogonal but not special orthogonal\n\nR =\n");
builder.append(R.getStorage().toString()).append('\n');
var msg = builder.toString();
var msg =
"Rotation matrix is orthogonal but not special orthogonal\n\nR =\n"
+ R.getStorage().toString()
+ '\n';
MathSharedStore.reportError(msg, Thread.currentThread().getStackTrace());
throw new IllegalArgumentException(msg);
}
@@ -191,7 +187,6 @@ public class Rotation3d implements Interpolatable<Rotation3d> {
// If the dot product is 1, the two vectors point in the same direction so
// there's no rotation. The default initialization of m_q will work.
m_q = new Quaternion();
return;
} else if (dotNorm < -1.0 + 1E-9) {
// If the dot product is -1, the two vectors point in opposite directions
// so a 180 degree rotation is required. Any orthogonal vector can be used

View File

@@ -87,7 +87,7 @@ public class TravelingSalesman {
* array.
*/
private <Poses extends Num> Vector<Poses> neighbor(Vector<Poses> state) {
var proposedState = new Vector<Poses>(state);
var proposedState = new Vector<>(state);
int rangeStart = (int) (Math.random() * (state.getNumRows() - 1));
int rangeEnd = (int) (Math.random() * (state.getNumRows() - 1));

View File

@@ -25,8 +25,8 @@ import org.ejml.simple.SimpleMatrix;
* of the controller (U is an output because that's what goes to the motors and Y is an input
* because that's what comes back from the sensors).
*
* <p>For more on the underlying math, read
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
* <p>For more on the underlying math, read <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">https://file.tavsys.net/control/controls-engineering-in-frc.pdf</a>.
*/
public class LinearSystemLoop<States extends Num, Inputs extends Num, Outputs extends Num> {
private final LinearQuadraticRegulator<States, Inputs, Outputs> m_controller;

View File

@@ -38,7 +38,7 @@ public interface TrajectoryConstraint {
/** Represents a minimum and maximum acceleration. */
class MinMax {
public double minAccelerationMetersPerSecondSq = -Double.MAX_VALUE;
public double maxAccelerationMetersPerSecondSq = +Double.MAX_VALUE;
public double maxAccelerationMetersPerSecondSq = Double.MAX_VALUE;
/**
* Constructs a MinMax.