2012-09-10 23:05:22 -03:00
|
|
|
|
|
|
|
#include <AP_Common.h>
|
2012-12-11 20:23:02 -04:00
|
|
|
#include <AP_Math.h>
|
|
|
|
#include <AP_Param.h>
|
2012-10-27 00:55:17 -03:00
|
|
|
#include <AP_Progmem.h>
|
2012-12-11 20:23:02 -04:00
|
|
|
|
2012-09-10 23:05:22 -03:00
|
|
|
#include <AP_HAL.h>
|
|
|
|
#include <AP_HAL_AVR.h>
|
2013-02-21 21:48:29 -04:00
|
|
|
#include <AP_HAL_AVR_SITL.h>
|
|
|
|
#include <AP_HAL_PX4.h>
|
|
|
|
#include <AP_HAL_Empty.h>
|
2012-09-10 23:05:22 -03:00
|
|
|
|
2013-02-21 21:48:29 -04:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
2012-09-10 23:05:22 -03:00
|
|
|
|
|
|
|
AP_HAL::AnalogSource* ch0;
|
|
|
|
AP_HAL::AnalogSource* ch1;
|
2013-02-21 21:48:29 -04:00
|
|
|
AP_HAL::AnalogSource* ch2;
|
2013-03-14 18:39:22 -03:00
|
|
|
AP_HAL::AnalogSource* ch3;
|
2013-02-21 21:48:29 -04:00
|
|
|
AP_HAL::AnalogSource* ch10;
|
|
|
|
AP_HAL::AnalogSource* ch11;
|
|
|
|
AP_HAL::AnalogSource* ch12;
|
|
|
|
AP_HAL::AnalogSource* ch13;
|
2012-11-28 20:05:37 -04:00
|
|
|
AP_HAL::AnalogSource* vcc;
|
2012-09-10 23:05:22 -03:00
|
|
|
|
|
|
|
void setup (void) {
|
2013-02-21 21:50:47 -04:00
|
|
|
hal.console->printf_P(PSTR("Starting AP_HAL::AnalogIn test\r\n"));
|
2012-09-10 23:05:22 -03:00
|
|
|
ch0 = hal.analogin->channel(0);
|
|
|
|
ch1 = hal.analogin->channel(1);
|
2013-02-21 21:48:29 -04:00
|
|
|
ch2 = hal.analogin->channel(2);
|
2013-03-14 18:39:22 -03:00
|
|
|
ch3 = hal.analogin->channel(3);
|
2013-02-21 21:48:29 -04:00
|
|
|
ch10 = hal.analogin->channel(10);
|
|
|
|
ch11 = hal.analogin->channel(11);
|
|
|
|
ch12 = hal.analogin->channel(12);
|
|
|
|
ch13 = hal.analogin->channel(13);
|
2012-11-28 20:05:37 -04:00
|
|
|
vcc = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC);
|
2012-09-10 23:05:22 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void loop (void) {
|
2013-03-14 18:39:22 -03:00
|
|
|
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"),
|
2013-02-21 21:48:29 -04:00
|
|
|
meas_ch0,
|
|
|
|
meas_ch1,
|
|
|
|
meas_ch2,
|
2013-03-14 18:39:22 -03:00
|
|
|
meas_ch3,
|
2013-02-21 21:48:29 -04:00
|
|
|
meas_ch10,
|
|
|
|
meas_ch11,
|
|
|
|
meas_ch12,
|
|
|
|
meas_ch13,
|
|
|
|
meas_vcc);
|
2013-02-28 20:19:26 -04:00
|
|
|
hal.scheduler->delay(200);
|
2012-09-10 23:05:22 -03:00
|
|
|
}
|
|
|
|
|
2012-12-03 20:25:11 -04:00
|
|
|
AP_HAL_MAIN();
|