From 39ad8b5eec5b5959ef7cd11647dee276ba17700b Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Tue, 24 Jul 2012 07:16:09 +0800 Subject: [PATCH] AP fix sitl hil attitude mode. --- ArduPlane/APM_Config.h | 2 +- ArduPlane/ArduPlane.pde | 7 +++++++ 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/ArduPlane/APM_Config.h b/ArduPlane/APM_Config.h index 18b5794ca7..96d2017fca 100644 --- a/ArduPlane/APM_Config.h +++ b/ArduPlane/APM_Config.h @@ -16,7 +16,7 @@ // The following are the recommended settings for Xplane // simulation. Remove the leading "/* and trailing "*/" to enable: -#define HIL_MODE HIL_MODE_DISABLED +//#define HIL_MODE HIL_MODE_DISABLED /* // HIL_MODE SELECTION diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index d853f18249..b9441f8b19 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -224,6 +224,11 @@ AP_AHRS_HIL ahrs(&imu, g_gps); AP_GPS_HIL g_gps_driver(NULL); AP_Compass_HIL compass; // never used AP_Baro_BMP085_HIL barometer; +#ifdef DESKTOP_BUILD +#include +SITL sitl; +AP_InertialSensor_Oilpan ins( &adc ); +#endif #else #error Unrecognised HIL_MODE setting. @@ -705,7 +710,9 @@ static void fast_loop() // Read Airspeed // ------------- if (airspeed.enabled()) { +#if HIL_MODE != HIL_MODE_ATTITUDE read_airspeed(); +#endif } #if HIL_MODE == HIL_MODE_SENSORS