AnalogIn.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414
  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. #if HAL_USE_ADC == TRUE && !defined(HAL_DISABLE_ADC_DRIVER)
  21. #include "AnalogIn.h"
  22. #if HAL_WITH_IO_MCU
  23. #include <AP_IOMCU/AP_IOMCU.h>
  24. extern AP_IOMCU iomcu;
  25. #endif
  26. #include "hwdef/common/stm32_util.h"
  27. #ifndef CHIBIOS_ADC_MAVLINK_DEBUG
  28. // this allows the first 6 analog channels to be reported by mavlink for debugging purposes
  29. #define CHIBIOS_ADC_MAVLINK_DEBUG 0
  30. #endif
  31. #include <GCS_MAVLink/GCS_MAVLink.h>
  32. #define ANLOGIN_DEBUGGING 0
  33. // base voltage scaling for 12 bit 3.3V ADC
  34. #define VOLTAGE_SCALING (3.3f/(1<<12))
  35. #if ANLOGIN_DEBUGGING
  36. # define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
  37. #else
  38. # define Debug(fmt, args ...)
  39. #endif
  40. extern const AP_HAL::HAL& hal;
  41. using namespace ChibiOS;
  42. // special pins
  43. #define ANALOG_SERVO_VRSSI_PIN 103
  44. /*
  45. scaling table between ADC count and actual input voltage, to account
  46. for voltage dividers on the board.
  47. */
  48. const AnalogIn::pin_info AnalogIn::pin_config[] = HAL_ANALOG_PINS;
  49. #define ADC_GRP1_NUM_CHANNELS ARRAY_SIZE(AnalogIn::pin_config)
  50. // samples filled in by ADC DMA engine
  51. adcsample_t *AnalogIn::samples;
  52. uint32_t AnalogIn::sample_sum[ADC_GRP1_NUM_CHANNELS];
  53. uint32_t AnalogIn::sample_count;
  54. AnalogSource::AnalogSource(int16_t pin, float initial_value) :
  55. _pin(pin),
  56. _value(initial_value),
  57. _value_ratiometric(initial_value),
  58. _latest_value(initial_value),
  59. _sum_count(0),
  60. _sum_value(0),
  61. _sum_ratiometric(0)
  62. {
  63. }
  64. float AnalogSource::read_average()
  65. {
  66. WITH_SEMAPHORE(_semaphore);
  67. if (_sum_count == 0) {
  68. return _value;
  69. }
  70. _value = _sum_value / _sum_count;
  71. _value_ratiometric = _sum_ratiometric / _sum_count;
  72. _sum_value = 0;
  73. _sum_ratiometric = 0;
  74. _sum_count = 0;
  75. return _value;
  76. }
  77. float AnalogSource::read_latest()
  78. {
  79. return _latest_value;
  80. }
  81. /*
  82. return scaling from ADC count to Volts
  83. */
  84. float AnalogSource::_pin_scaler(void)
  85. {
  86. float scaling = VOLTAGE_SCALING;
  87. for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
  88. if (AnalogIn::pin_config[i].channel == _pin) {
  89. scaling = AnalogIn::pin_config[i].scaling;
  90. break;
  91. }
  92. }
  93. return scaling;
  94. }
  95. /*
  96. return voltage in Volts
  97. */
  98. float AnalogSource::voltage_average()
  99. {
  100. return _pin_scaler() * read_average();
  101. }
  102. /*
  103. return voltage in Volts, assuming a ratiometric sensor powered by
  104. the 5V rail
  105. */
  106. float AnalogSource::voltage_average_ratiometric()
  107. {
  108. voltage_average();
  109. return _pin_scaler() * _value_ratiometric;
  110. }
  111. /*
  112. return voltage in Volts
  113. */
  114. float AnalogSource::voltage_latest()
  115. {
  116. return _pin_scaler() * read_latest();
  117. }
  118. void AnalogSource::set_pin(uint8_t pin)
  119. {
  120. if (_pin == pin) {
  121. return;
  122. }
  123. WITH_SEMAPHORE(_semaphore);
  124. _pin = pin;
  125. _sum_value = 0;
  126. _sum_ratiometric = 0;
  127. _sum_count = 0;
  128. _latest_value = 0;
  129. _value = 0;
  130. _value_ratiometric = 0;
  131. }
  132. /*
  133. apply a reading in ADC counts
  134. */
  135. void AnalogSource::_add_value(float v, float vcc5V)
  136. {
  137. WITH_SEMAPHORE(_semaphore);
  138. _latest_value = v;
  139. _sum_value += v;
  140. if (vcc5V < 3.0f) {
  141. _sum_ratiometric += v;
  142. } else {
  143. // this compensates for changes in the 5V rail relative to the
  144. // 3.3V reference used by the ADC.
  145. _sum_ratiometric += v * 5.0f / vcc5V;
  146. }
  147. _sum_count++;
  148. if (_sum_count == 254) {
  149. _sum_value /= 2;
  150. _sum_ratiometric /= 2;
  151. _sum_count /= 2;
  152. }
  153. }
  154. /*
  155. callback from ADC driver when sample buffer is filled
  156. */
  157. void AnalogIn::adccallback(ADCDriver *adcp)
  158. {
  159. const adcsample_t *buffer = samples;
  160. stm32_cacheBufferInvalidate(buffer, sizeof(adcsample_t)*ADC_DMA_BUF_DEPTH*ADC_GRP1_NUM_CHANNELS);
  161. for (uint8_t i = 0; i < ADC_DMA_BUF_DEPTH; i++) {
  162. for (uint8_t j = 0; j < ADC_GRP1_NUM_CHANNELS; j++) {
  163. sample_sum[j] += *buffer++;
  164. }
  165. }
  166. sample_count += ADC_DMA_BUF_DEPTH;
  167. }
  168. /*
  169. setup adc peripheral to capture samples with DMA into a buffer
  170. */
  171. void AnalogIn::init()
  172. {
  173. if (ADC_GRP1_NUM_CHANNELS == 0) {
  174. return;
  175. }
  176. samples = (adcsample_t *)hal.util->malloc_type(sizeof(adcsample_t)*ADC_DMA_BUF_DEPTH*ADC_GRP1_NUM_CHANNELS, AP_HAL::Util::MEM_DMA_SAFE);
  177. adcStart(&ADCD1, NULL);
  178. memset(&adcgrpcfg, 0, sizeof(adcgrpcfg));
  179. adcgrpcfg.circular = true;
  180. adcgrpcfg.num_channels = ADC_GRP1_NUM_CHANNELS;
  181. adcgrpcfg.end_cb = adccallback;
  182. #if defined(STM32H7)
  183. // use 12 bits resolution to keep scaling factors the same as other boards.
  184. // todo: enable oversampling in cfgr2 ?
  185. adcgrpcfg.cfgr = ADC_CFGR_CONT | ADC_CFGR_RES_12BITS;
  186. #else
  187. adcgrpcfg.sqr1 = ADC_SQR1_NUM_CH(ADC_GRP1_NUM_CHANNELS);
  188. adcgrpcfg.cr2 = ADC_CR2_SWSTART;
  189. #endif
  190. for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
  191. uint8_t chan = pin_config[i].channel;
  192. // setup cycles per sample for the channel
  193. #if defined(STM32H7)
  194. adcgrpcfg.pcsel |= (1<<chan);
  195. adcgrpcfg.smpr[chan/10] |= ADC_SMPR_SMP_384P5 << (3*(chan%10));
  196. if (i < 4) {
  197. adcgrpcfg.sqr[0] |= chan << (6*(i+1));
  198. } else if (i < 9) {
  199. adcgrpcfg.sqr[1] |= chan << (6*(i-4));
  200. } else {
  201. adcgrpcfg.sqr[2] |= chan << (6*(i-9));
  202. }
  203. #else
  204. if (chan < 10) {
  205. adcgrpcfg.smpr2 |= ADC_SAMPLE_480 << (3*chan);
  206. } else {
  207. adcgrpcfg.smpr1 |= ADC_SAMPLE_480 << (3*(chan-10));
  208. }
  209. // setup channel sequence
  210. if (i < 6) {
  211. adcgrpcfg.sqr3 |= chan << (5*i);
  212. } else if (i < 12) {
  213. adcgrpcfg.sqr2 |= chan << (5*(i-6));
  214. } else {
  215. adcgrpcfg.sqr1 |= chan << (5*(i-12));
  216. }
  217. #endif
  218. }
  219. adcStartConversion(&ADCD1, &adcgrpcfg, samples, ADC_DMA_BUF_DEPTH);
  220. }
  221. /*
  222. calculate average sample since last read for all channels
  223. */
  224. void AnalogIn::read_adc(uint32_t *val)
  225. {
  226. chSysLock();
  227. for (uint8_t i = 0; i < ADC_GRP1_NUM_CHANNELS; i++) {
  228. val[i] = sample_sum[i] / sample_count;
  229. }
  230. memset(sample_sum, 0, sizeof(sample_sum));
  231. sample_count = 0;
  232. chSysUnlock();
  233. }
  234. /*
  235. called at 1kHz
  236. */
  237. void AnalogIn::_timer_tick(void)
  238. {
  239. // read adc at 100Hz
  240. uint32_t now = AP_HAL::micros();
  241. uint32_t delta_t = now - _last_run;
  242. if (delta_t < 10000) {
  243. return;
  244. }
  245. _last_run = now;
  246. uint32_t buf_adc[ADC_GRP1_NUM_CHANNELS];
  247. /* read all channels available */
  248. read_adc(buf_adc);
  249. // update power status flags
  250. update_power_flags();
  251. // match the incoming channels to the currently active pins
  252. for (uint8_t i=0; i < ADC_GRP1_NUM_CHANNELS; i++) {
  253. #ifdef ANALOG_VCC_5V_PIN
  254. if (pin_config[i].channel == ANALOG_VCC_5V_PIN) {
  255. // record the Vcc value for later use in
  256. // voltage_average_ratiometric()
  257. _board_voltage = buf_adc[i] * pin_config[i].scaling;
  258. }
  259. #endif
  260. #ifdef FMU_SERVORAIL_ADC_CHAN
  261. if (pin_config[i].channel == FMU_SERVORAIL_ADC_CHAN) {
  262. _servorail_voltage = buf_adc[i] * pin_config[i].scaling;
  263. }
  264. #endif
  265. }
  266. #if HAL_WITH_IO_MCU
  267. // now handle special inputs from IOMCU
  268. _servorail_voltage = iomcu.get_vservo();
  269. _rssi_voltage = iomcu.get_vrssi();
  270. #endif
  271. for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
  272. Debug("chan %u value=%u\n",
  273. (unsigned)pin_config[i].channel,
  274. (unsigned)buf_adc[i]);
  275. for (uint8_t j=0; j < ANALOG_MAX_CHANNELS; j++) {
  276. ChibiOS::AnalogSource *c = _channels[j];
  277. if (c != nullptr) {
  278. if (pin_config[i].channel == c->_pin) {
  279. // add a value
  280. c->_add_value(buf_adc[i], _board_voltage);
  281. } else if (c->_pin == ANALOG_SERVO_VRSSI_PIN) {
  282. c->_add_value(_rssi_voltage / VOLTAGE_SCALING, 0);
  283. }
  284. }
  285. }
  286. }
  287. #if CHIBIOS_ADC_MAVLINK_DEBUG
  288. static uint8_t count;
  289. if (AP_HAL::millis() > 5000 && count++ == 10) {
  290. count = 0;
  291. uint16_t adc[6] {};
  292. uint8_t n = ADC_GRP1_NUM_CHANNELS;
  293. if (n > 6) {
  294. n = 6;
  295. }
  296. for (uint8_t i=0; i < n; i++) {
  297. adc[i] = buf_adc[i];
  298. }
  299. mavlink_msg_ap_adc_send(MAVLINK_COMM_0, adc[0], adc[1], adc[2], adc[3], adc[4], adc[5]);
  300. }
  301. #endif
  302. }
  303. AP_HAL::AnalogSource* AnalogIn::channel(int16_t pin)
  304. {
  305. for (uint8_t j=0; j<ANALOG_MAX_CHANNELS; j++) {
  306. if (_channels[j] == nullptr) {
  307. _channels[j] = new AnalogSource(pin, 0.0f);
  308. return _channels[j];
  309. }
  310. }
  311. hal.console->printf("Out of analog channels\n");
  312. return nullptr;
  313. }
  314. /*
  315. update power status flags
  316. */
  317. void AnalogIn::update_power_flags(void)
  318. {
  319. uint16_t flags = 0;
  320. #ifdef HAL_GPIO_PIN_VDD_BRICK_VALID
  321. if (!palReadLine(HAL_GPIO_PIN_VDD_BRICK_VALID)) {
  322. flags |= MAV_POWER_STATUS_BRICK_VALID;
  323. }
  324. #endif
  325. #ifdef HAL_GPIO_PIN_VDD_SERVO_VALID
  326. if (!palReadLine(HAL_GPIO_PIN_VDD_SERVO_VALID)) {
  327. flags |= MAV_POWER_STATUS_SERVO_VALID;
  328. }
  329. #elif defined(HAL_GPIO_PIN_VDD_BRICK2_VALID)
  330. // some boards defined BRICK2 instead of servo valid
  331. if (!palReadLine(HAL_GPIO_PIN_VDD_BRICK2_VALID)) {
  332. flags |= MAV_POWER_STATUS_SERVO_VALID;
  333. }
  334. #endif
  335. #ifdef HAL_GPIO_PIN_VBUS
  336. if (palReadLine(HAL_GPIO_PIN_VBUS)) {
  337. flags |= MAV_POWER_STATUS_USB_CONNECTED;
  338. }
  339. #elif defined(HAL_GPIO_PIN_nVBUS)
  340. if (!palReadLine(HAL_GPIO_PIN_nVBUS)) {
  341. flags |= MAV_POWER_STATUS_USB_CONNECTED;
  342. }
  343. #endif
  344. #ifdef HAL_GPIO_PIN_VDD_5V_HIPOWER_OC
  345. if (!palReadLine(HAL_GPIO_PIN_VDD_5V_HIPOWER_OC)) {
  346. flags |= MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT;
  347. }
  348. #endif
  349. #ifdef HAL_GPIO_PIN_VDD_5V_PERIPH_OC
  350. if (!palReadLine(HAL_GPIO_PIN_VDD_5V_PERIPH_OC)) {
  351. flags |= MAV_POWER_STATUS_PERIPH_OVERCURRENT;
  352. }
  353. #endif
  354. if (_power_flags != 0 &&
  355. _power_flags != flags &&
  356. hal.util->get_soft_armed()) {
  357. // the power status has changed while armed
  358. flags |= MAV_POWER_STATUS_CHANGED;
  359. }
  360. _power_flags = flags;
  361. }
  362. #endif // HAL_USE_ADC