mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: 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:
parent
d5effcdf92
commit
761297a068
|
@ -587,7 +587,7 @@ bool CANIface::set_event_handle(AP_HAL::EventHandle* handle) {
|
|||
}
|
||||
|
||||
|
||||
bool CANIface::CANSocketEventSource::wait(uint64_t duration, AP_HAL::EventHandle* evt_handle)
|
||||
bool CANIface::CANSocketEventSource::wait(uint16_t duration_us, AP_HAL::EventHandle* evt_handle)
|
||||
{
|
||||
if (evt_handle == nullptr) {
|
||||
return false;
|
||||
|
@ -616,8 +616,8 @@ bool CANIface::CANSocketEventSource::wait(uint64_t duration, AP_HAL::EventHandle
|
|||
|
||||
// Timeout conversion
|
||||
auto ts = timespec();
|
||||
ts.tv_sec = duration / 1000000LL;
|
||||
ts.tv_nsec = (duration % 1000000LL) * 1000;
|
||||
ts.tv_sec = 0;
|
||||
ts.tv_nsec = duration_us * 1000UL;
|
||||
|
||||
// Blocking here
|
||||
const int res = ppoll(pollfds, num_pollfds, &ts, nullptr);
|
||||
|
|
|
@ -132,7 +132,7 @@ public:
|
|||
public:
|
||||
// we just poll fd, no signaling is done
|
||||
void signal(uint32_t evt_mask) override { return; }
|
||||
bool wait(uint64_t duration, AP_HAL::EventHandle* evt_handle) override;
|
||||
bool wait(uint16_t duration_us, AP_HAL::EventHandle* evt_handle) override;
|
||||
};
|
||||
|
||||
private:
|
||||
|
|
Loading…
Reference in New Issue