Skip to content

Commit

Permalink
fix limelight fps input
Browse files Browse the repository at this point in the history
  • Loading branch information
mpatankar6 committed Apr 12, 2024
1 parent cd530d8 commit 7e828e6
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/vision/GamePieceDetection.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
import org.littletonrobotics.junction.Logger;

public class GamePieceDetection {
private final double kMinimumTargetAreaPercent = 1.7;
private final double kMinimumTargetAreaPercent = 0.8;
private final GamePieceDetectionIO m_io;
private final GamePieceDetectionIOInputsAutoLogged m_inputs =
new GamePieceDetectionIOInputsAutoLogged();
Expand All @@ -20,7 +20,7 @@ public class GamePieceDetection {
public final DoubleSupplier horizontalErrorDeg =
() ->
m_inputs.targetHorizontalOffsetDegrees
* (Constants.onRedAllianceSupplier.getAsBoolean() ? -1 : 1);
* (Constants.onRedAllianceSupplier.getAsBoolean() ? 1 : -1);

public GamePieceDetection(GamePieceDetectionIO io) {
m_io = io;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ public void updateInputs(GamePieceDetectionIOInputs inputs) {
inputs.targetArea = m_limelightTable.getEntry("ta").getDouble(0.0);
inputs.targetHorizontalOffsetDegrees = m_limelightTable.getEntry("tx").getDouble(0.0);
inputs.targetVerticalOffsetDegrees = m_limelightTable.getEntry("ty").getDouble(0.0);
inputs.fps = (int) m_limelightTable.getEntry("hw").getDoubleArray(new double[] {0.0})[0];
inputs.fps = (int) m_limelightTable.getEntry("hw").getDoubleArray(new double[] {0.0})[3];

double currentHeartbeatValue = m_limelightTable.getEntry("hb").getDouble(0.0);
if (m_lastHeartbeatValue != currentHeartbeatValue) {
Expand Down

0 comments on commit 7e828e6

Please sign in to comment.