diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index 6fa6ae3f9a..abbc7d2288 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -910,7 +910,7 @@ void NavEKF3::UpdateFilter(void) */ void NavEKF3::checkLaneSwitch(void) { - AP::dal().log_event3(AP_DAL::Event3::checkLaneSwitch); + AP::dal().log_event3(AP_DAL::Event::checkLaneSwitch); uint32_t now = AP::dal().millis(); if (lastLaneSwitch_ms != 0 && now - lastLaneSwitch_ms < 5000) { @@ -947,7 +947,7 @@ void NavEKF3::checkLaneSwitch(void) void NavEKF3::requestYawReset(void) { - AP::dal().log_event3(AP_DAL::Event3::requestYawReset); + AP::dal().log_event3(AP_DAL::Event::requestYawReset); for (uint8_t i = 0; i < num_cores; i++) { core[i].EKFGSF_requestYawReset(); @@ -1125,7 +1125,7 @@ void NavEKF3::getTiltError(int8_t instance, float &ang) const // reset body axis gyro bias estimates void NavEKF3::resetGyroBias(void) { - AP::dal().log_event3(AP_DAL::Event3::resetGyroBias); + AP::dal().log_event3(AP_DAL::Event::resetGyroBias); if (core) { for (uint8_t i=0; i