diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index 5d432f9f5e..d06561315b 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -832,7 +832,7 @@ void NavEKF2::UpdateFilter(void) void NavEKF2::checkLaneSwitch(void) { AP::dal().log_event2(AP_DAL::Event2::checkLaneSwitch); - uint32_t now = AP::dal().millis(); + const uint32_t now = AP::dal().millis(); if (lastLaneSwitch_ms != 0 && now - lastLaneSwitch_ms < 5000) { // don't switch twice in 5 seconds return;