12 #define ADC_BASE_PATH "/sys/kernel/rcio/adc" 30 _fd =
::open(channel_path, O_RDONLY|O_CLOEXEC);
70 if (pread(
_fd, buffer,
sizeof(buffer) - 1, 0) <= 0) {
76 buffer[
sizeof(
buffer) - 1] =
'\0';
78 _value = atoi(buffer) / 1000.0f;
100 return _board_voltage_pin->voltage_average();
105 return _servorail_pin->voltage_average();
110 for (uint8_t j = 0; j < _channels_number; j++) {
111 if (_channels[j] ==
nullptr) {
123 _board_voltage_pin = channel(0);
124 _servorail_pin = channel(1);
void set_pin(uint8_t p) override
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
AP_HAL::UARTDriver * console
static uint8_t buffer[SRXL_FRAMELEN_MAX]
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
#define ANALOG_INPUT_NONE
float servorail_voltage(void) override
void set_channel(uint8_t pin)
float voltage_average_ratiometric() override
float read_average() override
virtual void printf(const char *,...) FMT_PRINTF(2
float voltage_latest() override
float voltage_average() override
static const AP_HAL::HAL & hal
int close(int fileno)
POSIX Close a file with fileno handel.
AP_HAL::AnalogSource * channel(int16_t n) override
int errno
Note: fdevopen assigns stdin,stdout,stderr.
float board_voltage(void) override
int asprintf(char **strp, const char *fmt,...)
void panic(const char *errormsg,...) FMT_PRINTF(1
AnalogSource_Navio2(uint8_t pin)
float read_latest() override