mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
AP_HAL_ChibiOS: make all semaphores recursive
the cost is very similar and this prevents an easy coding error which can occur on less used code paths
This commit is contained in:
parent
cf8becfa71
commit
982cff0695
@ -13,7 +13,6 @@ namespace ChibiOS {
|
||||
class RCOutput;
|
||||
class Scheduler;
|
||||
class Semaphore;
|
||||
class Semaphore_Recursive;
|
||||
class SPIBus;
|
||||
class SPIDesc;
|
||||
class SPIDevice;
|
||||
|
@ -76,77 +76,4 @@ void Semaphore::assert_owner(void)
|
||||
osalDbgAssert(check_owner(), "owner");
|
||||
}
|
||||
|
||||
// constructor
|
||||
Semaphore_Recursive::Semaphore_Recursive()
|
||||
: Semaphore(), count(0)
|
||||
{}
|
||||
|
||||
|
||||
bool Semaphore_Recursive::give()
|
||||
{
|
||||
chSysLock();
|
||||
mutex_t *mtx = (mutex_t *)_lock;
|
||||
osalDbgAssert(count>0, "recursive semaphore");
|
||||
if (count != 0) {
|
||||
count--;
|
||||
if (count == 0) {
|
||||
// this thread is giving it up
|
||||
chMtxUnlockS(mtx);
|
||||
// we may need to re-schedule if our priority was increased due to
|
||||
// priority inheritance
|
||||
chSchRescheduleS();
|
||||
}
|
||||
}
|
||||
chSysUnlock();
|
||||
return true;
|
||||
}
|
||||
|
||||
bool Semaphore_Recursive::take(uint32_t timeout_ms)
|
||||
{
|
||||
// most common case is we can get the lock immediately
|
||||
if (Semaphore::take_nonblocking()) {
|
||||
count=1;
|
||||
return true;
|
||||
}
|
||||
|
||||
// check for case where we hold it already
|
||||
chSysLock();
|
||||
mutex_t *mtx = (mutex_t *)_lock;
|
||||
if (mtx->owner == chThdGetSelfX()) {
|
||||
count++;
|
||||
chSysUnlock();
|
||||
return true;
|
||||
}
|
||||
chSysUnlock();
|
||||
if (Semaphore::take(timeout_ms)) {
|
||||
count = 1;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool Semaphore_Recursive::take_nonblocking(void)
|
||||
{
|
||||
// most common case is we can get the lock immediately
|
||||
if (Semaphore::take_nonblocking()) {
|
||||
count=1;
|
||||
return true;
|
||||
}
|
||||
|
||||
// check for case where we hold it already
|
||||
chSysLock();
|
||||
mutex_t *mtx = (mutex_t *)_lock;
|
||||
if (mtx->owner == chThdGetSelfX()) {
|
||||
count++;
|
||||
chSysUnlock();
|
||||
return true;
|
||||
}
|
||||
chSysUnlock();
|
||||
if (Semaphore::take_nonblocking()) {
|
||||
count = 1;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // CH_CFG_USE_MUTEXES
|
||||
|
@ -34,18 +34,6 @@ public:
|
||||
void assert_owner(void);
|
||||
protected:
|
||||
// to avoid polluting the global namespace with the 'ch' variable,
|
||||
// we declare the lock as a uint64_t, and cast inside the cpp file
|
||||
uint64_t _lock[2];
|
||||
};
|
||||
|
||||
// a recursive semaphore, allowing for a thread to take it more than
|
||||
// once. It must be released the same number of times it is taken
|
||||
class ChibiOS::Semaphore_Recursive : public ChibiOS::Semaphore {
|
||||
public:
|
||||
Semaphore_Recursive();
|
||||
bool give() override;
|
||||
bool take(uint32_t timeout_ms) override;
|
||||
bool take_nonblocking() override;
|
||||
private:
|
||||
uint32_t count;
|
||||
// we declare the lock as a uint32_t array, and cast inside the cpp file
|
||||
uint32_t _lock[5];
|
||||
};
|
||||
|
@ -159,7 +159,7 @@ private:
|
||||
#endif
|
||||
ByteBuffer _readbuf{0};
|
||||
ByteBuffer _writebuf{0};
|
||||
HAL_Semaphore_Recursive _write_mutex;
|
||||
HAL_Semaphore _write_mutex;
|
||||
#ifndef HAL_UART_NODMA
|
||||
const stm32_dma_stream_t* rxdma;
|
||||
const stm32_dma_stream_t* txdma;
|
||||
|
@ -266,7 +266,7 @@
|
||||
* @note Requires @p CH_CFG_USE_MUTEXES.
|
||||
*/
|
||||
#if !defined(CH_CFG_USE_MUTEXES_RECURSIVE)
|
||||
#define CH_CFG_USE_MUTEXES_RECURSIVE FALSE
|
||||
#define CH_CFG_USE_MUTEXES_RECURSIVE TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
Loading…
Reference in New Issue
Block a user