Skip to content

Commit 8f57b2a

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

File tree

2 files changed

+20
-16
lines changed

2 files changed

+20
-16
lines changed

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

Lines changed: 10 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -143,15 +143,16 @@ 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 =
147-
m_visionUpdates.empty() ? std::nullopt
148-
: std::optional{*m_visionUpdates.crbegin()};
146+
const std::optional<std::pair<units::second_t, VisionUpdate>>
147+
latestVisionUpdate =
148+
m_visionUpdates.empty() ? std::nullopt
149+
: std::optional{*m_visionUpdates.crbegin()};
149150
m_odometryPoseBuffer.Clear();
150151
m_visionUpdates.clear();
151152

152153
if (latestVisionUpdate) {
153154
// apply vision compensation to the pose rotation
154-
VisionUpdate const visionUpdate{
155+
const VisionUpdate visionUpdate{
155156
Pose2d{translation, latestVisionUpdate->second.visionPose.Rotation()},
156157
Pose2d{translation,
157158
latestVisionUpdate->second.odometryPose.Rotation()}};
@@ -177,15 +178,16 @@ class WPILIB_DLLEXPORT PoseEstimator {
177178
void ResetRotation(const Rotation2d& rotation) {
178179
m_odometry.ResetRotation(rotation);
179180

180-
std::optional<std::pair<units::second_t, VisionUpdate>> latestVisionUpdate =
181-
m_visionUpdates.empty() ? std::nullopt
182-
: std::optional{*m_visionUpdates.crbegin()};
181+
const std::optional<std::pair<units::second_t, VisionUpdate>>
182+
latestVisionUpdate =
183+
m_visionUpdates.empty() ? std::nullopt
184+
: std::optional{*m_visionUpdates.crbegin()};
183185
m_odometryPoseBuffer.Clear();
184186
m_visionUpdates.clear();
185187

186188
if (latestVisionUpdate) {
187189
// apply vision compensation to the pose translation
188-
VisionUpdate const visionUpdate{
190+
const VisionUpdate visionUpdate{
189191
Pose2d{latestVisionUpdate->second.visionPose.Translation(), rotation},
190192
Pose2d{latestVisionUpdate->second.odometryPose.Translation(),
191193
rotation}};

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

Lines changed: 10 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -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

Comments
 (0)