AP_HAL_PX4: UARTDriver: remove commented out code

This is not working and there's no reason to keep it around.
This commit is contained in:
Lucas De Marchi 2016-10-05 13:12:11 -03:00
parent ec4d1eefca
commit a3140df24a

View File

@ -361,28 +361,7 @@ int PX4UARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
if (AP_HAL::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 (AP_HAL::micros64() - _last_write_time > 2000000) {
// we haven't done a successful write for 2 seconds - try
// reopening the port
_initialised = false;
::close(_fd);
_fd = ::open(_devpath, O_RDWR);
if (_fd == -1) {
fprintf(stdout, "Failed to reopen UART device %s - %s\n",
_devpath, strerror(errno));
// leave it uninitialised
return n;
}
_last_write_time = AP_HAL::micros64();
_initialised = true;
}
#else
_last_write_time = AP_HAL::micros64();
#endif
// we haven't done a successful write for 2ms, which means the
// port is running at less than 500 bytes/sec. Start