APM:Libraries
libraries
AP_HAL_VRBRAIN
Semaphores.cpp
Go to the documentation of this file.
1
#include <
AP_HAL/AP_HAL.h
>
2
3
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
4
5
#include "
Semaphores.h
"
6
#include <nuttx/arch.h>
7
8
extern
const
AP_HAL::HAL
&
hal
;
9
10
using namespace
VRBRAIN
;
11
12
bool
Semaphore::give
()
13
{
14
return
pthread_mutex_unlock(&
_lock
) == 0;
15
}
16
17
bool
Semaphore::take
(uint32_t timeout_ms)
18
{
19
if
(up_interrupt_context()) {
20
// don't ever wait on a semaphore in interrupt context
21
return
take_nonblocking
();
22
}
23
if
(timeout_ms ==
HAL_SEMAPHORE_BLOCK_FOREVER
) {
24
return
pthread_mutex_lock(&
_lock
) == 0;
25
}
26
if
(
take_nonblocking
()) {
27
return
true
;
28
}
29
uint64_t start =
AP_HAL::micros64
();
30
do
{
31
hal.
scheduler
->
delay_microseconds
(200);
32
if
(
take_nonblocking
()) {
33
return
true
;
34
}
35
}
while
((
AP_HAL::micros64
() - start) < timeout_ms*1000);
36
return
false
;
37
}
38
39
bool
Semaphore::take_nonblocking
()
40
{
41
return
pthread_mutex_trylock(&
_lock
) == 0;
42
}
43
44
#endif // CONFIG_HAL_BOARD
hal
const AP_HAL::HAL & hal
Definition:
AC_PID_test.cpp:14
AP_HAL.h
HAL_SEMAPHORE_BLOCK_FOREVER
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition:
Semaphores.h:5
Semaphores.h
VRBRAIN::Semaphore::take
bool take(uint32_t timeout_ms)
Definition:
Semaphores.cpp:17
AP_HAL::HAL
Definition:
HAL.h:26
VRBRAIN::Semaphore::give
bool give()
Definition:
Semaphores.cpp:12
AP_HAL::micros64
uint64_t micros64()
Definition:
system.cpp:162
VRBRAIN
Definition:
AP_HAL_VRBRAIN_Namespace.h:3
AP_HAL::Scheduler::delay_microseconds
virtual void delay_microseconds(uint16_t us)=0
VRBRAIN::Semaphore::take_nonblocking
bool take_nonblocking()
Definition:
Semaphores.cpp:39
AP_HAL::HAL::scheduler
AP_HAL::Scheduler * scheduler
Definition:
HAL.h:114
VRBRAIN::Semaphore::_lock
pthread_mutex_t _lock
Definition:
Semaphores.h:18
Generated on Sun Jun 17 2018 14:18:48 for APM:Libraries by
1.8.13