[wpilib] Add timestamp getters with configurable time base (#7378)

This commit is contained in:
Jonah Bonner
2024-11-16 10:43:38 -05:00
committed by GitHub
parent 91142ba5fe
commit ca51197486
27 changed files with 180 additions and 53 deletions

View File

@@ -245,7 +245,7 @@ public class Drivetrain {
// Apply vision measurements. For simulation purposes only, we don't input a latency delay -- on
// a real robot, this must be calculated based either on known latency or timestamps.
m_poseEstimator.addVisionMeasurement(visionMeasurement2d, Timer.getFPGATimestamp());
m_poseEstimator.addVisionMeasurement(visionMeasurement2d, Timer.getTimestamp());
}
/** This function is called periodically during simulation. */

View File

@@ -167,6 +167,6 @@ public class Drivetrain {
m_poseEstimator.addVisionMeasurement(
ExampleGlobalMeasurementSensor.getEstimatedGlobalPose(
m_poseEstimator.getEstimatedPosition()),
Timer.getFPGATimestamp() - 0.3);
Timer.getTimestamp() - 0.3);
}
}

View File

@@ -99,6 +99,6 @@ public class Drivetrain {
m_poseEstimator.addVisionMeasurement(
ExampleGlobalMeasurementSensor.getEstimatedGlobalPose(
m_poseEstimator.getEstimatedPosition()),
Timer.getFPGATimestamp() - 0.3);
Timer.getTimestamp() - 0.3);
}
}