avoid the need for compiler optimisation for HIL build

read_airspeed() is only available when in a non-HIL build. The
optimiser normally removes this call, but when debugging in a desktop
build, it is nice to avoid using the optimiser
This commit is contained in:
Andrew Tridgell 2011-10-08 09:12:02 +11:00
parent 26c8f734bf
commit 546b4df76d
1 changed files with 3 additions and 1 deletions

View File

@ -473,8 +473,10 @@ static void fast_loop()
// Read Airspeed
// -------------
if (g.airspeed_enabled == true && HIL_MODE != HIL_MODE_ATTITUDE) {
if (g.airspeed_enabled == true) {
#if HIL_MODE != HIL_MODE_ATTITUDE
read_airspeed();
#endif
} else if (g.airspeed_enabled == true && HIL_MODE == HIL_MODE_ATTITUDE) {
calc_airspeed_errors();
}