AP_HAL: update AnalogIn test to show the first 16 pins

This commit is contained in:
Andrew Tridgell 2013-05-02 21:31:55 +10:00
parent c90d44c121
commit 500497f5fa
1 changed files with 15 additions and 39 deletions

View File

@ -12,50 +12,26 @@
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
AP_HAL::AnalogSource* ch0;
AP_HAL::AnalogSource* ch1;
AP_HAL::AnalogSource* ch2;
AP_HAL::AnalogSource* ch3;
AP_HAL::AnalogSource* ch10;
AP_HAL::AnalogSource* ch11;
AP_HAL::AnalogSource* ch12;
AP_HAL::AnalogSource* ch13;
AP_HAL::AnalogSource* vcc;
AP_HAL::AnalogSource* ch;
void setup (void) {
hal.console->printf_P(PSTR("Starting AP_HAL::AnalogIn test\r\n"));
ch0 = hal.analogin->channel(0);
ch1 = hal.analogin->channel(1);
ch2 = hal.analogin->channel(2);
ch3 = hal.analogin->channel(3);
ch10 = hal.analogin->channel(10);
ch11 = hal.analogin->channel(11);
ch12 = hal.analogin->channel(12);
ch13 = hal.analogin->channel(13);
vcc = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC);
ch = hal.analogin->channel(0);
}
void loop (void) {
float meas_ch0 = ch0->voltage_average();
float meas_ch1 = ch1->voltage_average();
float meas_ch2 = ch2->voltage_average();
float meas_ch3 = ch3->voltage_average();
float meas_ch10 = ch10->voltage_average();
float meas_ch11 = ch11->voltage_average();
float meas_ch12 = ch12->voltage_average();
float meas_ch13 = ch13->voltage_average();
float meas_vcc = vcc->read_average() * 0.001;
hal.console->printf_P(PSTR("Voltage ch0:%.2f ch1:%.2f ch2:%.2f ch3:%.2f ch10:%.2f ch11:%.2f ch12:%.2f ch13:%.2f vcc:%.2f\n"),
meas_ch0,
meas_ch1,
meas_ch2,
meas_ch3,
meas_ch10,
meas_ch11,
meas_ch12,
meas_ch13,
meas_vcc);
hal.scheduler->delay(200);
static int8_t pin;
void loop (void)
{
float v = ch->voltage_average();
if (pin == 0) {
hal.console->println();
}
hal.console->printf_P(PSTR("[%u %.3f] "),
(unsigned)pin, v);
pin = (pin+1) % 16;
ch->set_pin(pin);
hal.scheduler->delay(100);
}
AP_HAL_MAIN();