mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SMACCM: Update to new semaphore interface.
- Renamed files to match AVR HAL.
This commit is contained in:
parent
155fca8a4b
commit
578c4859e4
|
@ -15,7 +15,7 @@
|
|||
#include "GPIO.h"
|
||||
#include "RCInput.h"
|
||||
#include "RCOutput.h"
|
||||
#include "Semaphore.h"
|
||||
#include "Semaphores.h"
|
||||
#include "Scheduler.h"
|
||||
#include "Util.h"
|
||||
#include "PrivateMember.h"
|
||||
|
|
|
@ -24,6 +24,7 @@ SMACCMSPIDeviceDriver::SMACCMSPIDeviceDriver(spi_bus *bus, spi_device *device)
|
|||
|
||||
void SMACCMSPIDeviceDriver::init()
|
||||
{
|
||||
_semaphore.init();
|
||||
}
|
||||
|
||||
AP_HAL::Semaphore* SMACCMSPIDeviceDriver::get_semaphore()
|
||||
|
@ -88,6 +89,7 @@ void SMACCMSPIDeviceManager::init(void *)
|
|||
spi_init(spi1);
|
||||
|
||||
spi_device_init(&g_mpu6000_spi_dev);
|
||||
g_mpu6000_dev.init();
|
||||
}
|
||||
|
||||
AP_HAL::SPIDeviceDriver* SMACCMSPIDeviceManager::device(AP_HAL::SPIDevice dev)
|
||||
|
|
|
@ -12,7 +12,7 @@
|
|||
#define __AP_HAL_SMACCM_SPIDRIVER_H__
|
||||
|
||||
#include <AP_HAL_SMACCM.h>
|
||||
#include "Semaphore.h"
|
||||
#include "Semaphores.h"
|
||||
|
||||
#include <hwf4/spi.h>
|
||||
|
||||
|
|
|
@ -1,40 +0,0 @@
|
|||
|
||||
#include "Semaphore.h"
|
||||
|
||||
using namespace SMACCM;
|
||||
|
||||
SMACCMSemaphore::SMACCMSemaphore() :
|
||||
_owner(NULL),
|
||||
_k(NULL)
|
||||
{}
|
||||
|
||||
|
||||
bool SMACCMSemaphore::get(void* owner) {
|
||||
if (_owner == NULL) {
|
||||
_owner = owner;
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
bool SMACCMSemaphore::release(void* owner) {
|
||||
if (_owner == NULL || _owner != owner) {
|
||||
return false;
|
||||
} else {
|
||||
_owner = NULL;
|
||||
if (_k){
|
||||
_k();
|
||||
_k = NULL;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
bool SMACCMSemaphore::call_on_release(void* caller, AP_HAL::Proc k) {
|
||||
/* idk what semantics randy was looking for here, honestly.
|
||||
* seems like a bad idea. */
|
||||
_k = k;
|
||||
return true;
|
||||
}
|
||||
|
|
@ -1,22 +0,0 @@
|
|||
|
||||
#ifndef __AP_HAL_SMACCM_SEMAPHORE_H__
|
||||
#define __AP_HAL_SMACCM_SEMAPHORE_H__
|
||||
|
||||
#include <AP_HAL_SMACCM.h>
|
||||
|
||||
class SMACCM::SMACCMSemaphore : public AP_HAL::Semaphore {
|
||||
public:
|
||||
SMACCMSemaphore();
|
||||
// get - to claim ownership of the semaphore
|
||||
bool get(void* owner);
|
||||
// release - to give up ownership of the semaphore
|
||||
bool release(void* owner);
|
||||
// call_on_release - returns true if caller successfully added to the
|
||||
// queue to be called back
|
||||
bool call_on_release(void* caller, AP_HAL::Proc k);
|
||||
private:
|
||||
void* _owner;
|
||||
AP_HAL::Proc _k;
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_SMACCM_SEMAPHORE_H__
|
|
@ -0,0 +1,36 @@
|
|||
|
||||
#include "Semaphores.h"
|
||||
|
||||
using namespace SMACCM;
|
||||
|
||||
SMACCMSemaphore::SMACCMSemaphore()
|
||||
: m_semaphore(NULL)
|
||||
{
|
||||
}
|
||||
|
||||
void SMACCMSemaphore::init()
|
||||
{
|
||||
m_semaphore = xSemaphoreCreateMutex();
|
||||
}
|
||||
|
||||
bool SMACCMSemaphore::take(uint32_t timeout_ms)
|
||||
{
|
||||
portTickType delay;
|
||||
|
||||
if (timeout_ms == HAL_SEMAPHORE_BLOCK_FOREVER)
|
||||
delay = portMAX_DELAY;
|
||||
else
|
||||
delay = timeout_ms / portTICK_RATE_MS;
|
||||
|
||||
return xSemaphoreTake(m_semaphore, delay);
|
||||
}
|
||||
|
||||
bool SMACCMSemaphore::take_nonblocking()
|
||||
{
|
||||
return xSemaphoreTake(m_semaphore, 0);
|
||||
}
|
||||
|
||||
bool SMACCMSemaphore::give()
|
||||
{
|
||||
return xSemaphoreGive(m_semaphore);
|
||||
}
|
|
@ -0,0 +1,22 @@
|
|||
|
||||
#ifndef __AP_HAL_SMACCM_SEMAPHORE_H__
|
||||
#define __AP_HAL_SMACCM_SEMAPHORE_H__
|
||||
|
||||
#include <AP_HAL_SMACCM.h>
|
||||
#include <FreeRTOS.h>
|
||||
#include <semphr.h>
|
||||
|
||||
class SMACCM::SMACCMSemaphore : public AP_HAL::Semaphore {
|
||||
public:
|
||||
SMACCMSemaphore();
|
||||
|
||||
void init();
|
||||
virtual bool take(uint32_t timeout_ms);
|
||||
virtual bool take_nonblocking();
|
||||
virtual bool give();
|
||||
|
||||
private:
|
||||
xSemaphoreHandle m_semaphore;
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_SMACCM_SEMAPHORE_H__
|
Loading…
Reference in New Issue