AP_NavEKF2: use common structure names

This commit is contained in:
Andrew Tridgell 2020-11-16 14:34:01 +11:00 committed by Peter Barker
parent 636fe783f4
commit 3a4095fc7f

View File

@ -831,7 +831,7 @@ void NavEKF2::UpdateFilter(void)
*/ */
void NavEKF2::checkLaneSwitch(void) void NavEKF2::checkLaneSwitch(void)
{ {
AP::dal().log_event2(AP_DAL::Event2::checkLaneSwitch); AP::dal().log_event2(AP_DAL::Event::checkLaneSwitch);
const uint32_t now = AP::dal().millis(); const uint32_t now = AP::dal().millis();
if (lastLaneSwitch_ms != 0 && now - lastLaneSwitch_ms < 5000) { if (lastLaneSwitch_ms != 0 && now - lastLaneSwitch_ms < 5000) {
// don't switch twice in 5 seconds // don't switch twice in 5 seconds
@ -992,7 +992,7 @@ void NavEKF2::getTiltError(int8_t instance, float &ang) const
// reset body axis gyro bias estimates // reset body axis gyro bias estimates
void NavEKF2::resetGyroBias(void) void NavEKF2::resetGyroBias(void)
{ {
AP::dal().log_event2(AP_DAL::Event2::resetGyroBias); AP::dal().log_event2(AP_DAL::Event::resetGyroBias);
if (core) { if (core) {
for (uint8_t i=0; i<num_cores; i++) { for (uint8_t i=0; i<num_cores; i++) {
@ -1008,7 +1008,7 @@ void NavEKF2::resetGyroBias(void)
// If using a range finder for height no reset is performed and it returns false // If using a range finder for height no reset is performed and it returns false
bool NavEKF2::resetHeightDatum(void) bool NavEKF2::resetHeightDatum(void)
{ {
AP::dal().log_event2(AP_DAL::Event2::resetHeightDatum); AP::dal().log_event2(AP_DAL::Event::resetHeightDatum);
bool status = true; bool status = true;
if (core) { if (core) {
@ -1031,7 +1031,7 @@ bool NavEKF2::resetHeightDatum(void)
// Returns 2 if attitude, 3D-velocity, vertical position and relative horizontal position will be provided // Returns 2 if attitude, 3D-velocity, vertical position and relative horizontal position will be provided
uint8_t NavEKF2::setInhibitGPS(void) uint8_t NavEKF2::setInhibitGPS(void)
{ {
AP::dal().log_event2(AP_DAL::Event2::setInhibitGPS); AP::dal().log_event2(AP_DAL::Event::setInhibitGPS);
if (!core) { if (!core) {
return 0; return 0;
@ -1043,9 +1043,9 @@ uint8_t NavEKF2::setInhibitGPS(void)
// This can be used for situations where GPS velocity errors are causing problems with height accuracy // This can be used for situations where GPS velocity errors are causing problems with height accuracy
void NavEKF2::setInhibitGpsVertVelUse(const bool varIn) { void NavEKF2::setInhibitGpsVertVelUse(const bool varIn) {
if (varIn) { if (varIn) {
AP::dal().log_event2(AP_DAL::Event2::setInhibitGpsVertVelUse); AP::dal().log_event2(AP_DAL::Event::setInhibitGpsVertVelUse);
} else { } else {
AP::dal().log_event2(AP_DAL::Event2::unsetInhibitGpsVertVelUse); AP::dal().log_event2(AP_DAL::Event::unsetInhibitGpsVertVelUse);
} }
inhibitGpsVertVelUse = varIn; inhibitGpsVertVelUse = varIn;
}; };
@ -1308,9 +1308,9 @@ bool NavEKF2::getRangeBeaconDebug(int8_t instance, uint8_t &ID, float &rng, floa
void NavEKF2::setTakeoffExpected(bool val) void NavEKF2::setTakeoffExpected(bool val)
{ {
if (val) { if (val) {
AP::dal().log_event2(AP_DAL::Event2::setTakeoffExpected); AP::dal().log_event2(AP_DAL::Event::setTakeoffExpected);
} else { } else {
AP::dal().log_event2(AP_DAL::Event2::unsetTakeoffExpected); AP::dal().log_event2(AP_DAL::Event::unsetTakeoffExpected);
} }
if (core) { if (core) {
@ -1325,9 +1325,9 @@ void NavEKF2::setTakeoffExpected(bool val)
void NavEKF2::setTouchdownExpected(bool val) void NavEKF2::setTouchdownExpected(bool val)
{ {
if (val) { if (val) {
AP::dal().log_event2(AP_DAL::Event2::setTouchdownExpected); AP::dal().log_event2(AP_DAL::Event::setTouchdownExpected);
} else { } else {
AP::dal().log_event2(AP_DAL::Event2::unsetTouchdownExpected); AP::dal().log_event2(AP_DAL::Event::unsetTouchdownExpected);
} }
if (core) { if (core) {
@ -1344,9 +1344,9 @@ void NavEKF2::setTouchdownExpected(bool val)
void NavEKF2::setTerrainHgtStable(bool val) void NavEKF2::setTerrainHgtStable(bool val)
{ {
if (val) { if (val) {
AP::dal().log_event2(AP_DAL::Event2::setTerrainHgtStable); AP::dal().log_event2(AP_DAL::Event::setTerrainHgtStable);
} else { } else {
AP::dal().log_event2(AP_DAL::Event2::unsetTerrainHgtStable); AP::dal().log_event2(AP_DAL::Event::unsetTerrainHgtStable);
} }
if (core) { if (core) {
for (uint8_t i=0; i<num_cores; i++) { for (uint8_t i=0; i<num_cores; i++) {
@ -1696,7 +1696,7 @@ bool NavEKF2::isExtNavUsedForYaw() const
void NavEKF2::requestYawReset(void) void NavEKF2::requestYawReset(void)
{ {
AP::dal().log_event2(AP_DAL::Event2::requestYawReset); AP::dal().log_event2(AP_DAL::Event::requestYawReset);
for (uint8_t i = 0; i < num_cores; i++) { for (uint8_t i = 0; i < num_cores; i++) {
core[i].EKFGSF_requestYawReset(); core[i].EKFGSF_requestYawReset();