Device.cpp 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191
  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. #include "Device.h"
  16. #include <AP_HAL/AP_HAL.h>
  17. #include <AP_HAL/utility/OwnPtr.h>
  18. #include <stdio.h>
  19. #if HAL_USE_I2C == TRUE || HAL_USE_SPI == TRUE
  20. #include "Scheduler.h"
  21. #include "Semaphores.h"
  22. #include "Util.h"
  23. #include "hwdef/common/stm32_util.h"
  24. #ifndef HAL_DEVICE_THREAD_STACK
  25. #define HAL_DEVICE_THREAD_STACK 1024
  26. #endif
  27. using namespace ChibiOS;
  28. static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
  29. DeviceBus::DeviceBus(uint8_t _thread_priority) :
  30. thread_priority(_thread_priority)
  31. {
  32. bouncebuffer_init(&bounce_buffer_tx, 10, false);
  33. bouncebuffer_init(&bounce_buffer_rx, 10, false);
  34. }
  35. /*
  36. per-bus callback thread
  37. */
  38. void DeviceBus::bus_thread(void *arg)
  39. {
  40. struct DeviceBus *binfo = (struct DeviceBus *)arg;
  41. while (true) {
  42. uint64_t now = AP_HAL::micros64();
  43. DeviceBus::callback_info *callback;
  44. // find a callback to run
  45. for (callback = binfo->callbacks; callback; callback = callback->next) {
  46. if (now >= callback->next_usec) {
  47. while (now >= callback->next_usec) {
  48. callback->next_usec += callback->period_usec;
  49. }
  50. // call it with semaphore held
  51. if (binfo->semaphore.take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  52. callback->cb();
  53. binfo->semaphore.give();
  54. }
  55. }
  56. }
  57. // work out when next loop is needed
  58. uint64_t next_needed = 0;
  59. now = AP_HAL::micros64();
  60. for (callback = binfo->callbacks; callback; callback = callback->next) {
  61. if (next_needed == 0 ||
  62. callback->next_usec < next_needed) {
  63. next_needed = callback->next_usec;
  64. if (next_needed < now) {
  65. next_needed = now;
  66. }
  67. }
  68. }
  69. // delay for at most 50ms, to handle newly added callbacks
  70. uint32_t delay = 50000;
  71. if (next_needed >= now && next_needed - now < delay) {
  72. delay = next_needed - now;
  73. }
  74. // don't delay for less than 100usec, so one thread doesn't
  75. // completely dominate the CPU
  76. if (delay < 100) {
  77. delay = 100;
  78. }
  79. hal.scheduler->delay_microseconds(delay);
  80. }
  81. return;
  82. }
  83. #if CH_CFG_USE_HEAP == TRUE
  84. AP_HAL::Device::PeriodicHandle DeviceBus::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb, AP_HAL::Device *_hal_device)
  85. {
  86. if (!thread_started) {
  87. thread_started = true;
  88. hal_device = _hal_device;
  89. // setup a name for the thread
  90. const uint8_t name_len = 7;
  91. char *name = (char *)malloc(name_len);
  92. switch (hal_device->bus_type()) {
  93. case AP_HAL::Device::BUS_TYPE_I2C:
  94. snprintf(name, name_len, "I2C:%u",
  95. hal_device->bus_num());
  96. break;
  97. case AP_HAL::Device::BUS_TYPE_SPI:
  98. snprintf(name, name_len, "SPI:%u",
  99. hal_device->bus_num());
  100. break;
  101. default:
  102. break;
  103. }
  104. thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(HAL_DEVICE_THREAD_STACK),
  105. name,
  106. thread_priority, /* Initial priority. */
  107. DeviceBus::bus_thread, /* Thread function. */
  108. this); /* Thread parameter. */
  109. if (thread_ctx == nullptr) {
  110. AP_HAL::panic("Failed to create bus thread %s", name);
  111. }
  112. }
  113. DeviceBus::callback_info *callback = new DeviceBus::callback_info;
  114. if (callback == nullptr) {
  115. return nullptr;
  116. }
  117. callback->cb = cb;
  118. callback->period_usec = period_usec;
  119. callback->next_usec = AP_HAL::micros64() + period_usec;
  120. // add to linked list of callbacks on thread
  121. callback->next = callbacks;
  122. callbacks = callback;
  123. return callback;
  124. }
  125. #endif // CH_CFG_USE_HEAP
  126. /*
  127. * Adjust the timer for the next call: it needs to be called from the bus
  128. * thread, otherwise it will race with it
  129. */
  130. bool DeviceBus::adjust_timer(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)
  131. {
  132. if (chThdGetSelfX() != thread_ctx) {
  133. return false;
  134. }
  135. DeviceBus::callback_info *callback = static_cast<DeviceBus::callback_info *>(h);
  136. callback->period_usec = period_usec;
  137. callback->next_usec = AP_HAL::micros64() + period_usec;
  138. return true;
  139. }
  140. /*
  141. setup to use DMA-safe bouncebuffers for device transfers
  142. */
  143. void DeviceBus::bouncebuffer_setup(const uint8_t *&buf_tx, uint16_t tx_len,
  144. uint8_t *&buf_rx, uint16_t rx_len)
  145. {
  146. if (buf_rx) {
  147. bouncebuffer_setup_read(bounce_buffer_rx, &buf_rx, rx_len);
  148. }
  149. if (buf_tx) {
  150. bouncebuffer_setup_write(bounce_buffer_tx, &buf_tx, tx_len);
  151. }
  152. }
  153. /*
  154. complete a transfer using DMA bounce buffer
  155. */
  156. void DeviceBus::bouncebuffer_finish(const uint8_t *buf_tx, uint8_t *buf_rx, uint16_t rx_len)
  157. {
  158. if (buf_rx) {
  159. bouncebuffer_finish_read(bounce_buffer_rx, buf_rx, rx_len);
  160. }
  161. if (buf_tx) {
  162. bouncebuffer_finish_write(bounce_buffer_tx, buf_tx);
  163. }
  164. }
  165. #endif // HAL_USE_I2C || HAL_USE_SPI