Skip to content

Commit 7753199

Browse files
authored
Fix usage of const to be on the left
1 parent e680f81 commit 7753199

File tree

2 files changed

+8
-8
lines changed

2 files changed

+8
-8
lines changed

wpimath/src/main/native/include/frc/estimator/PoseEstimator.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -143,15 +143,15 @@ class WPILIB_DLLEXPORT PoseEstimator {
143143
void ResetTranslation(const Translation2d& translation) {
144144
m_odometry.ResetTranslation(translation);
145145

146-
std::optional<std::pair<units::second_t, VisionUpdate>> latestVisionUpdate =
146+
const std::optional<std::pair<units::second_t, VisionUpdate>> latestVisionUpdate =
147147
m_visionUpdates.empty() ? std::nullopt
148148
: std::optional{*m_visionUpdates.crbegin()};
149149
m_odometryPoseBuffer.Clear();
150150
m_visionUpdates.clear();
151151

152152
if (latestVisionUpdate) {
153153
// apply vision compensation to the pose rotation
154-
VisionUpdate const visionUpdate{
154+
const VisionUpdate visionUpdate{
155155
Pose2d{translation, latestVisionUpdate->second.visionPose.Rotation()},
156156
Pose2d{translation,
157157
latestVisionUpdate->second.odometryPose.Rotation()}};
@@ -177,15 +177,15 @@ class WPILIB_DLLEXPORT PoseEstimator {
177177
void ResetRotation(const Rotation2d& rotation) {
178178
m_odometry.ResetRotation(rotation);
179179

180-
std::optional<std::pair<units::second_t, VisionUpdate>> latestVisionUpdate =
180+
const std::optional<std::pair<units::second_t, VisionUpdate>> latestVisionUpdate =
181181
m_visionUpdates.empty() ? std::nullopt
182182
: std::optional{*m_visionUpdates.crbegin()};
183183
m_odometryPoseBuffer.Clear();
184184
m_visionUpdates.clear();
185185

186186
if (latestVisionUpdate) {
187187
// apply vision compensation to the pose translation
188-
VisionUpdate const visionUpdate{
188+
const VisionUpdate visionUpdate{
189189
Pose2d{latestVisionUpdate->second.visionPose.Translation(), rotation},
190190
Pose2d{latestVisionUpdate->second.odometryPose.Translation(),
191191
rotation}};

wpimath/src/main/native/include/frc/estimator/PoseEstimator3d.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -152,15 +152,15 @@ 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 =
155+
const std::optional<std::pair<units::second_t, VisionUpdate>> latestVisionUpdate =
156156
m_visionUpdates.empty() ? std::nullopt
157157
: std::optional{*m_visionUpdates.crbegin()};
158158
m_odometryPoseBuffer.Clear();
159159
m_visionUpdates.clear();
160160

161161
if (latestVisionUpdate) {
162162
// apply vision compensation to the pose rotation
163-
VisionUpdate const visionUpdate{
163+
const VisionUpdate visionUpdate{
164164
Pose3d{translation, latestVisionUpdate->second.visionPose.Rotation()},
165165
Pose3d{translation,
166166
latestVisionUpdate->second.odometryPose.Rotation()}};
@@ -186,15 +186,15 @@ class WPILIB_DLLEXPORT PoseEstimator3d {
186186
void ResetRotation(const Rotation3d& rotation) {
187187
m_odometry.ResetRotation(rotation);
188188

189-
std::optional<std::pair<units::second_t, VisionUpdate>> latestVisionUpdate =
189+
const std::optional<std::pair<units::second_t, VisionUpdate>> latestVisionUpdate =
190190
m_visionUpdates.empty() ? std::nullopt
191191
: std::optional{*m_visionUpdates.crbegin()};
192192
m_odometryPoseBuffer.Clear();
193193
m_visionUpdates.clear();
194194

195195
if (latestVisionUpdate) {
196196
// apply vision compensation to the pose translation
197-
VisionUpdate const visionUpdate{
197+
const VisionUpdate visionUpdate{
198198
Pose3d{latestVisionUpdate->second.visionPose.Translation(), rotation},
199199
Pose3d{latestVisionUpdate->second.odometryPose.Translation(),
200200
rotation}};

0 commit comments

Comments
 (0)