|
|
|
@ -391,7 +391,7 @@ int VRBRAINUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
@@ -391,7 +391,7 @@ int VRBRAINUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
|
|
|
|
|
_last_write_time != 0 && |
|
|
|
|
_total_written != 0 && |
|
|
|
|
_os_write_buffer_size == _total_written && |
|
|
|
|
hrt_elapsed_time(&_last_write_time) > 500*1000UL) { |
|
|
|
|
(hal.scheduler->micros64() - _last_write_time) > 500*1000UL) { |
|
|
|
|
// it doesn't look like hw flow control is working
|
|
|
|
|
::printf("disabling flow control on %s _total_written=%u\n",
|
|
|
|
|
_devpath, (unsigned)_total_written); |
|
|
|
@ -407,17 +407,17 @@ int VRBRAINUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
@@ -407,17 +407,17 @@ int VRBRAINUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
|
|
|
|
|
|
|
|
|
|
if (ret > 0) { |
|
|
|
|
BUF_ADVANCEHEAD(_writebuf, ret); |
|
|
|
|
_last_write_time = hrt_absolute_time(); |
|
|
|
|
_last_write_time = hal.scheduler->micros64(); |
|
|
|
|
_total_written += ret; |
|
|
|
|
return ret; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (hrt_absolute_time() - _last_write_time > 2000 && |
|
|
|
|
if (hal.scheduler->micros64() - _last_write_time > 2000 && |
|
|
|
|
_flow_control == FLOW_CONTROL_DISABLE) { |
|
|
|
|
#if 0 |
|
|
|
|
// this trick is disabled for now, as it sometimes blocks on
|
|
|
|
|
// re-opening the ttyACM0 port, which would cause a crash
|
|
|
|
|
if (hrt_absolute_time() - _last_write_time > 2000000) { |
|
|
|
|
if (hal.scheduler->micros64() - _last_write_time > 2000000) { |
|
|
|
|
// we haven't done a successful write for 2 seconds - try
|
|
|
|
|
// reopening the port
|
|
|
|
|
_initialised = false; |
|
|
|
@ -430,11 +430,11 @@ int VRBRAINUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
@@ -430,11 +430,11 @@ int VRBRAINUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
|
|
|
|
|
return n; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
_last_write_time = hrt_absolute_time(); |
|
|
|
|
_last_write_time = hal.scheduler->micros64(); |
|
|
|
|
_initialised = true; |
|
|
|
|
} |
|
|
|
|
#else |
|
|
|
|
_last_write_time = hrt_absolute_time(); |
|
|
|
|
_last_write_time = hal.scheduler->micros64(); |
|
|
|
|
#endif |
|
|
|
|
// we haven't done a successful write for 2ms, which means the
|
|
|
|
|
// port is running at less than 500 bytes/sec. Start
|
|
|
|
|