From eef516fcc90e67f22d6522ebd547bbee608ca0fb Mon Sep 17 00:00:00 2001 From: Jade Date: Wed, 21 Aug 2024 22:51:21 +0800 Subject: [PATCH] [wpimath] Fix pose estimator ResetRotation() in C++ (#6984) --- wpimath/src/main/native/include/frc/estimator/PoseEstimator.inc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.inc b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.inc index fb583226e4..51bb834306 100644 --- a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.inc +++ b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.inc @@ -71,7 +71,7 @@ void PoseEstimator::ResetTranslation( template void PoseEstimator::ResetRotation( const Rotation2d& rotation) { - m_odometry.ResetTranslation(rotation); + m_odometry.ResetRotation(rotation); m_odometryPoseBuffer.Clear(); }