2012-11-28 21:53:15 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2013-01-03 21:32:36 -04:00
|
|
|
|
|
|
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
|
|
|
|
|
|
|
#include <avr/io.h>
|
|
|
|
#include <avr/interrupt.h>
|
2012-11-28 21:53:15 -04:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include "AP_HAL_AVR.h"
|
2013-01-02 03:22:07 -04:00
|
|
|
#include "Semaphores.h"
|
2013-01-02 20:32:37 -04:00
|
|
|
#include "Scheduler.h"
|
2012-11-28 21:53:15 -04:00
|
|
|
using namespace AP_HAL_AVR;
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
// Constructor
|
2013-01-02 20:32:37 -04:00
|
|
|
AVRSemaphore::AVRSemaphore() : _taken(false) {}
|
2012-11-28 21:53:15 -04:00
|
|
|
|
2013-01-02 20:32:37 -04:00
|
|
|
bool AVRSemaphore::give() {
|
|
|
|
if (!_taken) {
|
|
|
|
return false;
|
|
|
|
} else {
|
|
|
|
_taken = false;
|
|
|
|
return true;
|
2012-11-28 21:53:15 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2013-01-02 20:32:37 -04:00
|
|
|
bool AVRSemaphore::take(uint32_t timeout_ms) {
|
2013-01-10 17:50:23 -04:00
|
|
|
if (hal.scheduler->in_timerprocess()) {
|
2013-01-02 20:32:37 -04:00
|
|
|
hal.scheduler->panic(PSTR("PANIC: AVRSemaphore::take used from "
|
|
|
|
"inside timer process"));
|
|
|
|
return false; /* Never reached - panic does not return */
|
2012-11-28 21:53:15 -04:00
|
|
|
}
|
2013-01-02 20:32:37 -04:00
|
|
|
return _take_from_mainloop(timeout_ms);
|
|
|
|
}
|
2012-11-28 21:53:15 -04:00
|
|
|
|
2013-01-02 20:32:37 -04:00
|
|
|
bool AVRSemaphore::take_nonblocking() {
|
2013-01-10 17:50:23 -04:00
|
|
|
if (hal.scheduler->in_timerprocess()) {
|
2013-01-02 20:32:37 -04:00
|
|
|
return _take_nonblocking();
|
|
|
|
} else {
|
|
|
|
return _take_from_mainloop(0);
|
|
|
|
}
|
|
|
|
}
|
2012-11-28 21:53:15 -04:00
|
|
|
|
2013-01-02 20:32:37 -04:00
|
|
|
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;
|
2012-11-28 21:53:15 -04:00
|
|
|
}
|
|
|
|
|
2013-10-08 08:06:11 -03:00
|
|
|
uint16_t timeout_ticks = timeout_ms*10;
|
2013-01-02 20:32:37 -04:00
|
|
|
do {
|
|
|
|
/* Delay 1ms until we can successfully take, or we timed out */
|
2013-10-08 08:06:11 -03:00
|
|
|
hal.scheduler->delay_microseconds(100);
|
|
|
|
timeout_ticks--;
|
2013-01-02 20:32:37 -04:00
|
|
|
if (_take_nonblocking()) {
|
|
|
|
return true;
|
|
|
|
}
|
2013-10-08 08:06:11 -03:00
|
|
|
} while (timeout_ticks > 0);
|
2013-01-02 20:32:37 -04:00
|
|
|
|
|
|
|
return false;
|
2012-11-28 21:53:15 -04:00
|
|
|
}
|
|
|
|
|
2013-01-02 20:32:37 -04:00
|
|
|
bool AVRSemaphore::_take_nonblocking() {
|
2012-11-28 21:53:15 -04:00
|
|
|
bool result = false;
|
2013-01-03 21:32:36 -04:00
|
|
|
uint8_t sreg = SREG;
|
|
|
|
cli();
|
2013-01-02 20:32:37 -04:00
|
|
|
if (!_taken) {
|
|
|
|
_taken = true;
|
2012-11-28 21:53:15 -04:00
|
|
|
result = true;
|
|
|
|
}
|
2013-01-03 21:32:36 -04:00
|
|
|
SREG = sreg;
|
2012-11-28 21:53:15 -04:00
|
|
|
return result;
|
|
|
|
}
|
2013-01-02 20:32:37 -04:00
|
|
|
|
2013-01-03 21:32:36 -04:00
|
|
|
#endif // CONFIG_HAL_BOARD
|