purple: adc test not useful if no ADC

This commit is contained in:
Andrew Tridgell 2011-11-13 20:24:05 +11:00 committed by Pat Hickey
parent 6c856dde4e
commit b6bab1d92d
1 changed files with 7 additions and 0 deletions

View File

@ -9,7 +9,9 @@ static int8_t test_radio(uint8_t argc, const Menu::arg *argv);
static int8_t test_passthru(uint8_t argc, const Menu::arg *argv); static int8_t test_passthru(uint8_t argc, const Menu::arg *argv);
static int8_t test_failsafe(uint8_t argc, const Menu::arg *argv); static int8_t test_failsafe(uint8_t argc, const Menu::arg *argv);
static int8_t test_gps(uint8_t argc, const Menu::arg *argv); static int8_t test_gps(uint8_t argc, const Menu::arg *argv);
#if CONFIG_ADC == ENABLED
static int8_t test_adc(uint8_t argc, const Menu::arg *argv); static int8_t test_adc(uint8_t argc, const Menu::arg *argv);
#endif
static int8_t test_imu(uint8_t argc, const Menu::arg *argv); static int8_t test_imu(uint8_t argc, const Menu::arg *argv);
static int8_t test_gyro(uint8_t argc, const Menu::arg *argv); static int8_t test_gyro(uint8_t argc, const Menu::arg *argv);
static int8_t test_battery(uint8_t argc, const Menu::arg *argv); static int8_t test_battery(uint8_t argc, const Menu::arg *argv);
@ -45,7 +47,9 @@ static const struct Menu::command test_menu_commands[] PROGMEM = {
// Tests below here are for hardware sensors only present // Tests below here are for hardware sensors only present
// when real sensors are attached or they are emulated // when real sensors are attached or they are emulated
#if HIL_MODE == HIL_MODE_DISABLED #if HIL_MODE == HIL_MODE_DISABLED
#if CONFIG_ADC == ENABLED
{"adc", test_adc}, {"adc", test_adc},
#endif
{"gps", test_gps}, {"gps", test_gps},
{"rawgps", test_rawgps}, {"rawgps", test_rawgps},
{"imu", test_imu}, {"imu", test_imu},
@ -437,6 +441,8 @@ test_dipswitches(uint8_t argc, const Menu::arg *argv)
// tests in this section are for real sensors or sensors that have been simulated // tests in this section are for real sensors or sensors that have been simulated
#if HIL_MODE == HIL_MODE_DISABLED || HIL_MODE == HIL_MODE_SENSORS #if HIL_MODE == HIL_MODE_DISABLED || HIL_MODE == HIL_MODE_SENSORS
#if CONFIG_ADC == ENABLED
static int8_t static int8_t
test_adc(uint8_t argc, const Menu::arg *argv) test_adc(uint8_t argc, const Menu::arg *argv)
{ {
@ -457,6 +463,7 @@ test_adc(uint8_t argc, const Menu::arg *argv)
} }
} }
} }
#endif // CONFIG_ADC
static int8_t static int8_t
test_gps(uint8_t argc, const Menu::arg *argv) test_gps(uint8_t argc, const Menu::arg *argv)