ardupilot/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp

39 lines
742 B
C++
Raw Normal View History

2012-09-10 23:05:22 -03:00
#include <AP_Common.h>
#include <AP_Math.h>
#include <AP_Param.h>
#include <AP_Progmem.h>
2012-09-10 23:05:22 -03:00
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_SITL.h>
#include <AP_HAL_PX4.h>
#include <AP_HAL_Empty.h>
2015-01-28 04:10:34 -04:00
#include <StorageManager.h>
2012-09-10 23:05:22 -03:00
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
2012-09-10 23:05:22 -03:00
AP_HAL::AnalogSource* ch;
2012-09-10 23:05:22 -03:00
void setup (void) {
hal.console->printf_P(PSTR("Starting AP_HAL::AnalogIn test\r\n"));
ch = hal.analogin->channel(0);
2012-09-10 23:05:22 -03:00
}
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);
2012-09-10 23:05:22 -03:00
}
AP_HAL_MAIN();