AP_HAL: change to 16 bit timeout in event interface

prevent issues on 16 bit timers where we can end up with TIME_INFINITE
This commit is contained in:
Andrew Tridgell 2023-04-17 14:34:22 +10:00
parent 86b6f3a2c6
commit d1e50cb0c8
2 changed files with 4 additions and 4 deletions

View File

@ -16,12 +16,12 @@ bool AP_HAL::EventHandle::unregister_event(uint32_t evt_mask)
return true;
}
bool AP_HAL::EventHandle::wait(uint64_t duration)
bool AP_HAL::EventHandle::wait(uint16_t duration_us)
{
if (evt_src_ == nullptr) {
return false;
}
return evt_src_->wait(duration, this);
return evt_src_->wait(duration_us, this);
}
bool AP_HAL::EventHandle::set_source(AP_HAL::EventSource* src)

View File

@ -14,7 +14,7 @@ public:
// Wait on an Event handle, method for internal use by EventHandle
virtual bool wait(uint64_t duration, AP_HAL::EventHandle* evt_handle) = 0;
virtual bool wait(uint16_t duration_us, AP_HAL::EventHandle* evt_handle) = 0;
};
class AP_HAL::EventHandle {
@ -31,7 +31,7 @@ public:
virtual bool unregister_event(uint32_t evt_mask);
// return true if event was triggered within the duration
virtual bool wait(uint64_t duration);
virtual bool wait(uint16_t duration_us);
virtual uint32_t get_evt_mask() const { return evt_mask_; }