mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[wpimath] Fix pose estimator ResetRotation() in C++ (#6984)
This commit is contained in:
@@ -71,7 +71,7 @@ void PoseEstimator<WheelSpeeds, WheelPositions>::ResetTranslation(
|
||||
template <typename WheelSpeeds, typename WheelPositions>
|
||||
void PoseEstimator<WheelSpeeds, WheelPositions>::ResetRotation(
|
||||
const Rotation2d& rotation) {
|
||||
m_odometry.ResetTranslation(rotation);
|
||||
m_odometry.ResetRotation(rotation);
|
||||
m_odometryPoseBuffer.Clear();
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user