@@ -152,15 +152,16 @@ class WPILIB_DLLEXPORT PoseEstimator3d {
152152  void  ResetTranslation (const  Translation3d& translation) {
153153    m_odometry.ResetTranslation (translation);
154154
155-     std::optional<std::pair<units::second_t , VisionUpdate>> latestVisionUpdate =
156-         m_visionUpdates.empty () ? std::nullopt 
157-                                 : std::optional{*m_visionUpdates.crbegin ()};
155+     const  std::optional<std::pair<units::second_t , VisionUpdate>>
156+         latestVisionUpdate =
157+             m_visionUpdates.empty () ? std::nullopt 
158+                                     : std::optional{*m_visionUpdates.crbegin ()};
158159    m_odometryPoseBuffer.Clear ();
159160    m_visionUpdates.clear ();
160161
161162    if  (latestVisionUpdate) {
162163      //  apply vision compensation to the pose rotation
163-       VisionUpdate  const  visionUpdate{
164+       const  VisionUpdate  visionUpdate{
164165          Pose3d{translation, latestVisionUpdate->second .visionPose .Rotation ()},
165166          Pose3d{translation,
166167                 latestVisionUpdate->second .odometryPose .Rotation ()}};
@@ -186,15 +187,16 @@ class WPILIB_DLLEXPORT PoseEstimator3d {
186187  void  ResetRotation (const  Rotation3d& rotation) {
187188    m_odometry.ResetRotation (rotation);
188189
189-     std::optional<std::pair<units::second_t , VisionUpdate>> latestVisionUpdate =
190-         m_visionUpdates.empty () ? std::nullopt 
191-                                 : std::optional{*m_visionUpdates.crbegin ()};
190+     const  std::optional<std::pair<units::second_t , VisionUpdate>>
191+         latestVisionUpdate =
192+             m_visionUpdates.empty () ? std::nullopt 
193+                                     : std::optional{*m_visionUpdates.crbegin ()};
192194    m_odometryPoseBuffer.Clear ();
193195    m_visionUpdates.clear ();
194196
195197    if  (latestVisionUpdate) {
196198      //  apply vision compensation to the pose translation
197-       VisionUpdate  const  visionUpdate{
199+       const  VisionUpdate  visionUpdate{
198200          Pose3d{latestVisionUpdate->second .visionPose .Translation (), rotation},
199201          Pose3d{latestVisionUpdate->second .odometryPose .Translation (),
200202                 rotation}};
0 commit comments