mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Semaphore: switch to SREG = oldSREG pattern for interrupt mask/restore
This commit is contained in:
parent
da6f6f3e41
commit
d6d7e2674f
@ -22,13 +22,14 @@ AP_Semaphore::AP_Semaphore()
|
|||||||
bool AP_Semaphore::get(void* caller)
|
bool AP_Semaphore::get(void* caller)
|
||||||
{
|
{
|
||||||
bool result = false;
|
bool result = false;
|
||||||
|
uint8_t oldSREG = SREG;
|
||||||
cli();
|
cli();
|
||||||
if( !_taken ) {
|
if( !_taken ) {
|
||||||
_taken = true;
|
_taken = true;
|
||||||
_owner = caller;
|
_owner = caller;
|
||||||
result = true;
|
result = true;
|
||||||
}
|
}
|
||||||
sei();
|
SREG = oldSREG;
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -67,12 +68,13 @@ bool AP_Semaphore::release(void* caller)
|
|||||||
bool AP_Semaphore::call_on_release(void* caller, ap_semaphore_callback callback_fn)
|
bool AP_Semaphore::call_on_release(void* caller, ap_semaphore_callback callback_fn)
|
||||||
{
|
{
|
||||||
bool result = false;
|
bool result = false;
|
||||||
|
uint8_t oldSREG = SREG;
|
||||||
cli();
|
cli();
|
||||||
if( _waiting_owner == NULL ) {
|
if( _waiting_owner == NULL ) {
|
||||||
_waiting_owner = caller;
|
_waiting_owner = caller;
|
||||||
_waiting_callback = callback_fn;
|
_waiting_callback = callback_fn;
|
||||||
result = true;
|
result = true;
|
||||||
}
|
}
|
||||||
sei();
|
SREG = oldSREG;
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user