SoftSigReader.cpp 4.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115
  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 "SoftSigReader.h"
  18. #include "hwdef/common/stm32_util.h"
  19. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  20. using namespace ChibiOS;
  21. extern const AP_HAL::HAL& hal;
  22. #if HAL_USE_ICU == TRUE
  23. bool SoftSigReader::attach_capture_timer(ICUDriver* icu_drv, icuchannel_t chan, uint8_t dma_stream, uint32_t dma_channel)
  24. {
  25. if (chan > ICU_CHANNEL_2) {
  26. return false;
  27. }
  28. signal = (uint32_t*)hal.util->malloc_type(sizeof(uint32_t)*SOFTSIG_BOUNCE_BUF_SIZE, AP_HAL::Util::MEM_DMA_SAFE);
  29. if (signal == nullptr) {
  30. return false;
  31. }
  32. _icu_drv = icu_drv;
  33. //Setup Burst transfer of period and width measurement
  34. osalDbgAssert(dma == nullptr, "double DMA allocation");
  35. chSysLock();
  36. dma = dmaStreamAllocI(dma_stream,
  37. 12, //IRQ Priority
  38. (stm32_dmaisr_t)_irq_handler,
  39. (void *)this);
  40. osalDbgAssert(dma, "stream allocation failed");
  41. chSysUnlock();
  42. #if STM32_DMA_SUPPORTS_DMAMUX
  43. dmaSetRequestSource(dma, dma_channel);
  44. #endif
  45. //setup address for full word transfer from Timer
  46. dmaStreamSetPeripheral(dma, &icu_drv->tim->DMAR);
  47. dmamode = STM32_DMA_CR_DMEIE | STM32_DMA_CR_TEIE;
  48. dmamode |= STM32_DMA_CR_CHSEL(dma_channel);
  49. dmamode |= STM32_DMA_CR_PL(0);
  50. dmamode |= STM32_DMA_CR_DIR_P2M | STM32_DMA_CR_PSIZE_WORD |
  51. STM32_DMA_CR_MSIZE_WORD | STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE;
  52. dmaStreamSetMemory0(dma, signal);
  53. dmaStreamSetTransactionSize(dma, SOFTSIG_BOUNCE_BUF_SIZE);
  54. dmaStreamSetMode(dma, dmamode);
  55. icucfg.frequency = INPUT_CAPTURE_FREQUENCY;
  56. icucfg.channel = chan;
  57. icucfg.width_cb = NULL;
  58. icucfg.period_cb = NULL;
  59. icucfg.overflow_cb = NULL;
  60. if (chan == ICU_CHANNEL_1) {
  61. icucfg.dier = STM32_TIM_DIER_CC1DE;
  62. icucfg.mode = ICU_INPUT_ACTIVE_HIGH;
  63. need_swap = true;
  64. } else {
  65. icucfg.mode = ICU_INPUT_ACTIVE_LOW;
  66. icucfg.dier = STM32_TIM_DIER_CC2DE;
  67. }
  68. #ifdef HAL_RCIN_IS_INVERTED
  69. icucfg.mode = (icucfg.mode==ICU_INPUT_ACTIVE_LOW)?ICU_INPUT_ACTIVE_HIGH:ICU_INPUT_ACTIVE_LOW;
  70. #endif
  71. icuStart(_icu_drv, &icucfg);
  72. //Extended Timer Setup to enable DMA transfer
  73. //selected offset for TIM_CCR1 and for two words
  74. _icu_drv->tim->DCR = STM32_TIM_DCR_DBA(0x0D) | STM32_TIM_DCR_DBL(1);
  75. //Enable DMA
  76. dmaStreamEnable(dma);
  77. //sets input filtering to 4 timer clock
  78. stm32_timer_set_input_filter(_icu_drv->tim, chan, 2);
  79. //Start Timer
  80. icuStartCapture(_icu_drv);
  81. return true;
  82. }
  83. void SoftSigReader::_irq_handler(void* self, uint32_t flags)
  84. {
  85. SoftSigReader* sig_reader = (SoftSigReader*)self;
  86. // we need to restart the DMA as quickly as possible to prevent losing pulses, so we
  87. // make a fixed length copy to a 2nd buffer. On the F100 this reduces the time with DMA
  88. // disabled from 20us to under 1us
  89. stm32_cacheBufferInvalidate(sig_reader->signal, SOFTSIG_BOUNCE_BUF_SIZE*4);
  90. memcpy(sig_reader->signal2, sig_reader->signal, SOFTSIG_BOUNCE_BUF_SIZE*4);
  91. //restart the DMA transfers
  92. dmaStreamDisable(sig_reader->dma);
  93. dmaStreamSetPeripheral(sig_reader->dma, &sig_reader->_icu_drv->tim->DMAR);
  94. dmaStreamSetMemory0(sig_reader->dma, sig_reader->signal);
  95. dmaStreamSetTransactionSize(sig_reader->dma, SOFTSIG_BOUNCE_BUF_SIZE);
  96. dmaStreamSetMode(sig_reader->dma, sig_reader->dmamode);
  97. dmaStreamEnable(sig_reader->dma);
  98. sig_reader->sigbuf.push((const pulse_t *)sig_reader->signal2, SOFTSIG_BOUNCE_BUF_SIZE/2);
  99. }
  100. #endif // HAL_USE_ICU
  101. #endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS