ardupilot/libraries/AP_HAL/EventHandle.cpp

34 lines
636 B
C++
Raw Normal View History

2020-05-31 09:09:21 -03:00
#include "EventHandle.h"
#include <AP_HAL/AP_HAL.h>
bool AP_HAL::EventHandle::register_event(uint32_t evt_mask)
{
WITH_SEMAPHORE(sem);
evt_mask_ |= evt_mask;
return true;
}
bool AP_HAL::EventHandle::unregister_event(uint32_t evt_mask)
{
WITH_SEMAPHORE(sem);
evt_mask_ &= ~evt_mask;
return true;
}
bool AP_HAL::EventHandle::wait(uint16_t duration_us)
2020-05-31 09:09:21 -03:00
{
if (evt_src_ == nullptr) {
return false;
}
return evt_src_->wait(duration_us, this);
2020-05-31 09:09:21 -03:00
}
bool AP_HAL::EventHandle::set_source(AP_HAL::EventSource* src)
{
WITH_SEMAPHORE(sem);
evt_src_ = src;
evt_mask_ = 0;
return true;
}