diff --git a/ArduCopter/sensors.pde b/ArduCopter/sensors.pde index a80f80aa9d..3aed001f79 100644 --- a/ArduCopter/sensors.pde +++ b/ArduCopter/sensors.pde @@ -88,6 +88,8 @@ static void zero_airspeed(void) } +#endif // HIL_MODE != HIL_MODE_ATTITUDE + static void init_compass() { compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft @@ -110,8 +112,6 @@ static void init_optflow() #endif } -#endif // HIL_MODE != HIL_MODE_ATTITUDE - static void read_battery(void) { battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN1)) * .1 + battery_voltage1 * .9;