Skip to content

Commit

Permalink
calculated latency since it is not returned by botpose
Browse files Browse the repository at this point in the history
  • Loading branch information
DarkMetalMouse committed Mar 7, 2023
1 parent b1162a3 commit 3db7354
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/subsystems/LimeLight.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@
import edu.wpi.first.networktables.NetworkTableEntry;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.LimelightConstants;

Expand Down Expand Up @@ -86,12 +86,12 @@ public BotPose getBotPose() {
double[] poseComponents = limeLightTable.getEntry(entryName).getDoubleArray(new double[6]);
if (poseComponents.length == 0)
return null;

double latency = limeLightTable.getEntry("tl").getDouble(0) + limeLightTable.getEntry("cl").getDouble(0);
return new BotPose(new Pose2d(
poseComponents[0],
poseComponents[1],
new Rotation2d(Math.toRadians(poseComponents[5]))),
Timer.getFPGATimestamp() - (poseComponents[6] / 1000.0));
Timer.getFPGATimestamp() - (latency / 1000.0));

}
}

0 comments on commit 3db7354

Please sign in to comment.