mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
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:
parent
c0c645bdc5
commit
657367426b
@ -473,8 +473,10 @@ static void fast_loop()
|
|||||||
|
|
||||||
// Read Airspeed
|
// 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();
|
read_airspeed();
|
||||||
|
#endif
|
||||||
} else if (g.airspeed_enabled == true && HIL_MODE == HIL_MODE_ATTITUDE) {
|
} else if (g.airspeed_enabled == true && HIL_MODE == HIL_MODE_ATTITUDE) {
|
||||||
calc_airspeed_errors();
|
calc_airspeed_errors();
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user