mirror of https://github.com/ArduPilot/ardupilot
AP_Proximity: cope with AP_OADATABASE_ENABLED being false
This commit is contained in:
parent
97b9c5d4b5
commit
6534a9657c
|
@ -122,7 +122,7 @@ void AP_Proximity_Backend::database_push(float angle, float pitch, float distanc
|
|||
void AP_Proximity_Backend::database_push(float angle, float pitch, float distance, uint32_t timestamp_ms, const Vector3f ¤t_pos, const Matrix3f &body_to_ned)
|
||||
{
|
||||
|
||||
#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph)
|
||||
#if AP_OADATABASE_ENABLED
|
||||
AP_OADatabase *oaDb = AP::oadatabase();
|
||||
if (oaDb == nullptr || !oaDb->healthy()) {
|
||||
return;
|
||||
|
@ -142,7 +142,7 @@ void AP_Proximity_Backend::database_push(float angle, float pitch, float distanc
|
|||
temp_pos.z = temp_pos.z * -1.0f;
|
||||
|
||||
oaDb->queue_push(temp_pos, timestamp_ms, distance);
|
||||
#endif
|
||||
#endif // AP_OADATABASE_ENABLED
|
||||
}
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
|
Loading…
Reference in New Issue