mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Avoidance: conditionally compile based on ADSB support
This commit is contained in:
parent
465357e715
commit
32cd6b487e
@ -1,5 +1,7 @@
|
|||||||
#include "AP_Avoidance.h"
|
#include "AP_Avoidance.h"
|
||||||
|
|
||||||
|
#if HAL_ADSB_ENABLED
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
#include <limits>
|
#include <limits>
|
||||||
@ -680,3 +682,5 @@ AP_Avoidance *ap_avoidance()
|
|||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // HAL_ADSB_ENABLED
|
||||||
|
@ -27,6 +27,8 @@
|
|||||||
|
|
||||||
#include <AP_ADSB/AP_ADSB.h>
|
#include <AP_ADSB/AP_ADSB.h>
|
||||||
|
|
||||||
|
#if HAL_ADSB_ENABLED
|
||||||
|
|
||||||
#define AP_AVOIDANCE_STATE_RECOVERY_TIME_MS 2000 // we will not downgrade state any faster than this (2 seconds)
|
#define AP_AVOIDANCE_STATE_RECOVERY_TIME_MS 2000 // we will not downgrade state any faster than this (2 seconds)
|
||||||
|
|
||||||
#define AP_AVOIDANCE_ESCAPE_TIME_SEC 2 // vehicle runs from thread for 2 seconds
|
#define AP_AVOIDANCE_ESCAPE_TIME_SEC 2 // vehicle runs from thread for 2 seconds
|
||||||
@ -229,3 +231,6 @@ float closest_approach_z(const Location &my_loc,
|
|||||||
namespace AP {
|
namespace AP {
|
||||||
AP_Avoidance *ap_avoidance();
|
AP_Avoidance *ap_avoidance();
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user