APM:Libraries
|
#include <Semaphores.h>
Public Member Functions | |
Semaphore () | |
bool | give () |
bool | take (uint32_t timeout_ms) |
bool | take_nonblocking () |
bool | check_owner (void) |
void | assert_owner (void) |
Public Member Functions inherited from AP_HAL::Semaphore | |
virtual void | take_blocking () |
virtual | ~Semaphore (void) |
Private Attributes | |
mutex_t | _lock |
Definition at line 24 of file Semaphores.h.
|
inline |
|
inline |
Definition at line 41 of file Semaphores.h.
Referenced by ChibiOS::SPIDevice::acquire_bus(), ChibiOS::SPIDevice::clock_pulse(), and ChibiOS::SPIDevice::transfer_fullduplex().
|
inline |
Definition at line 34 of file Semaphores.h.
Referenced by assert_owner(), ChibiOS::I2CDevice::transfer(), and ChibiOS::SPIDevice::transfer().
|
virtual |
Implements AP_HAL::Semaphore.
Definition at line 26 of file Semaphores.cpp.
Referenced by ChibiOS::UARTDriver::_timer_tick(), ChibiOS::RCInput::_timer_tick(), ChibiOS::DeviceBus::bus_thread(), ChibiOS::SPIDevice::clock_pulse(), ChibiOS::RCInput::new_input(), ChibiOS::RCInput::read(), Semaphore(), ChibiOS::UARTDriver::write(), and ChibiOS::UARTDriver::write_locked().
|
virtual |
Implements AP_HAL::Semaphore.
Definition at line 32 of file Semaphores.cpp.
Referenced by ChibiOS::UARTDriver::_timer_tick(), ChibiOS::RCInput::_timer_tick(), ChibiOS::DeviceBus::bus_thread(), ChibiOS::SPIDevice::clock_pulse(), ChibiOS::RCInput::read(), and Semaphore().
|
virtual |
Implements AP_HAL::Semaphore.
Definition at line 51 of file Semaphores.cpp.
Referenced by ChibiOS::RCInput::new_input(), Semaphore(), take(), ChibiOS::UARTDriver::write(), and ChibiOS::UARTDriver::write_locked().
|
private |
Definition at line 45 of file Semaphores.h.
Referenced by check_owner(), give(), Semaphore(), take(), and take_nonblocking().