Remove extra newlines after open curly braces (NFC) (#3471)

This commit is contained in:
Tyler Veness
2021-07-09 00:41:30 -04:00
committed by GitHub
parent a4233e1a16
commit 9d68d95825
47 changed files with 0 additions and 67 deletions

View File

@@ -15,7 +15,6 @@ import org.ejml.simple.SimpleMatrix;
* @param <R> The number of rows in this matrix.
*/
public class Vector<R extends Num> extends Matrix<R, N1> {
/**
* Constructs an empty zero vector of the given dimensions.
*

View File

@@ -23,7 +23,6 @@ import org.ejml.simple.SimpleMatrix;
* State-Space Models" (Doctoral dissertation)
*/
public class MerweScaledSigmaPoints<S extends Num> {
private final double m_alpha;
private final int m_kappa;
private final Nat<S> m_states;

View File

@@ -29,7 +29,6 @@ import org.ejml.simple.SimpleMatrix;
@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;
private final Nat<Outputs> m_outputs;

View File

@@ -9,7 +9,6 @@ import edu.wpi.first.math.geometry.Rotation2d;
/** 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

@@ -81,7 +81,6 @@ public final class SplineHelper {
@SuppressWarnings("LocalVariableName")
public static CubicHermiteSpline[] getCubicSplinesFromControlVectors(
Spline.ControlVector start, Translation2d[] waypoints, Spline.ControlVector end) {
CubicHermiteSpline[] splines = new CubicHermiteSpline[waypoints.length + 1];
double[] xInitial = start.x;

View File

@@ -11,7 +11,6 @@ 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;
@@ -42,7 +41,6 @@ public class LinearSystem<States extends Num, Inputs extends Num, Outputs extend
Matrix<States, Inputs> b,
Matrix<Outputs, States> c,
Matrix<Outputs, Inputs> d) {
this.m_A = a;
this.m_B = b;
this.m_C = c;

View File

@@ -30,7 +30,6 @@ import org.ejml.simple.SimpleMatrix;
*/
@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;
private final KalmanFilter<States, Inputs, Outputs> m_observer;

View File

@@ -75,7 +75,6 @@ public final class NumericalIntegration {
Matrix<States, N1> x,
Matrix<Inputs, N1> u,
double dtSeconds) {
final var halfDt = 0.5 * dtSeconds;
Matrix<States, N1> k1 = f.apply(x, u);
Matrix<States, N1> k2 = f.apply(x.plus(k1.times(halfDt)), u);
@@ -96,7 +95,6 @@ public final class NumericalIntegration {
@SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
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 halfDt = 0.5 * dtSeconds;
Matrix<States, N1> k1 = f.apply(x);
Matrix<States, N1> k2 = f.apply(x.plus(k1.times(halfDt)));
@@ -147,7 +145,6 @@ public final class NumericalIntegration {
Matrix<Inputs, N1> u,
double dtSeconds,
double maxError) {
double dtElapsed = 0;
double previousH = dtSeconds;
// Loop until we've gotten to our desired dt
@@ -224,7 +221,6 @@ public final class NumericalIntegration {
double initialH,
double maxTruncationError,
double dtRemaining) {
double truncationErr;
double h = initialH;
Matrix<States, N1> newX;

View File

@@ -195,7 +195,6 @@ public final class LinearSystemId {
@SuppressWarnings("ParameterName")
public static LinearSystem<N2, N2, N2> identifyDrivetrainSystem(
double kVLinear, double kALinear, double kVAngular, double kAAngular) {
final double A1 = 0.5 * -(kVLinear / kALinear + kVAngular / kAAngular);
final double A2 = 0.5 * -(kVLinear / kALinear - kVAngular / kAAngular);
final double B1 = 0.5 * (1.0 / kALinear + 1.0 / kAAngular);

View File

@@ -260,7 +260,6 @@ public final class TrajectoryParameterizer {
private static void enforceAccelerationLimits(
boolean reverse, List<TrajectoryConstraint> constraints, ConstrainedState state) {
for (final var constraint : constraints) {
double factor = reverse ? -1.0 : 1.0;
final var minMaxAccel =

View File

@@ -51,7 +51,6 @@ public class DifferentialDriveVoltageConstraint implements TrajectoryConstraint
@Override
public MinMax getMinMaxAccelerationMetersPerSecondSq(
Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond) {
var wheelSpeeds =
m_kinematics.toWheelSpeeds(
new ChassisSpeeds(

View File

@@ -11,7 +11,6 @@ import edu.wpi.first.math.geometry.Pose2d;
* trajectories.
*/
public interface TrajectoryConstraint {
/**
* Returns the max velocity given the current pose and curvature.
*