AP_Proximity: cope with AP_AVOIDANCE_ENABLED being false

This commit is contained in:
Peter Barker 2024-03-09 18:49:48 +11:00 committed by Peter Barker
parent ceb45a9c3b
commit e4ff1a97d5
1 changed files with 1 additions and 1 deletions

View File

@ -88,7 +88,7 @@ bool AP_Proximity_Backend::ignore_reading(float pitch, float yaw, float distance
// returns true if database is ready to be pushed to and all cached data is ready // returns true if database is ready to be pushed to and all cached data is ready
bool AP_Proximity_Backend::database_prepare_for_push(Vector3f &current_pos, Matrix3f &body_to_ned) bool AP_Proximity_Backend::database_prepare_for_push(Vector3f &current_pos, Matrix3f &body_to_ned)
{ {
#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph) #if AP_OADATABASE_ENABLED
AP_OADatabase *oaDb = AP::oadatabase(); AP_OADatabase *oaDb = AP::oadatabase();
if (oaDb == nullptr || !oaDb->healthy()) { if (oaDb == nullptr || !oaDb->healthy()) {
return false; return false;