mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_HAL_AVR analog in example: use new constant for board vcc, and vcc not vdd
This commit is contained in:
parent
0c3e59a307
commit
5f48193ea0
@ -8,21 +8,21 @@ const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
|||||||
|
|
||||||
AP_HAL::AnalogSource* ch0;
|
AP_HAL::AnalogSource* ch0;
|
||||||
AP_HAL::AnalogSource* ch1;
|
AP_HAL::AnalogSource* ch1;
|
||||||
AP_HAL::AnalogSource* vdd;
|
AP_HAL::AnalogSource* vcc;
|
||||||
|
|
||||||
void setup (void) {
|
void setup (void) {
|
||||||
hal.console->printf_P(PSTR("Starting AP_HAL_AVR::AnalogIn test\r\n"));
|
hal.console->printf_P(PSTR("Starting AP_HAL_AVR::AnalogIn test\r\n"));
|
||||||
ch0 = hal.analogin->channel(0);
|
ch0 = hal.analogin->channel(0);
|
||||||
ch1 = hal.analogin->channel(1);
|
ch1 = hal.analogin->channel(1);
|
||||||
vdd = hal.analogin->channel(2);
|
vcc = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC);
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop (void) {
|
void loop (void) {
|
||||||
float meas_ch0 = ch0->read();
|
float meas_ch0 = ch0->read();
|
||||||
float meas_ch1 = ch1->read();
|
float meas_ch1 = ch1->read();
|
||||||
float meas_vdd = vdd->read();
|
float meas_vcc = vcc->read();
|
||||||
hal.console->printf_P(PSTR("read ch0: %f, ch1: %f, vdd: %f\r\n"),
|
hal.console->printf_P(PSTR("read ch0: %f, ch1: %f, vcc: %f\r\n"),
|
||||||
meas_ch0, meas_ch1, meas_vdd);
|
meas_ch0, meas_ch1, meas_vcc);
|
||||||
hal.scheduler->delay(10);
|
hal.scheduler->delay(10);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user