Semaphores.cpp 3.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153
  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 "Semaphores.h"
  19. #include "AP_HAL_ChibiOS.h"
  20. #if CH_CFG_USE_MUTEXES == TRUE
  21. extern const AP_HAL::HAL& hal;
  22. using namespace ChibiOS;
  23. // constructor
  24. Semaphore::Semaphore()
  25. {
  26. static_assert(sizeof(_lock) >= sizeof(mutex_t), "invalid mutex size");
  27. mutex_t *mtx = (mutex_t *)_lock;
  28. chMtxObjectInit(mtx);
  29. }
  30. bool Semaphore::give()
  31. {
  32. mutex_t *mtx = (mutex_t *)_lock;
  33. chMtxUnlock(mtx);
  34. return true;
  35. }
  36. bool Semaphore::take(uint32_t timeout_ms)
  37. {
  38. mutex_t *mtx = (mutex_t *)_lock;
  39. if (timeout_ms == HAL_SEMAPHORE_BLOCK_FOREVER) {
  40. chMtxLock(mtx);
  41. return true;
  42. }
  43. if (take_nonblocking()) {
  44. return true;
  45. }
  46. uint64_t start = AP_HAL::micros64();
  47. do {
  48. hal.scheduler->delay_microseconds(200);
  49. if (take_nonblocking()) {
  50. return true;
  51. }
  52. } while ((AP_HAL::micros64() - start) < timeout_ms*1000);
  53. return false;
  54. }
  55. bool Semaphore::take_nonblocking()
  56. {
  57. mutex_t *mtx = (mutex_t *)_lock;
  58. return chMtxTryLock(mtx);
  59. }
  60. bool Semaphore::check_owner(void)
  61. {
  62. mutex_t *mtx = (mutex_t *)_lock;
  63. return mtx->owner == chThdGetSelfX();
  64. }
  65. void Semaphore::assert_owner(void)
  66. {
  67. osalDbgAssert(check_owner(), "owner");
  68. }
  69. // constructor
  70. Semaphore_Recursive::Semaphore_Recursive()
  71. : Semaphore(), count(0)
  72. {}
  73. bool Semaphore_Recursive::give()
  74. {
  75. chSysLock();
  76. mutex_t *mtx = (mutex_t *)_lock;
  77. osalDbgAssert(count>0, "recursive semaphore");
  78. if (count != 0) {
  79. count--;
  80. if (count == 0) {
  81. // this thread is giving it up
  82. chMtxUnlockS(mtx);
  83. // we may need to re-schedule if our priority was increased due to
  84. // priority inheritance
  85. chSchRescheduleS();
  86. }
  87. }
  88. chSysUnlock();
  89. return true;
  90. }
  91. bool Semaphore_Recursive::take(uint32_t timeout_ms)
  92. {
  93. // most common case is we can get the lock immediately
  94. if (Semaphore::take_nonblocking()) {
  95. count=1;
  96. return true;
  97. }
  98. // check for case where we hold it already
  99. chSysLock();
  100. mutex_t *mtx = (mutex_t *)_lock;
  101. if (mtx->owner == chThdGetSelfX()) {
  102. count++;
  103. chSysUnlock();
  104. return true;
  105. }
  106. chSysUnlock();
  107. if (Semaphore::take(timeout_ms)) {
  108. count = 1;
  109. return true;
  110. }
  111. return false;
  112. }
  113. bool Semaphore_Recursive::take_nonblocking(void)
  114. {
  115. // most common case is we can get the lock immediately
  116. if (Semaphore::take_nonblocking()) {
  117. count=1;
  118. return true;
  119. }
  120. // check for case where we hold it already
  121. chSysLock();
  122. mutex_t *mtx = (mutex_t *)_lock;
  123. if (mtx->owner == chThdGetSelfX()) {
  124. count++;
  125. chSysUnlock();
  126. return true;
  127. }
  128. chSysUnlock();
  129. if (Semaphore::take_nonblocking()) {
  130. count = 1;
  131. return true;
  132. }
  133. return false;
  134. }
  135. #endif // CH_CFG_USE_MUTEXES