APM:Libraries
AnalogIn.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
4 #include "AnalogIn.h"
5 #include <drivers/drv_adc.h>
6 #include <stdio.h>
7 #include <sys/types.h>
8 #include <sys/stat.h>
9 #include <fcntl.h>
10 #include <unistd.h>
11 #include <nuttx/analog/adc.h>
12 #include <nuttx/config.h>
13 #include <arch/board/board.h>
14 #include <uORB/topics/battery_status.h>
15 #include <uORB/topics/servorail_status.h>
16 #include <uORB/topics/system_power.h>
18 #include <errno.h>
19 #include "GPIO.h"
20 
21 #define ANLOGIN_DEBUGGING 0
22 
23 // base voltage scaling for 12 bit 3.3V ADC
24 #define VRBRAIN_VOLTAGE_SCALING (3.3f/4096.0f)
25 
26 #if ANLOGIN_DEBUGGING
27  # define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
28 #else
29  # define Debug(fmt, args ...)
30 #endif
31 
32 extern const AP_HAL::HAL& hal;
33 
34 /*
35  scaling table between ADC count and actual input voltage, to account
36  for voltage dividers on the board.
37  */
38 static const struct {
39  uint8_t pin;
40  float scaling;
41 } pin_scaling[] = {
42 #if defined(CONFIG_ARCH_BOARD_VRBRAIN_V45) || defined(CONFIG_ARCH_BOARD_VRBRAIN_V51) || defined(CONFIG_ARCH_BOARD_VRBRAIN_V52) || defined(CONFIG_ARCH_BOARD_VRBRAIN_V52E) || defined(CONFIG_ARCH_BOARD_VRCORE_V10) || defined(CONFIG_ARCH_BOARD_VRBRAIN_V54)
43  { 10, 3.3f/4096 },
44  { 11, 3.3f/4096 },
45 #elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V51)
46  { 10, 3.3f/4096 },
47 #elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52)
48  { 1, 3.3f/4096 },
49  { 2, 3.3f/4096 },
50  { 3, 3.3f/4096 },
51  { 10, 3.3f/4096 },
52 #else
53 #error "Unknown board type for AnalogIn scaling"
54 #endif
55  { 0, 0.f },
56 };
57 
58 using namespace VRBRAIN;
59 
60 VRBRAINAnalogSource::VRBRAINAnalogSource(int16_t pin, float initial_value) :
61  _pin(pin),
62  _stop_pin(-1),
63  _settle_time_ms(0),
64  _value(initial_value),
65  _value_ratiometric(initial_value),
66  _latest_value(initial_value),
67  _sum_count(0),
68  _sum_value(0),
69  _sum_ratiometric(0)
70 {
71 
72 
73 
74 
75 
76 }
77 
79 {
80  _stop_pin = p;
81 }
82 
84 {
85  if (_sum_count == 0) {
86  return _value;
87  }
91  _sum_value = 0;
92  _sum_ratiometric = 0;
93  _sum_count = 0;
95  return _value;
96 }
97 
99 {
100  return _latest_value;
101 }
102 
103 /*
104  return scaling from ADC count to Volts
105  */
107 {
109  uint8_t num_scalings = ARRAY_SIZE(pin_scaling);
110  for (uint8_t i=0; i<num_scalings; i++) {
111  if (pin_scaling[i].pin == _pin) {
112  scaling = pin_scaling[i].scaling;
113  break;
114  }
115  }
116  return scaling;
117 }
118 
119 /*
120  return voltage in Volts
121  */
123 {
124  return _pin_scaler() * read_average();
125 }
126 
127 /*
128  return voltage in Volts, assuming a ratiometric sensor powered by
129  the 5V rail
130  */
132 {
133  voltage_average();
134  return _pin_scaler() * _value_ratiometric;
135 }
136 
137 /*
138  return voltage in Volts
139  */
141 {
142  return _pin_scaler() * read_latest();
143 }
144 
146 {
147  if (_pin == pin) {
148  return;
149  }
151  _pin = pin;
152  _sum_value = 0;
153  _sum_ratiometric = 0;
154  _sum_count = 0;
155  _latest_value = 0;
156  _value = 0;
157  _value_ratiometric = 0;
159 }
160 
161 /*
162  apply a reading in ADC counts
163  */
164 void VRBRAINAnalogSource::_add_value(float v, float vcc5V)
165 {
166  _latest_value = v;
167  _sum_value += v;
168  if (vcc5V < 3.0f) {
169  _sum_ratiometric += v;
170  } else {
171  // this compensates for changes in the 5V rail relative to the
172  // 3.3V reference used by the ADC.
173  _sum_ratiometric += v * 5.0f / vcc5V;
174  }
175  _sum_count++;
176  if (_sum_count == 254) {
177  _sum_value /= 2;
178  _sum_ratiometric /= 2;
179  _sum_count /= 2;
180  }
181 }
182 
183 
185  _current_stop_pin_i(0),
186  _board_voltage(0),
187  _servorail_voltage(0),
188  _power_flags(0)
189 {}
190 
192 {
193  _adc_fd = open(ADC0_DEVICE_PATH, O_RDONLY | O_NONBLOCK);
194  if (_adc_fd == -1) {
195  AP_HAL::panic("Unable to open " ADC0_DEVICE_PATH);
196  }
197  _battery_handle = orb_subscribe(ORB_ID(battery_status));
198  _servorail_handle = orb_subscribe(ORB_ID(servorail_status));
199  _system_power_handle = orb_subscribe(ORB_ID(system_power));
200 }
201 
202 
203 /*
204  move to the next stop pin
205  */
207 {
208  // find the next stop pin. We start one past the current stop pin
209  // and wrap completely, so we do the right thing is there is only
210  // one stop pin
211  for (uint8_t i=1; i <= VRBRAIN_ANALOG_MAX_CHANNELS; i++) {
212  uint8_t idx = (_current_stop_pin_i + i) % VRBRAIN_ANALOG_MAX_CHANNELS;
214  if (c && c->_stop_pin != -1) {
215  // found another stop pin
217  _current_stop_pin_i = idx;
218 
219  // set that pin high
220  hal.gpio->pinMode(c->_stop_pin, 1);
221  hal.gpio->write(c->_stop_pin, 1);
222 
223  // set all others low
224  for (uint8_t j=0; j<VRBRAIN_ANALOG_MAX_CHANNELS; j++) {
226  if (c2 && c2->_stop_pin != -1 && j != idx) {
227  hal.gpio->pinMode(c2->_stop_pin, 1);
228  hal.gpio->write(c2->_stop_pin, 0);
229  }
230  }
231  break;
232  }
233  }
234 }
235 
236 /*
237  called at 1kHz
238  */
240 {
241  if (_adc_fd == -1) {
242  // not initialised yet
243  return;
244  }
245 
246  // read adc at 100Hz
247  uint32_t now = AP_HAL::micros();
248  uint32_t delta_t = now - _last_run;
249  if (delta_t < 10000) {
250  return;
251  }
252  _last_run = now;
253 
254  struct adc_msg_s buf_adc[VRBRAIN_ANALOG_MAX_CHANNELS];
255 
256  // cope with initial setup of stop pin
257  if (_channels[_current_stop_pin_i] == nullptr ||
258  _channels[_current_stop_pin_i]->_stop_pin == -1) {
259  next_stop_pin();
260  }
261 
262  /* read all channels available */
263  int ret = read(_adc_fd, &buf_adc, sizeof(buf_adc));
264  if (ret > 0) {
265  // match the incoming channels to the currently active pins
266  for (uint8_t i=0; i<ret/sizeof(buf_adc[0]); i++) {
267  Debug("chan %u value=%u\n",
268  (unsigned)buf_adc[i].am_channel,
269  (unsigned)buf_adc[i].am_data);
270  for (uint8_t j=0; j<VRBRAIN_ANALOG_MAX_CHANNELS; j++) {
272  if (c != nullptr && buf_adc[i].am_channel == c->_pin) {
273  // add a value if either there is no stop pin, or
274  // the stop pin has been settling for enough time
275  if (c->_stop_pin == -1 ||
276  (_current_stop_pin_i == j &&
278  c->_add_value(buf_adc[i].am_data, _board_voltage);
279  if (c->_stop_pin != -1 && _current_stop_pin_i == j) {
280  next_stop_pin();
281  }
282  }
283  }
284  }
285  }
286  }
287 
288 }
289 
291 {
292  for (uint8_t j=0; j<VRBRAIN_ANALOG_MAX_CHANNELS; j++) {
293  if (_channels[j] == nullptr) {
294  _channels[j] = new VRBRAINAnalogSource(pin, 0.0f);
295  return _channels[j];
296  }
297  }
298  hal.console->printf("Out of analog channels\n");
299  return nullptr;
300 }
301 
302 #endif // CONFIG_HAL_BOARD
float scaling
Definition: AnalogIn.cpp:40
uint8_t _current_stop_pin_i
Definition: AnalogIn.h:73
VRBRAIN::VRBRAINAnalogSource * _channels[VRBRAIN_ANALOG_MAX_CHANNELS]
Definition: AnalogIn.h:70
void _add_value(float v, float vcc5V)
Definition: AnalogIn.cpp:164
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
void init() override
Definition: AnalogIn.cpp:191
#define VRBRAIN_ANALOG_MAX_CHANNELS
Definition: AnalogIn.h:7
virtual void write(uint8_t pin, uint8_t value)=0
AP_HAL::AnalogSource * channel(int16_t pin) override
Definition: AnalogIn.cpp:290
virtual void resume_timer_procs()=0
uint32_t _stop_pin_change_time
Definition: AnalogIn.h:74
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint8_t pin
Definition: AnalogIn.cpp:39
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
#define f(i)
uint32_t millis()
Definition: system.cpp:157
virtual void pinMode(uint8_t pin, uint8_t output)=0
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AnalogIn.cpp:6
float v
Definition: Printf.cpp:15
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
virtual void suspend_timer_procs()=0
static const struct @112 pin_scaling[]
#define Debug(fmt, args ...)
Definition: AnalogIn.cpp:29
AP_HAL::GPIO * gpio
Definition: HAL.h:111
#define VRBRAIN_VOLTAGE_SCALING
Definition: AnalogIn.cpp:24
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
void set_stop_pin(uint8_t p)
Definition: AnalogIn.cpp:78
uint32_t micros()
Definition: system.cpp:152
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114