APM:Libraries
AnalogIn_Navio2.cpp
Go to the documentation of this file.
1 #include <cstdio>
2 #include <cstdlib>
3 #include <errno.h>
4 #include <unistd.h>
5 
6 #include <AP_HAL/AP_HAL.h>
7 
8 #include "AnalogIn_Navio2.h"
9 
10 static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
11 
12 #define ADC_BASE_PATH "/sys/kernel/rcio/adc"
13 
15 {
16  char *channel_path;
17 
18  if (pin == ANALOG_INPUT_NONE) {
19  return;
20  }
21 
22  if (asprintf(&channel_path, "%s/ch%d", ADC_BASE_PATH, pin) == -1) {
23  AP_HAL::panic("asprintf failed\n");
24  }
25 
26  if (_fd >= 0) {
27  ::close(_fd);
28  }
29 
30  _fd = ::open(channel_path, O_RDONLY|O_CLOEXEC);
31 
32  if (_fd < 0) {
33  hal.console->printf("%s not opened: %s\n", channel_path, strerror(errno));
34  }
35 
36  free(channel_path);
37 }
38 
40  : _pin(pin)
41 {
42  set_channel(pin);
43 }
44 
46 {
47  if (_pin == pin) {
48  return;
49  }
50 
51  set_channel(pin);
52 
53  _pin = pin;
54 }
55 
57 {
58  return read_latest();
59 }
60 
62 {
63  return voltage_average();
64 }
65 
67 {
68  char buffer[12];
69 
70  if (pread(_fd, buffer, sizeof(buffer) - 1, 0) <= 0) {
71  /* Don't log fails since this could spam the console */
72  return -1.0f;
73  }
74 
75  /* Avoid overriding NULL char at the end of the string */
76  buffer[sizeof(buffer) - 1] = '\0';
77 
78  _value = atoi(buffer) / 1000.0f;
79 
80  return _value;
81 }
82 
84 {
85  read_latest();
86  return _value;
87 }
88 
90 {
91  return voltage_average();
92 }
93 
95 {
96 }
97 
99 {
100  return _board_voltage_pin->voltage_average();
101 }
102 
104 {
105  return _servorail_pin->voltage_average();
106 }
107 
109 {
110  for (uint8_t j = 0; j < _channels_number; j++) {
111  if (_channels[j] == nullptr) {
112  _channels[j] = new AnalogSource_Navio2(pin);
113  return _channels[j];
114  }
115  }
116 
117  hal.console->printf("Out of analog channels\n");
118  return nullptr;
119 }
120 
122 {
123  _board_voltage_pin = channel(0);
124  _servorail_pin = channel(1);
125 }
void set_pin(uint8_t p) override
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
AP_HAL::UARTDriver * console
Definition: HAL.h:110
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
#define ANALOG_INPUT_NONE
Definition: AnalogIn.h:56
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
Definition: BetterStream.cpp:5
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.
Definition: posix.c:675
AP_HAL::AnalogSource * channel(int16_t n) override
const HAL & get_HAL()
void free(void *ptr)
Definition: malloc.c:81
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
float board_voltage(void) override
int asprintf(char **strp, const char *fmt,...)
Definition: stdio.c:91
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
static int8_t pin
Definition: AnalogIn.cpp:15
AnalogSource_Navio2(uint8_t pin)
void init() override
#define ADC_BASE_PATH
float read_latest() override