mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_HAL_AVR: Implements new Semaphore interface
This commit is contained in:
parent
74e2ba2168
commit
0029148b3a
@ -3,68 +3,69 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
#include "Semaphores.h"
|
#include "Semaphores.h"
|
||||||
|
#include "Scheduler.h"
|
||||||
using namespace AP_HAL_AVR;
|
using namespace AP_HAL_AVR;
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
// Constructor
|
// Constructor
|
||||||
AVRSemaphore::AVRSemaphore() {}
|
AVRSemaphore::AVRSemaphore() : _taken(false) {}
|
||||||
|
|
||||||
// get - to claim ownership of the semaphore
|
bool AVRSemaphore::give() {
|
||||||
bool AVRSemaphore::get(void* caller)
|
if (!_taken) {
|
||||||
{
|
return false;
|
||||||
bool result = false;
|
} else {
|
||||||
hal.scheduler->begin_atomic();
|
_taken = false;
|
||||||
if( !_taken ) {
|
return true;
|
||||||
_taken = true;
|
|
||||||
_owner = caller;
|
|
||||||
result = true;
|
|
||||||
}
|
}
|
||||||
hal.scheduler->end_atomic();
|
|
||||||
return result;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// release - to give up ownership of the semaphore
|
bool AVRSemaphore::take(uint32_t timeout_ms) {
|
||||||
// returns true if successfully released
|
if (AVRScheduler::_in_timer_proc) {
|
||||||
bool AVRSemaphore::release(void* caller)
|
hal.scheduler->panic(PSTR("PANIC: AVRSemaphore::take used from "
|
||||||
{
|
"inside timer process"));
|
||||||
|
return false; /* Never reached - panic does not return */
|
||||||
|
}
|
||||||
|
return _take_from_mainloop(timeout_ms);
|
||||||
|
}
|
||||||
|
|
||||||
// check legitimacy of release call
|
bool AVRSemaphore::take_nonblocking() {
|
||||||
if( caller != _owner ) {
|
if (AVRScheduler::_in_timer_proc) {
|
||||||
|
return _take_nonblocking();
|
||||||
|
} else {
|
||||||
|
return _take_from_mainloop(0);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool AVRSemaphore::_take_from_mainloop(uint32_t timeout_ms) {
|
||||||
|
/* Try to take immediately */
|
||||||
|
if (_take_nonblocking()) {
|
||||||
|
return true;
|
||||||
|
} else if (timeout_ms == 0) {
|
||||||
|
/* Return immediately if timeout is 0 */
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// if another process is waiting immediately call the provided kontinuation
|
do {
|
||||||
if( _waiting_k != NULL ) {
|
/* Delay 1ms until we can successfully take, or we timed out */
|
||||||
|
hal.scheduler->delay(1);
|
||||||
|
timeout_ms--;
|
||||||
|
if (_take_nonblocking()) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
} while (timeout_ms > 0);
|
||||||
|
|
||||||
// give ownership to waiting process
|
return false;
|
||||||
_owner = _waiting_owner;
|
|
||||||
AP_HAL::Proc k = _waiting_k;
|
|
||||||
|
|
||||||
// clear waiting process
|
|
||||||
_waiting_k = NULL;
|
|
||||||
_waiting_owner = NULL;
|
|
||||||
|
|
||||||
// callback
|
|
||||||
k();
|
|
||||||
}
|
|
||||||
|
|
||||||
// give up the semaphore
|
|
||||||
_taken = false;
|
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// call_on_release - returns true if caller successfully added to the queue to
|
bool AVRSemaphore::_take_nonblocking() {
|
||||||
// be called back
|
|
||||||
bool AVRSemaphore::call_on_release(void* caller, AP_HAL::Proc k)
|
|
||||||
{
|
|
||||||
bool result = false;
|
bool result = false;
|
||||||
hal.scheduler->begin_atomic();
|
hal.scheduler->begin_atomic();
|
||||||
if( _waiting_owner == NULL ) {
|
if (!_taken) {
|
||||||
_waiting_owner = caller;
|
_taken = true;
|
||||||
_waiting_k = k;
|
|
||||||
result = true;
|
result = true;
|
||||||
}
|
}
|
||||||
hal.scheduler->end_atomic();
|
hal.scheduler->end_atomic();
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1,32 +1,23 @@
|
|||||||
|
|
||||||
#ifndef __AP_HAL_AVR_SEMAPHORE_H__
|
#ifndef __AP_HAL_AVR_SEMAPHORES_H__
|
||||||
#define __AP_HAL_AVR_SEMAPHORE_H__
|
#define __AP_HAL_AVR_SEMAPHORES_H__
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR_Namespace.h>
|
#include <AP_HAL_AVR_Namespace.h>
|
||||||
|
|
||||||
class AP_HAL_AVR::AVRSemaphore : public AP_HAL::Semaphore {
|
class AP_HAL_AVR::AVRSemaphore : public AP_HAL::Semaphore {
|
||||||
public:
|
public:
|
||||||
// Constructor
|
|
||||||
AVRSemaphore();
|
AVRSemaphore();
|
||||||
|
|
||||||
// get - to claim ownership of the semaphore
|
bool give();
|
||||||
bool get(void* caller);
|
bool take(uint32_t timeout_ms);
|
||||||
|
bool take_nonblocking();
|
||||||
// release - to give up ownership of the semaphore
|
|
||||||
bool release(void* caller);
|
|
||||||
|
|
||||||
// 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);
|
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
bool _taken;
|
bool _take_from_mainloop(uint32_t timeout_ms);
|
||||||
void* _owner;
|
bool _take_nonblocking();
|
||||||
void* _waiting_owner;
|
|
||||||
|
|
||||||
// procedure of process waiting for sempahore
|
bool _taken;
|
||||||
AP_HAL::Proc _waiting_k;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_HAL_AVR_SEMAPHORE_H__
|
#endif // __AP_HAL_AVR_SEMAPHORES_H__
|
||||||
|
Loading…
Reference in New Issue
Block a user