shared_dma.h 3.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109
  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. #pragma once
  18. #include "AP_HAL_ChibiOS.h"
  19. #define SHARED_DMA_MAX_STREAM_ID (8*2)
  20. // DMA stream ID for stream_id2 when only one is needed
  21. #define SHARED_DMA_NONE 255
  22. class ChibiOS::Shared_DMA
  23. {
  24. public:
  25. FUNCTOR_TYPEDEF(dma_allocate_fn_t, void, Shared_DMA *);
  26. FUNCTOR_TYPEDEF(dma_deallocate_fn_t, void, Shared_DMA *);
  27. // the use of two stream IDs is for support of peripherals that
  28. // need both a RX and TX DMA channel
  29. Shared_DMA(uint8_t stream_id1, uint8_t stream_id2,
  30. dma_allocate_fn_t allocate,
  31. dma_allocate_fn_t deallocate);
  32. // initialise the stream locks
  33. static void init(void);
  34. // blocking lock call
  35. void lock(void);
  36. // non-blocking lock call
  37. bool lock_nonblock(void);
  38. // unlock call. The DMA channel will not be immediately
  39. // deallocated. Instead it will be deallocated if another driver
  40. // needs it
  41. void unlock(void);
  42. // unlock call from an IRQ
  43. void unlock_from_IRQ(void);
  44. // unlock call from a chSysLock zone
  45. void unlock_from_lockzone(void);
  46. //should be called inside the destructor of Shared DMA participants
  47. void unregister(void);
  48. // return true if this DMA channel is being actively contended for
  49. // by multiple drivers
  50. bool has_contention(void) const { return contention; }
  51. // lock all shared DMA channels. Used on reboot
  52. static void lock_all(void);
  53. private:
  54. dma_allocate_fn_t allocate;
  55. dma_allocate_fn_t deallocate;
  56. uint8_t stream_id1;
  57. uint8_t stream_id2;
  58. bool have_lock;
  59. // we set the contention flag if two drivers are fighting over a DMA channel.
  60. // the UART driver uses this to change its max transmit size to reduce latency
  61. bool contention;
  62. // core of lock call, after semaphores gained
  63. void lock_core(void);
  64. // lock one stream
  65. static void lock_stream(uint8_t stream_id);
  66. // unlock one stream
  67. void unlock_stream(uint8_t stream_id);
  68. // unlock one stream from an IRQ handler
  69. void unlock_stream_from_IRQ(uint8_t stream_id);
  70. // lock one stream, non-blocking
  71. bool lock_stream_nonblocking(uint8_t stream_id);
  72. static struct dma_lock {
  73. // semaphore to ensure only one peripheral uses a DMA channel at a time
  74. #if CH_CFG_USE_SEMAPHORES == TRUE
  75. binary_semaphore_t semaphore;
  76. #endif // CH_CFG_USE_SEMAPHORES
  77. // a de-allocation function that is called to release an existing user
  78. dma_deallocate_fn_t deallocate;
  79. // point to object that holds the allocation, if allocated
  80. Shared_DMA *obj;
  81. } locks[SHARED_DMA_MAX_STREAM_ID+1];
  82. };