47 _channels_number = _adc->get_channels_number();
52 for (uint8_t j = 0; j < _channels_number; j++) {
53 if (_channels[j] ==
nullptr) {
80 size_t rc = _adc->
read(reports, 6);
82 for (
size_t i = 0; i <
rc; i++) {
83 for (uint8_t j=0; j <
rc; j++) {
86 if (source !=
nullptr && reports[i].
id == source->
_pin) {
#define ADS1115_ADC_MAX_CHANNELS
AP_HAL::UARTDriver * console
virtual void resume_timer_procs()=0
AnalogSource_ADS1115(int16_t pin)
virtual void printf(const char *,...) FMT_PRINTF(2
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
virtual void suspend_timer_procs()=0
AP_HAL::AnalogSource * channel(int16_t n) override
virtual void register_timer_process(AP_HAL::MemberProc)=0
float voltage_average_ratiometric()
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
AP_HAL::Scheduler * scheduler