Skip to content
This repository has been archived by the owner on Feb 18, 2024. It is now read-only.

Commit

Permalink
Review fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
srimanachanta committed Dec 7, 2023
1 parent aea93a7 commit 5b92f42
Show file tree
Hide file tree
Showing 8 changed files with 18 additions and 24 deletions.
12 changes: 4 additions & 8 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ public RobotContainer() {
}
}

// Confiure PathPlanner
// Configure PathPlanner
AutoBuilder.configureHolonomic(
() -> PoseEstimator.getInstance().getPose(),
(pose) -> PoseEstimator.getInstance().resetPose(pose),
Expand All @@ -86,14 +86,10 @@ public RobotContainer() {
m_drive);
Pathfinding.setPathfinder(new LocalADStarAK());
PathPlannerLogging.setLogActivePathCallback(
(activePath) -> {
Logger.recordOutput(
"Odometry/Trajectory", activePath.toArray(new Pose2d[activePath.size()]));
});
(activePath) ->
Logger.recordOutput("Odometry/Trajectory", activePath.toArray(new Pose2d[0])));
PathPlannerLogging.setLogTargetPoseCallback(
(targetPose) -> {
Logger.recordOutput("Odometry/TrajectorySetpoint", targetPose);
});
(targetPose) -> Logger.recordOutput("Odometry/TrajectorySetpoint", targetPose));

autoChooser = new LoggedDashboardChooser<>("Auto Choices", AutoBuilder.buildAutoChooser());

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ public void add(double velocity, double voltage) {
}

public void print() {
if (velocityData.size() == 0 || voltageData.size() == 0) {
if (velocityData.isEmpty() || voltageData.isEmpty()) {
return;
}

Expand All @@ -91,10 +91,10 @@ public void print() {
1);

System.out.println("FF Characterization Results:");
System.out.println("\tCount=" + Integer.toString(velocityData.size()) + "");
System.out.println(String.format("\tR2=%.5f", regression.R2()));
System.out.println(String.format("\tkS=%.5f", regression.beta(0)));
System.out.println(String.format("\tkV=%.5f", regression.beta(1)));
System.out.println("\tCount=" + velocityData.size());
System.out.printf("\tR2=%.5f%n", regression.R2());
System.out.printf("\tkS=%.5f%n", regression.beta(0));
System.out.printf("\tkV=%.5f%n", regression.beta(1));
}
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/constants/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
public final class Constants {
private static RobotType kRobotType = RobotType.ROBOT_SIMBOT;

public static double kLoopPeriodSecs = 0.02;
public static final double kLoopPeriodSecs = 0.02;

public enum RobotMode {
REAL,
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/drive/DriveBase.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
import org.littletonrobotics.junction.Logger;

public class DriveBase extends SubsystemBase {
public static double ODOMETRY_FREQUENCY = 250.0;
public static final double ODOMETRY_FREQUENCY = 250.0;

private final GyroIO m_gyroIO;
private final GyroIOInputsAutoLogged m_gyroInputs = new GyroIOInputsAutoLogged();
Expand Down
4 changes: 1 addition & 3 deletions src/main/java/frc/robot/subsystems/drive/GyroIOPigeon2.java
Original file line number Diff line number Diff line change
Expand Up @@ -75,9 +75,7 @@ public void updateInputs(GyroIOInputs inputs) {
inputs.accelZ = m_accelZ.getValueAsDouble();

inputs.odometryYawPositions =
yawPositionQueue.stream()
.map((Double value) -> Rotation2d.fromDegrees(value))
.toArray(Rotation2d[]::new);
yawPositionQueue.stream().map(Rotation2d::fromDegrees).toArray(Rotation2d[]::new);
this.yawPositionQueue.clear();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ public void updateInputs(ModuleIOInputs inputs) {
inputs.driveAppliedVolts = m_driveMotor.getAppliedOutput() * m_driveMotor.getBusVoltage();
inputs.driveCurrentAmps = new double[] {m_driveMotor.getOutputCurrent()};

// Refresh the Encoder data becasue it is cached. This is non-blocking.
// Refresh the Encoder data because it is cached. This is non-blocking.
m_turnAbsoluteEncoder.refresh();
inputs.turnAbsolutePosition =
Rotation2d.fromRotations(m_turnAbsoluteEncoder.getValueAsDouble());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
* blocking thread. A Notifier thread is used to gather samples with consistent timing.
*/
public class SparkMaxOdometryThread {
private List<DoubleSupplier> signals = new ArrayList<>();
private List<Queue<Double>> queues = new ArrayList<>();
private final List<DoubleSupplier> signals = new ArrayList<>();
private final List<Queue<Double>> queues = new ArrayList<>();

private final Notifier notifier;
private static SparkMaxOdometryThread instance = null;
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/util/PolynomialRegression.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
// http://algs4.cs.princeton.edu/14analysis/PolynomialRegression.java.html

/**
* The {@code PolynomialRegression} class performs a polynomial regression on an set of <em>N</em>
* The {@code PolynomialRegression} class performs a polynomial regression on a set of <em>N</em>
* data points (<em>y<sub>i</sub></em>, <em>x<sub>i</sub></em>). That is, it fits a polynomial
* <em>y</em> = &beta;<sub>0</sub> + &beta;<sub>1</sub> <em>x</em> + &beta;<sub>2</sub>
* <em>x</em><sup>2</sup> + ... + &beta;<sub><em>d</em></sub> <em>x</em><sup><em>d</em></sup> (where
Expand Down Expand Up @@ -154,20 +154,20 @@ public double predict(double x) {
* polynomial and the coefficient of determination <em>R</em><sup>2</sup>
*/
public String toString() {
StringBuilder s = new StringBuilder();
int j = degree;

// ignoring leading zero coefficients
while (j >= 0 && Math.abs(beta(j)) < 1E-5) j--;

StringBuilder s = new StringBuilder();
// create remaining terms
while (j >= 0) {
if (j == 0) s.append(String.format("%.10f ", beta(j)));
else if (j == 1) s.append(String.format("%.10f %s + ", beta(j), variableName));
else s.append(String.format("%.10f %s^%d + ", beta(j), variableName, j));
j--;
}
s = s.append(" (R^2 = " + String.format("%.3f", R2()) + ")");
s.append(" (R^2 = ").append(String.format("%.3f", R2())).append(")");

// replace "+ -2n" with "- 2n"
return s.toString().replace("+ -", "- ");
Expand Down

0 comments on commit 5b92f42

Please sign in to comment.