Skip to content

Commit

Permalink
Address review comments
Browse files Browse the repository at this point in the history
  • Loading branch information
calcmogul committed Dec 2, 2023
1 parent d672a24 commit 5f05124
Show file tree
Hide file tree
Showing 33 changed files with 109 additions and 100 deletions.
4 changes: 2 additions & 2 deletions cscore/src/main/java/edu/wpi/first/cscore/HttpCamera.java
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ public static HttpCameraKind getHttpCameraKindFromInt(int kind) {
* Create a source for a MJPEG-over-HTTP (IP) camera.
*
* @param name Source name (arbitrary unique identifier)
* @param url Camera URL (e.g. "<a href="http://10.x.y.11/video/stream.mjpg">...</a>")
* @param url Camera URL (e.g. "http://10.x.y.11/video/stream.mjpg")
*/
public HttpCamera(String name, String url) {
super(CameraServerJNI.createHttpCamera(name, url, HttpCameraKind.kUnknown.getValue()));
Expand All @@ -56,7 +56,7 @@ public HttpCamera(String name, String url) {
* Create a source for a MJPEG-over-HTTP (IP) camera.
*
* @param name Source name (arbitrary unique identifier)
* @param url Camera URL (e.g. "<a href="http://10.x.y.11/video/stream.mjpg">...</a>")
* @param url Camera URL (e.g. "http://10.x.y.11/video/stream.mjpg")
* @param kind Camera kind (e.g. kAxis)
*/
public HttpCamera(String name, String url, HttpCameraKind kind) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@

import static org.junit.jupiter.api.Assertions.assertEquals;

import java.util.Arrays;
import java.util.Collections;
import java.util.List;
import java.util.stream.Stream;
Expand Down Expand Up @@ -61,8 +60,8 @@ private static Stream<Arguments> getHierarchyArguments() {
return Stream.of(
Arguments.of(Collections.singletonList("/"), ""),
Arguments.of(Collections.singletonList("/"), "/"),
Arguments.of(Arrays.asList("/", "/foo", "/foo/bar", "/foo/bar/baz"), "/foo/bar/baz"),
Arguments.of(Arrays.asList("/", "/foo", "/foo/bar", "/foo/bar/"), "/foo/bar/"));
Arguments.of(List.of("/", "/foo", "/foo/bar", "/foo/bar/baz"), "/foo/bar/baz"),
Arguments.of(List.of("/", "/foo", "/foo/bar", "/foo/bar/"), "/foo/bar/"));
}

@ParameterizedTest
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,26 +92,22 @@ Pose2d DifferentialDrivetrainSim::GetPose() const {
}

units::ampere_t DifferentialDrivetrainSim::GetLeftCurrentDraw() const {
auto loadIleft =
m_motor.Current(
units::radians_per_second_t{m_x(State::kLeftVelocity) *
m_currentGearing / m_wheelRadius.value()},
units::volt_t{m_u(0)}) *
wpi::sgn(m_u(0));

return loadIleft;
return m_motor.Current(units::radians_per_second_t{m_x(State::kLeftVelocity) *
m_currentGearing /
m_wheelRadius.value()},
units::volt_t{m_u(0)}) *
wpi::sgn(m_u(0));
}

units::ampere_t DifferentialDrivetrainSim::GetRightCurrentDraw() const {
auto loadIRight =
m_motor.Current(
units::radians_per_second_t{m_x(State::kRightVelocity) *
m_currentGearing / m_wheelRadius.value()},
units::volt_t{m_u(1)}) *
wpi::sgn(m_u(1));

return loadIRight;
return m_motor.Current(
units::radians_per_second_t{m_x(State::kRightVelocity) *
m_currentGearing /
m_wheelRadius.value()},
units::volt_t{m_u(1)}) *
wpi::sgn(m_u(1));
}

units::ampere_t DifferentialDrivetrainSim::GetCurrentDraw() const {
return GetLeftCurrentDraw() + GetRightCurrentDraw();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,8 @@
* 884 controllers also but if users experience issues such as asymmetric behavior around the
* deadband or inability to saturate the controller in either direction, calibration is recommended.
* The calibration procedure can be found in the Victor 884 User Manual available from VEX Robotics:
* <a href="http://content.vexrobotics.com/docs/ifi-v884-users-manual-9-25-06.pdf">...</a>
* <a
* href="http://content.vexrobotics.com/docs/ifi-v884-users-manual-9-25-06.pdf">http://content.vexrobotics.com/docs/ifi-v884-users-manual-9-25-06.pdf</a>
*
* <ul>
* <li>2.027ms = full "forward"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ synchronized void updateEntry(boolean setDefault) {
int ndx = 0;
for (Pose2d pose : m_poses) {
Translation2d translation = pose.getTranslation();
arr[ndx] = translation.getX();
arr[ndx + 0] = translation.getX();
arr[ndx + 1] = translation.getY();
arr[ndx + 2] = pose.getRotation().getDegrees();
ndx += 3;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,8 @@ private double getPressure() {
* @return command
*/
public Command disableCompressorCommand() {
// Disable closed-loop mode on the compressor.
return startEnd(
// Disable closed-loop mode on the compressor.
m_compressor::disable,
// Enable closed-loop mode based on the digital pressure switch connected to the
// PCM/PH.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
import static org.junit.Assert.assertEquals;

import edu.wpi.first.wpilibj.test.AbstractComsSetup;
import java.util.Arrays;
import java.util.Collection;
import java.util.List;
import java.util.logging.Logger;
import org.junit.BeforeClass;
import org.junit.Test;
Expand Down Expand Up @@ -38,7 +38,7 @@ public static void waitASecond() {
/** Test with all valid ranges to make sure unpacking is always done correctly. */
@Parameters
public static Collection<BuiltInAccelerometer.Range[]> generateData() {
return Arrays.asList(
return List.of(
new BuiltInAccelerometer.Range[][] {
{BuiltInAccelerometer.Range.k2G},
{BuiltInAccelerometer.Range.k4G},
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
import edu.wpi.first.wpilibj.test.AbstractComsSetup;
import edu.wpi.first.wpilibj.test.TestBench;
import java.util.Arrays;
import java.util.Collection;
import java.util.List;
import java.util.logging.Logger;
import org.junit.After;
import org.junit.AfterClass;
Expand Down Expand Up @@ -56,7 +56,7 @@ public MotorEncoderTest(MotorEncoderFixture<?> mef) {
@Parameters(name = "{index}: {0}")
public static Collection<MotorEncoderFixture<?>[]> generateData() {
// logger.fine("Loading the MotorList");
return Arrays.asList(
return List.of(
new MotorEncoderFixture<?>[][] {
{TestBench.getTalonPair()}, {TestBench.getVictorPair()}, {TestBench.getJaguarPair()}
});
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@
import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
import edu.wpi.first.wpilibj.test.AbstractComsSetup;
import edu.wpi.first.wpilibj.test.TestBench;
import java.util.Arrays;
import java.util.Collection;
import java.util.List;
import java.util.logging.Logger;
import org.junit.AfterClass;
import org.junit.Before;
Expand Down Expand Up @@ -44,7 +44,7 @@ public MotorInvertingTest(MotorEncoderFixture<?> afixture) {
@Parameters(name = "{index}: {0}")
public static Collection<MotorEncoderFixture<?>[]> generateData() {
// logger.fine("Loading the MotorList");
return Arrays.asList(
return List.of(
new MotorEncoderFixture<?>[][] {
{TestBench.getTalonPair()}, {TestBench.getVictorPair()}, {TestBench.getJaguarPair()}
});
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,8 @@
import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
import edu.wpi.first.wpilibj.test.AbstractComsSetup;
import edu.wpi.first.wpilibj.test.TestBench;
import java.util.Arrays;
import java.util.Collection;
import java.util.List;
import java.util.logging.Logger;
import org.junit.After;
import org.junit.AfterClass;
Expand Down Expand Up @@ -65,7 +65,7 @@ public PDPTest(MotorEncoderFixture<?> mef, Double expectedCurrentDraw) {
@Parameters(name = "{index}: {0}, Expected Stopped Current Draw: {1}")
public static Collection<Object[]> generateData() {
// logger.fine("Loading the MotorList");
return Arrays.asList(new Object[][] {{TestBench.getTalonPair(), 0.0}});
return List.of(new Object[][] {{TestBench.getTalonPair(), 0.0}});
}

@After
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
import edu.wpi.first.wpilibj.test.AbstractComsSetup;
import edu.wpi.first.wpilibj.test.TestBench;
import java.util.ArrayList;
import java.util.Arrays;
import java.util.Collection;
import java.util.List;
import java.util.logging.Logger;
import org.junit.After;
import org.junit.AfterClass;
Expand Down Expand Up @@ -78,7 +78,7 @@ public static Collection<Object[]> generateData() {
double kd = 0.0;
for (int i = 0; i < 1; i++) {
data.addAll(
Arrays.asList(
List.of(
new Object[][] {
{kp, ki, kd, TestBench.getTalonPair()},
{kp, ki, kd, TestBench.getVictorPair()},
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
import edu.wpi.first.wpilibj.motorcontrol.Victor;
import java.io.PrintStream;
import java.util.ArrayList;
import java.util.Arrays;
import java.util.Collection;
import java.util.List;

Expand Down Expand Up @@ -192,15 +191,15 @@ public static DIOCrossConnectFixture getDIOCrossConnectFixture(int inputPort, in
private static List<List<Integer[]>> getDIOCrossConnect() {
List<List<Integer[]>> pairs = new ArrayList<List<Integer[]>>();
List<Integer[]> setA =
Arrays.asList(
List.of(
new Integer[][] {
{DIOCrossConnectA1, DIOCrossConnectA2},
{DIOCrossConnectA2, DIOCrossConnectA1}
});
pairs.add(setA);

List<Integer[]> setB =
Arrays.asList(
List.of(
new Integer[][] {
{DIOCrossConnectB1, DIOCrossConnectB2},
{DIOCrossConnectB2, DIOCrossConnectB1}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
import java.io.IOException;
import java.io.InputStream;
import java.util.ArrayList;
import java.util.Arrays;
import java.util.List;
import java.util.Objects;
import java.util.logging.LogManager;
Expand Down Expand Up @@ -193,7 +192,7 @@ protected static Result parseArgsRunAndGetResult(final String[] args) {
}
}

ArrayList<String> argsParsed = new ArrayList<String>(Arrays.asList(args));
ArrayList<String> argsParsed = new ArrayList<String>(List.of(args));
if (argsParsed.contains(HELP_FLAG)) {
// If the user inputs the help flag then return the help message and exit
// without running any tests
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
* when the feedforward is created and remains constant.
*
* <p>For more on the underlying math, read <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">...</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. */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
* 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 <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">...</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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ private enum State {
* Constructs a linear time-varying differential drive controller.
*
* <p>See <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning">...</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.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ public LTVUnicycleController(double dt, double maxVelocity) {
* Constructs a linear time-varying unicycle controller.
*
* <p>See <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning">...</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.
Expand All @@ -96,7 +96,7 @@ public LTVUnicycleController(Vector<N3> qelems, Vector<N2> relems, double dt) {
* Constructs a linear time-varying unicycle controller.
*
* <p>See <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning">...</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.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
* where <strong> B<sup>+</sup> </strong> is the pseudoinverse of B.
*
* <p>For more on the underlying math, read <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">...</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> {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
* the control law u = K(r - x).
*
* <p>For more on the underlying math, read <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">...</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. */
Expand All @@ -36,7 +36,7 @@ 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 <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning">...</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.
Expand All @@ -62,7 +62,7 @@ public LinearQuadraticRegulator(
* Constructs a controller with the given coefficients and plant.
*
* <p>See <a
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning">...</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.
Expand Down Expand Up @@ -258,7 +258,8 @@ public Matrix<Inputs, N1> calculate(Matrix<States, N1> x, Matrix<States, N1> nex
* 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 <a href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">...</a>
* <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.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,8 @@
* Kalman filter equations.
*
* <p>For more on the underlying math, read <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">...</a> chapter 9
* "Stochastic control theory".
* 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> {
Expand Down Expand Up @@ -60,7 +60,7 @@ public class ExtendedKalmanFilter<States extends Num, Inputs extends Num, Output
* Constructs an extended Kalman filter.
*
* <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">...</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.
Expand Down Expand Up @@ -98,7 +98,7 @@ public ExtendedKalmanFilter(
* Constructs an extended Kalman filter.
*
* <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">...</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.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@
* model.
*
* <p>For more on the underlying math, read <a
* href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">...</a> chapter 9
* "Stochastic control theory".
* 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> {
Expand All @@ -46,7 +46,7 @@ public class KalmanFilter<States extends Num, Inputs extends Num, Outputs extend
* Constructs a Kalman filter with the given plant.
*
* <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">...</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.
Expand Down
Loading

0 comments on commit 5f05124

Please sign in to comment.