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_PX4
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 PX4_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 #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
43  // PX4 has 4 FMU analog input pins
44  { 10, (5.7f*3.3f)/4096 }, // FMU battery on multi-connector pin 5,
45  // 5.7:1 scaling
46  { 11, 6.6f/4096 }, // analog airspeed input, 2:1 scaling
47  { 12, 3.3f/4096 }, // analog2, on SPI port pin 3
48  { 13, 16.8f/4096 }, // analog3, on SPI port pin 4
49 #elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4PRO)
50  { 2, 3.3f/4096 }, // 3DR Brick voltage, usually 10.1:1
51  // scaled from battery voltage
52  { 3, 3.3f/4096 }, // 3DR Brick current, usually 17:1 scaled
53  // for APM_PER_VOLT
54  { 4, 6.6f/4096 }, // VCC 5V rail sense
55  { 10, 3.3f/4096 }, // spare ADC
56  { 11, 3.3f/4096 }, // spare ADC
57  { 12, 3.3f/4096 }, // spare ADC
58  { 13, 3.3f/4096 }, // AUX ADC pin 4
59  { 14, 3.3f/4096 }, // AUX ADC pin 3
60  { 15, 6.6f/4096 }, // analog airspeed sensor, 2:1 scaling
61 #elif defined(CONFIG_ARCH_BOARD_AEROFC_V1)
62  { 1, 3.3f/4096 },
63 #else
64 #error "Unknown board type for AnalogIn scaling"
65 #endif
66  { 0, 0.f },
67 };
68 
69 using namespace PX4;
70 
71 PX4AnalogSource::PX4AnalogSource(int16_t pin, float initial_value) :
72  _pin(pin),
73  _stop_pin(-1),
74  _settle_time_ms(0),
75  _value(initial_value),
76  _value_ratiometric(initial_value),
77  _latest_value(initial_value),
78  _sum_count(0),
79  _sum_value(0),
80  _sum_ratiometric(0)
81 {
82 #ifdef PX4_ANALOG_VCC_5V_PIN
84  _pin = PX4_ANALOG_VCC_5V_PIN;
85  }
86 #endif
87 }
88 
90 {
91  _stop_pin = p;
92 }
93 
95 {
96  if (_sum_count == 0) {
97  return _value;
98  }
102  _sum_value = 0;
103  _sum_ratiometric = 0;
104  _sum_count = 0;
106  return _value;
107 }
108 
110 {
111  return _latest_value;
112 }
113 
114 /*
115  return scaling from ADC count to Volts
116  */
118 {
120  uint8_t num_scalings = ARRAY_SIZE(pin_scaling) - 1;
121  for (uint8_t i=0; i<num_scalings; i++) {
122  if (pin_scaling[i].pin == _pin) {
123  scaling = pin_scaling[i].scaling;
124  break;
125  }
126  }
127  return scaling;
128 }
129 
130 /*
131  return voltage in Volts
132  */
134 {
135  return _pin_scaler() * read_average();
136 }
137 
138 /*
139  return voltage in Volts, assuming a ratiometric sensor powered by
140  the 5V rail
141  */
143 {
144  voltage_average();
145  return _pin_scaler() * _value_ratiometric;
146 }
147 
148 /*
149  return voltage in Volts
150  */
152 {
153  return _pin_scaler() * read_latest();
154 }
155 
157 {
158  if (_pin == pin) {
159  return;
160  }
162  _pin = pin;
163  _sum_value = 0;
164  _sum_ratiometric = 0;
165  _sum_count = 0;
166  _latest_value = 0;
167  _value = 0;
168  _value_ratiometric = 0;
170 }
171 
172 /*
173  apply a reading in ADC counts
174  */
175 void PX4AnalogSource::_add_value(float v, float vcc5V)
176 {
177  _latest_value = v;
178  _sum_value += v;
179  if (vcc5V < 3.0f) {
180  _sum_ratiometric += v;
181  } else {
182  // this compensates for changes in the 5V rail relative to the
183  // 3.3V reference used by the ADC.
184  _sum_ratiometric += v * 5.0f / vcc5V;
185  }
186  _sum_count++;
187  if (_sum_count == 254) {
188  _sum_value /= 2;
189  _sum_ratiometric /= 2;
190  _sum_count /= 2;
191  }
192 }
193 
194 
196  _current_stop_pin_i(0),
197  _board_voltage(0),
198  _servorail_voltage(0),
199  _power_flags(0)
200 {}
201 
203 {
204  _adc_fd = open(ADC0_DEVICE_PATH, O_RDONLY | O_NONBLOCK);
205  if (_adc_fd == -1) {
206  AP_HAL::panic("Unable to open " ADC0_DEVICE_PATH);
207  }
208  _battery_handle = orb_subscribe(ORB_ID(battery_status));
209  _servorail_handle = orb_subscribe(ORB_ID(servorail_status));
210  _system_power_handle = orb_subscribe(ORB_ID(system_power));
211 }
212 
213 
214 /*
215  move to the next stop pin
216  */
218 {
219  // find the next stop pin. We start one past the current stop pin
220  // and wrap completely, so we do the right thing is there is only
221  // one stop pin
222  for (uint8_t i=1; i <= PX4_ANALOG_MAX_CHANNELS; i++) {
223  uint8_t idx = (_current_stop_pin_i + i) % PX4_ANALOG_MAX_CHANNELS;
225  if (c && c->_stop_pin != -1) {
226  // found another stop pin
228  _current_stop_pin_i = idx;
229 
230  // set that pin high
231  hal.gpio->pinMode(c->_stop_pin, 1);
232  hal.gpio->write(c->_stop_pin, 1);
233 
234  // set all others low
235  for (uint8_t j=0; j<PX4_ANALOG_MAX_CHANNELS; j++) {
237  if (c2 && c2->_stop_pin != -1 && j != idx) {
238  hal.gpio->pinMode(c2->_stop_pin, 1);
239  hal.gpio->write(c2->_stop_pin, 0);
240  }
241  }
242  break;
243  }
244  }
245 }
246 
247 /*
248  called at 1kHz
249  */
251 {
252  if (_adc_fd == -1) {
253  // not initialised yet
254  return;
255  }
256 
257  // read adc at 100Hz
258  uint32_t now = AP_HAL::micros();
259  uint32_t delta_t = now - _last_run;
260  if (delta_t < 10000) {
261  return;
262  }
263  _last_run = now;
264 
265  struct adc_msg_s buf_adc[PX4_ANALOG_MAX_CHANNELS];
266 
267  // cope with initial setup of stop pin
268  if (_channels[_current_stop_pin_i] == nullptr ||
269  _channels[_current_stop_pin_i]->_stop_pin == -1) {
270  next_stop_pin();
271  }
272 
273  /* read all channels available */
274  int ret = read(_adc_fd, &buf_adc, sizeof(buf_adc));
275  if (ret > 0) {
276  // match the incoming channels to the currently active pins
277  for (uint8_t i=0; i<ret/sizeof(buf_adc[0]); i++) {
278 #if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4PRO)
279  if (buf_adc[i].am_channel == 4) {
280  // record the Vcc value for later use in
281  // voltage_average_ratiometric()
282  _board_voltage = buf_adc[i].am_data * 6.6f / 4096;
283  }
284 #endif
285  }
286  for (uint8_t i=0; i<ret/sizeof(buf_adc[0]); i++) {
287  Debug("chan %u value=%u\n",
288  (unsigned)buf_adc[i].am_channel,
289  (unsigned)buf_adc[i].am_data);
290  for (uint8_t j=0; j<PX4_ANALOG_MAX_CHANNELS; j++) {
292  if (c != nullptr && buf_adc[i].am_channel == c->_pin) {
293  // add a value if either there is no stop pin, or
294  // the stop pin has been settling for enough time
295  if (c->_stop_pin == -1 ||
296  (_current_stop_pin_i == j &&
298  c->_add_value(buf_adc[i].am_data, _board_voltage);
299  if (c->_stop_pin != -1 && _current_stop_pin_i == j) {
300  next_stop_pin();
301  }
302  }
303  }
304  }
305  }
306  }
307 
308 #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
309  // check for new battery data on FMUv1
310  if (_battery_handle != -1) {
311  struct battery_status_s battery;
312  bool updated = false;
313  if (orb_check(_battery_handle, &updated) == 0 && updated) {
314  orb_copy(ORB_ID(battery_status), _battery_handle, &battery);
315  if (battery.timestamp != _battery_timestamp) {
316  _battery_timestamp = battery.timestamp;
317  for (uint8_t j=0; j<PX4_ANALOG_MAX_CHANNELS; j++) {
319  if (c == nullptr) continue;
320  if (c->_pin == PX4_ANALOG_ORB_BATTERY_VOLTAGE_PIN) {
321  c->_add_value(battery.voltage_v / PX4_VOLTAGE_SCALING, 0);
322  }
323  if (c->_pin == PX4_ANALOG_ORB_BATTERY_CURRENT_PIN) {
324  // scale it back to voltage, knowing that the
325  // px4io code scales by 90.0/5.0
326  c->_add_value(battery.current_a * (5.0f/90.0f) / PX4_VOLTAGE_SCALING, 0);
327  }
328  }
329  }
330  }
331  }
332 #endif
333 
334 #if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4PRO)
335  // check for new servorail data on FMUv2
336  if (_servorail_handle != -1) {
337  struct servorail_status_s servorail;
338  bool updated = false;
339  if (orb_check(_servorail_handle, &updated) == 0 && updated) {
340  orb_copy(ORB_ID(servorail_status), _servorail_handle, &servorail);
341  if (servorail.timestamp != _servorail_timestamp) {
342  _servorail_timestamp = servorail.timestamp;
343  _servorail_voltage = servorail.voltage_v;
344  for (uint8_t j=0; j<PX4_ANALOG_MAX_CHANNELS; j++) {
346  if (c == nullptr) continue;
347  if (c->_pin == PX4_ANALOG_ORB_SERVO_VOLTAGE_PIN) {
348  c->_add_value(servorail.voltage_v / PX4_VOLTAGE_SCALING, 0);
349  }
350  if (c->_pin == PX4_ANALOG_ORB_SERVO_VRSSI_PIN) {
351  c->_add_value(servorail.rssi_v / PX4_VOLTAGE_SCALING, 0);
352  }
353  }
354  }
355  }
356  }
357  if (_system_power_handle != -1) {
358  struct system_power_s system_power;
359  bool updated = false;
360  if (orb_check(_system_power_handle, &updated) == 0 && updated) {
361  orb_copy(ORB_ID(system_power), _system_power_handle, &system_power);
362  uint16_t flags = 0;
363  if (system_power.usb_connected) flags |= MAV_POWER_STATUS_USB_CONNECTED;
364  if (system_power.brick_valid) flags |= MAV_POWER_STATUS_BRICK_VALID;
365  if (system_power.servo_valid) flags |= MAV_POWER_STATUS_SERVO_VALID;
366  if (system_power.periph_5V_OC) flags |= MAV_POWER_STATUS_PERIPH_OVERCURRENT;
367  if (system_power.hipower_5V_OC) flags |= MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT;
368  if (_power_flags != 0 &&
369  _power_flags != flags &&
370  hal.util->get_soft_armed()) {
371  // the power status has changed while armed
372  flags |= MAV_POWER_STATUS_CHANGED;
373  }
374  _power_flags = flags;
375  }
376  }
377 #endif
378 
379 }
380 
382 {
383  for (uint8_t j=0; j<PX4_ANALOG_MAX_CHANNELS; j++) {
384  if (_channels[j] == nullptr) {
385  _channels[j] = new PX4AnalogSource(pin, 0.0f);
386  return _channels[j];
387  }
388  }
389  hal.console->printf("Out of analog channels\n");
390  return nullptr;
391 }
392 
393 #endif // CONFIG_HAL_BOARD
float scaling
Definition: AnalogIn.cpp:40
bool get_soft_armed() const
Definition: Util.h:15
uint32_t _stop_pin_change_time
Definition: AnalogIn.h:73
AP_HAL::AnalogSource * channel(int16_t pin) override
Definition: AnalogIn.cpp:381
int _battery_handle
Definition: AnalogIn.h:64
uint8_t _current_stop_pin_i
Definition: AnalogIn.h:72
int _servorail_handle
Definition: AnalogIn.h:65
void _timer_tick(void)
Definition: AnalogIn.cpp:250
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
#define Debug(fmt, args ...)
Definition: AnalogIn.cpp:29
void next_stop_pin(void)
Definition: AnalogIn.cpp:217
float _value_ratiometric
Definition: AnalogIn.h:43
AP_HAL::Util * util
Definition: HAL.h:115
uint64_t _servorail_timestamp
Definition: AnalogIn.h:68
virtual void write(uint8_t pin, uint8_t value)=0
void _add_value(float v, float vcc5V)
Definition: AnalogIn.cpp:175
virtual void resume_timer_procs()=0
uint64_t _battery_timestamp
Definition: AnalogIn.h:67
uint8_t _sum_count
Definition: AnalogIn.h:45
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)
void init() override
Definition: AnalogIn.cpp:202
uint32_t millis()
Definition: system.cpp:157
static const struct @103 pin_scaling[]
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
uint16_t _settle_time_ms
Definition: AnalogIn.h:39
float v
Definition: Printf.cpp:15
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
PX4::PX4AnalogSource * _channels[PX4_ANALOG_MAX_CHANNELS]
Definition: AnalogIn.h:69
virtual void suspend_timer_procs()=0
float _sum_ratiometric
Definition: AnalogIn.h:47
uint16_t _power_flags
Definition: AnalogIn.h:78
uint32_t _last_run
Definition: AnalogIn.h:75
void set_pin(uint8_t p)
Definition: AnalogIn.cpp:156
AP_HAL::GPIO * gpio
Definition: HAL.h:111
float _board_voltage
Definition: AnalogIn.h:76
#define ANALOG_INPUT_BOARD_VCC
Definition: AnalogIn.h:55
#define PX4_ANALOG_MAX_CHANNELS
Definition: AnalogIn.h:7
void set_stop_pin(uint8_t p)
Definition: AnalogIn.cpp:89
float _servorail_voltage
Definition: AnalogIn.h:77
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
uint32_t micros()
Definition: system.cpp:152
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
int _system_power_handle
Definition: AnalogIn.h:66
float voltage_average_ratiometric()
Definition: AnalogIn.cpp:142
#define PX4_VOLTAGE_SCALING
Definition: AnalogIn.cpp:24