mirror of https://github.com/ArduPilot/ardupilot
AP_GyroFFT: convert APM_BUILD_COPTER_OR_HELI() to APM_BUILD_COPTER_OR_HELI
This commit is contained in:
parent
9bea417d5c
commit
71c0d9479a
|
@ -683,7 +683,7 @@ float AP_GyroFFT::get_weighted_noise_center_freq_hz() const
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!_health) {
|
if (!_health) {
|
||||||
#if APM_BUILD_COPTER_OR_HELI() || APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
||||||
AP_Motors* motors = AP::motors();
|
AP_Motors* motors = AP::motors();
|
||||||
if (motors != nullptr) {
|
if (motors != nullptr) {
|
||||||
// FFT is not healthy, fallback to throttle-based estimate
|
// FFT is not healthy, fallback to throttle-based estimate
|
||||||
|
@ -715,7 +715,7 @@ uint8_t AP_GyroFFT::get_weighted_noise_center_frequencies_hz(uint8_t num_freqs,
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!_health) {
|
if (!_health) {
|
||||||
#if APM_BUILD_COPTER_OR_HELI() || APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
||||||
AP_Motors* motors = AP::motors();
|
AP_Motors* motors = AP::motors();
|
||||||
if (motors != nullptr) {
|
if (motors != nullptr) {
|
||||||
// FFT is not healthy, fallback to throttle-based estimate
|
// FFT is not healthy, fallback to throttle-based estimate
|
||||||
|
|
Loading…
Reference in New Issue