APM:Libraries
AnalogIn.cpp
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  *
15  * Code by Andrew Tridgell and Siddharth Bharat Purohit
16  */
17 #include <AP_HAL/AP_HAL.h>
18 #include "ch.h"
19 #include "hal.h"
20 
21 #if HAL_USE_ADC == TRUE
22 
23 #include "AnalogIn.h"
24 
25 #if HAL_WITH_IO_MCU
26 #include <AP_IOMCU/AP_IOMCU.h>
27 extern AP_IOMCU iomcu;
28 #endif
29 
30 #ifndef CHIBIOS_ADC_MAVLINK_DEBUG
31 // this allows the first 6 analog channels to be reported by mavlink for debugging purposes
32 #define CHIBIOS_ADC_MAVLINK_DEBUG 0
33 #endif
34 
36 
37 #define ANLOGIN_DEBUGGING 0
38 
39 // base voltage scaling for 12 bit 3.3V ADC
40 #define VOLTAGE_SCALING (3.3f/4096.0f)
41 
42 #if ANLOGIN_DEBUGGING
43  # define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
44 #else
45  # define Debug(fmt, args ...)
46 #endif
47 
48 extern const AP_HAL::HAL& hal;
49 
50 using namespace ChibiOS;
51 
52 /*
53  scaling table between ADC count and actual input voltage, to account
54  for voltage dividers on the board.
55  */
56 const AnalogIn::pin_info AnalogIn::pin_config[] = HAL_ANALOG_PINS;
57 
58 #define ADC_GRP1_NUM_CHANNELS ARRAY_SIZE_SIMPLE(AnalogIn::pin_config)
59 
60 // samples filled in by ADC DMA engine
63 uint32_t AnalogIn::sample_count;
64 
65 AnalogSource::AnalogSource(int16_t pin, float initial_value) :
66  _pin(pin),
67  _value(initial_value),
68  _value_ratiometric(initial_value),
69  _latest_value(initial_value),
70  _sum_count(0),
71  _sum_value(0),
72  _sum_ratiometric(0)
73 {
74 }
75 
76 
78 {
79  if (_sum_count == 0) {
80  return _value;
81  }
84  _sum_value = 0;
85  _sum_ratiometric = 0;
86  _sum_count = 0;
87  return _value;
88 }
89 
91 {
92  return _latest_value;
93 }
94 
95 /*
96  return scaling from ADC count to Volts
97  */
99 {
100  float scaling = VOLTAGE_SCALING;
101  for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
102  if (AnalogIn::pin_config[i].channel == _pin) {
103  scaling = AnalogIn::pin_config[i].scaling;
104  break;
105  }
106  }
107  return scaling;
108 }
109 
110 /*
111  return voltage in Volts
112  */
114 {
115  return _pin_scaler() * read_average();
116 }
117 
118 /*
119  return voltage in Volts, assuming a ratiometric sensor powered by
120  the 5V rail
121  */
123 {
124  voltage_average();
125  return _pin_scaler() * _value_ratiometric;
126 }
127 
128 /*
129  return voltage in Volts
130  */
132 {
133  return _pin_scaler() * read_latest();
134 }
135 
137 {
138  if (_pin == pin) {
139  return;
140  }
141  _pin = pin;
142  _sum_value = 0;
143  _sum_ratiometric = 0;
144  _sum_count = 0;
145  _latest_value = 0;
146  _value = 0;
147  _value_ratiometric = 0;
148 }
149 
150 /*
151  apply a reading in ADC counts
152  */
153 void AnalogSource::_add_value(float v, float vcc5V)
154 {
155  _latest_value = v;
156  _sum_value += v;
157  if (vcc5V < 3.0f) {
158  _sum_ratiometric += v;
159  } else {
160  // this compensates for changes in the 5V rail relative to the
161  // 3.3V reference used by the ADC.
162  _sum_ratiometric += v * 5.0f / vcc5V;
163  }
164  _sum_count++;
165  if (_sum_count == 254) {
166  _sum_value /= 2;
167  _sum_ratiometric /= 2;
168  _sum_count /= 2;
169  }
170 }
171 
172 
174  _board_voltage(0),
175  _servorail_voltage(0),
176  _power_flags(0)
177 {
178 }
179 
180 /*
181  callback from ADC driver when sample buffer is filled
182  */
183 void AnalogIn::adccallback(ADCDriver *adcp, adcsample_t *buffer, size_t n)
184 {
185  if (buffer != samples) {
186  return;
187  }
188  for (uint8_t i = 0; i < ADC_DMA_BUF_DEPTH; i++) {
189  for (uint8_t j = 0; j < ADC_GRP1_NUM_CHANNELS; j++) {
190  sample_sum[j] += *buffer++;
191  }
192  }
194 }
195 
196 /*
197  setup adc peripheral to capture samples with DMA into a buffer
198  */
200 {
201  if (ADC_GRP1_NUM_CHANNELS == 0) {
202  return;
203  }
204  adcStart(&ADCD1, NULL);
205  memset(&adcgrpcfg, 0, sizeof(adcgrpcfg));
206  adcgrpcfg.circular = true;
207  adcgrpcfg.num_channels = ADC_GRP1_NUM_CHANNELS;
208  adcgrpcfg.end_cb = adccallback;
209  adcgrpcfg.cr2 = ADC_CR2_SWSTART;
210  adcgrpcfg.sqr1 = ADC_SQR1_NUM_CH(ADC_GRP1_NUM_CHANNELS);
211 
212  for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
213  uint8_t chan = pin_config[i].channel;
214  // setup cycles per sample for the channel
215  if (chan < 10) {
216  adcgrpcfg.smpr2 |= ADC_SAMPLE_480 << (3*chan);
217  } else {
218  adcgrpcfg.smpr1 |= ADC_SAMPLE_480 << (3*(chan-10));
219  }
220  // setup channel sequence
221  if (i < 6) {
222  adcgrpcfg.sqr3 |= chan << (5*i);
223  } else if (i < 12) {
224  adcgrpcfg.sqr2 |= chan << (5*(i-6));
225  } else {
226  adcgrpcfg.sqr1 |= chan << (5*(i-12));
227  }
228  }
229  adcStartConversion(&ADCD1, &adcgrpcfg, samples, ADC_DMA_BUF_DEPTH);
230 }
231 
232 /*
233  calculate average sample since last read for all channels
234  */
235 void AnalogIn::read_adc(uint32_t *val)
236 {
237  chSysLock();
238  for (uint8_t i = 0; i < ADC_GRP1_NUM_CHANNELS; i++) {
239  val[i] = sample_sum[i] / sample_count;
240  }
241  memset(sample_sum, 0, sizeof(sample_sum));
242  sample_count = 0;
243  chSysUnlock();
244 }
245 
246 /*
247  called at 1kHz
248  */
250 {
251  // read adc at 100Hz
252  uint32_t now = AP_HAL::micros();
253  uint32_t delta_t = now - _last_run;
254  if (delta_t < 10000) {
255  return;
256  }
257  _last_run = now;
258 
259  uint32_t buf_adc[ADC_GRP1_NUM_CHANNELS];
260 
261  /* read all channels available */
262  read_adc(buf_adc);
263 
264  // update power status flags
266 
267  // match the incoming channels to the currently active pins
268  for (uint8_t i=0; i < ADC_GRP1_NUM_CHANNELS; i++) {
269 #ifdef ANALOG_VCC_5V_PIN
270  if (pin_config[i].channel == ANALOG_VCC_5V_PIN) {
271  // record the Vcc value for later use in
272  // voltage_average_ratiometric()
273  _board_voltage = buf_adc[i] * pin_config[i].scaling;
274  }
275 #endif
276  }
277  for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
278  Debug("chan %u value=%u\n",
279  (unsigned)pin_config[i].channel,
280  (unsigned)buf_adc[i]);
281  for (uint8_t j=0; j < ADC_GRP1_NUM_CHANNELS; j++) {
283  if (c != nullptr && pin_config[i].channel == c->_pin) {
284  // add a value
285  c->_add_value(buf_adc[i], _board_voltage);
286  }
287  }
288  }
289 
290 #if HAL_WITH_IO_MCU
291  // now handle special inputs from IOMCU
292  _servorail_voltage = iomcu.get_vservo();
293 #endif
294 
295 #if CHIBIOS_ADC_MAVLINK_DEBUG
296  static uint8_t count;
297  if (AP_HAL::millis() > 5000 && count++ == 10) {
298  count = 0;
299  uint16_t adc[6] {};
300  for (uint8_t i=0; i < ADC_GRP1_NUM_CHANNELS; i++) {
301  adc[i] = buf_adc[i];
302  }
303  mavlink_msg_ap_adc_send(MAVLINK_COMM_0, adc[0], adc[1], adc[2], adc[3], adc[4], adc[5]);
304  }
305 #endif
306 }
307 
309 {
310  for (uint8_t j=0; j<ANALOG_MAX_CHANNELS; j++) {
311  if (_channels[j] == nullptr) {
312  _channels[j] = new AnalogSource(pin, 0.0f);
313  return _channels[j];
314  }
315  }
316  hal.console->printf("Out of analog channels\n");
317  return nullptr;
318 }
319 
320 /*
321  update power status flags
322  */
324 {
325  uint16_t flags = 0;
326 
327 #ifdef HAL_GPIO_PIN_VDD_BRICK_VALID
328  if (!palReadLine(HAL_GPIO_PIN_VDD_BRICK_VALID)) {
329  flags |= MAV_POWER_STATUS_BRICK_VALID;
330  }
331 #endif
332 
333 #ifdef HAL_GPIO_PIN_VDD_SERVO_VALID
334  if (!palReadLine(HAL_GPIO_PIN_VDD_SERVO_VALID)) {
335  flags |= MAV_POWER_STATUS_SERVO_VALID;
336  }
337 #endif
338 
339 #ifdef HAL_GPIO_PIN_VBUS
340  if (palReadLine(HAL_GPIO_PIN_VBUS)) {
341  flags |= MAV_POWER_STATUS_USB_CONNECTED;
342  }
343 #endif
344 
345 #ifdef HAL_GPIO_PIN_VDD_5V_HIPOWER_OC
346  if (!palReadLine(HAL_GPIO_PIN_VDD_5V_HIPOWER_OC)) {
347  flags |= MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT;
348  }
349 #endif
350 
351 #ifdef HAL_GPIO_PIN_VDD_5V_PERIPH_OC
352  if (!palReadLine(HAL_GPIO_PIN_VDD_5V_PERIPH_OC)) {
353  flags |= MAV_POWER_STATUS_PERIPH_OVERCURRENT;
354  }
355 #endif
356  if (_power_flags != 0 &&
357  _power_flags != flags &&
358  hal.util->get_soft_armed()) {
359  // the power status has changed while armed
360  flags |= MAV_POWER_STATUS_CHANGED;
361  }
362  _power_flags = flags;
363 }
364 #endif // HAL_USE_ADC
365 
float scaling
Definition: AnalogIn.cpp:40
bool get_soft_armed() const
Definition: Util.h:15
void update_power_flags(void)
Definition: AnalogIn.cpp:323
static adcsample_t samples[]
Definition: AnalogIn.h:91
AP_HAL::UARTDriver * console
Definition: HAL.h:110
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
AP_HAL::AnalogSource * channel(int16_t pin) override
Definition: AnalogIn.cpp:308
void init() override
Definition: AnalogIn.cpp:199
float _servorail_voltage
Definition: AnalogIn.h:81
AP_HAL::Util * util
Definition: HAL.h:115
#define Debug(fmt, args ...)
Definition: AnalogIn.cpp:45
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint8_t pin
Definition: AnalogIn.cpp:39
void set_pin(uint8_t p)
Definition: AnalogIn.cpp:136
#define f(i)
AnalogSource(int16_t pin, float initial_value)
Definition: AnalogIn.cpp:65
static uint32_t sample_sum[]
Definition: AnalogIn.h:92
ChibiOS::AnalogSource * _channels[ANALOG_MAX_CHANNELS]
Definition: AnalogIn.h:77
uint32_t millis()
Definition: system.cpp:157
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AnalogIn.cpp:6
void _add_value(float v, float vcc5V)
Definition: AnalogIn.cpp:153
friend class AnalogSource
Definition: AnalogIn.h:57
float v
Definition: Printf.cpp:15
#define VOLTAGE_SCALING
Definition: AnalogIn.cpp:40
#define NULL
Definition: hal_types.h:59
uint16_t _power_flags
Definition: AnalogIn.h:82
#define ADC_GRP1_NUM_CHANNELS
Definition: AnalogIn.cpp:58
float voltage_average_ratiometric()
Definition: AnalogIn.cpp:122
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
uint32_t _last_run
Definition: AnalogIn.h:79
static uint32_t sample_count
Definition: AnalogIn.h:93
static void adccallback(ADCDriver *adcp, adcsample_t *buffer, size_t n)
Definition: AnalogIn.cpp:183
float _value_ratiometric
Definition: AnalogIn.h:46
static const pin_info pin_config[]
Definition: AnalogIn.h:89
#define ANALOG_MAX_CHANNELS
Definition: AnalogIn.h:22
ADCConversionGroup adcgrpcfg
Definition: AnalogIn.h:83
float _board_voltage
Definition: AnalogIn.h:80
void _timer_tick(void)
Definition: AnalogIn.cpp:249
#define ADC_DMA_BUF_DEPTH
Definition: AnalogIn.h:25
uint32_t micros()
Definition: system.cpp:152
void read_adc(uint32_t *val)
Definition: AnalogIn.cpp:235