HAL_ChibiOS: added support for HAL_Semaphore type

This commit is contained in:
Andrew Tridgell 2018-08-07 16:39:42 +10:00
parent 0a73c3492d
commit dabdb969f6
4 changed files with 56 additions and 26 deletions

View File

@ -16,6 +16,7 @@
*/ */
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include "Semaphores.h" #include "Semaphores.h"
#include "AP_HAL_ChibiOS.h"
#if CH_CFG_USE_MUTEXES == TRUE #if CH_CFG_USE_MUTEXES == TRUE
@ -23,16 +24,28 @@ extern const AP_HAL::HAL& hal;
using namespace ChibiOS; using namespace ChibiOS;
// constructor
Semaphore::Semaphore()
{
static_assert(sizeof(_lock) >= sizeof(mutex_t), "invalid mutex size");
#if CH_CFG_USE_MUTEXES == TRUE
mutex_t *mtx = (mutex_t *)_lock;
chMtxObjectInit(mtx);
#endif
}
bool Semaphore::give() bool Semaphore::give()
{ {
chMtxUnlock(&_lock); mutex_t *mtx = (mutex_t *)_lock;
chMtxUnlock(mtx);
return true; return true;
} }
bool Semaphore::take(uint32_t timeout_ms) bool Semaphore::take(uint32_t timeout_ms)
{ {
mutex_t *mtx = (mutex_t *)_lock;
if (timeout_ms == HAL_SEMAPHORE_BLOCK_FOREVER) { if (timeout_ms == HAL_SEMAPHORE_BLOCK_FOREVER) {
chMtxLock(&_lock); chMtxLock(mtx);
return true; return true;
} }
if (take_nonblocking()) { if (take_nonblocking()) {
@ -50,7 +63,23 @@ bool Semaphore::take(uint32_t timeout_ms)
bool Semaphore::take_nonblocking() bool Semaphore::take_nonblocking()
{ {
return chMtxTryLock(&_lock); mutex_t *mtx = (mutex_t *)_lock;
return chMtxTryLock(mtx);
}
bool Semaphore::check_owner(void)
{
mutex_t *mtx = (mutex_t *)_lock;
#if CH_CFG_USE_MUTEXES == TRUE
return mtx->owner == chThdGetSelfX();
#else
return true;
#endif
}
void Semaphore::assert_owner(void)
{
osalDbgAssert(check_owner(), "owner");
} }
#endif // CH_CFG_USE_MUTEXES #endif // CH_CFG_USE_MUTEXES

View File

@ -16,31 +16,24 @@
*/ */
#pragma once #pragma once
#include <stdint.h>
#include <AP_HAL/AP_HAL_Boards.h> #include <AP_HAL/AP_HAL_Boards.h>
#include <AP_HAL/AP_HAL_Macros.h>
#include "AP_HAL_ChibiOS.h" #include <AP_HAL/Semaphores.h>
#include "AP_HAL_ChibiOS_Namespace.h"
class ChibiOS::Semaphore : public AP_HAL::Semaphore { class ChibiOS::Semaphore : public AP_HAL::Semaphore {
public: public:
Semaphore() { Semaphore();
#if CH_CFG_USE_MUTEXES == TRUE bool give() override;
chMtxObjectInit(&_lock); bool take(uint32_t timeout_ms) override;
#endif bool take_nonblocking() override;
}
bool give(); // methods within HAL_ChibiOS only
bool take(uint32_t timeout_ms); bool check_owner(void);
bool take_nonblocking(); void assert_owner(void);
bool check_owner(void) {
#if CH_CFG_USE_MUTEXES == TRUE
return _lock.owner == chThdGetSelfX();
#else
return true;
#endif
}
void assert_owner(void) {
osalDbgAssert(check_owner(), "owner");
}
private: private:
mutex_t _lock; // 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];
}; };

View File

@ -18,7 +18,7 @@
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include "AP_HAL_ChibiOS_Namespace.h" #include "AP_HAL_ChibiOS_Namespace.h"
#include "Semaphores.h" #include "AP_HAL_ChibiOS.h"
class ChibiOS::Util : public AP_HAL::Util { class ChibiOS::Util : public AP_HAL::Util {
public: public:

View File

@ -39,6 +39,14 @@
*/ */
/*===========================================================================*/ /*===========================================================================*/
#if !defined(FALSE)
#define FALSE 0
#endif
#if !defined(TRUE)
#define TRUE 1
#endif
#ifdef HAL_CHIBIOS_ENABLE_ASSERTS #ifdef HAL_CHIBIOS_ENABLE_ASSERTS
#define CH_DBG_ENABLE_ASSERTS TRUE #define CH_DBG_ENABLE_ASSERTS TRUE
#define CH_DBG_ENABLE_CHECKS TRUE #define CH_DBG_ENABLE_CHECKS TRUE