AP_SerialManager: removed set_blocking_writes_all

This commit is contained in:
Andrew Tridgell 2023-07-07 18:46:52 +10:00
parent 36528cae57
commit a6055033ab
2 changed files with 0 additions and 15 deletions

View File

@ -649,18 +649,6 @@ AP_HAL::UARTDriver *AP_SerialManager::get_serial_by_id(uint8_t id)
return nullptr;
}
// set_blocking_writes_all - sets block_writes on or off for all serial channels
void AP_SerialManager::set_blocking_writes_all(bool blocking)
{
// set block_writes for all initialised serial ports
for (uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) {
auto *uart = hal.serial(i);
if (uart != nullptr) {
uart->set_blocking_writes(blocking);
}
}
}
/*
* map from a 16 bit EEPROM baud rate to a real baud rate. For
* stm32-based boards we can do 1.5MBit, although 921600 is more

View File

@ -201,9 +201,6 @@ public:
// find_portnum - find port number (SERIALn index) for a protocol and instance, -1 for not found
int8_t find_portnum(enum SerialProtocol protocol, uint8_t instance) const;
// set_blocking_writes_all - sets block_writes on or off for all serial channels
void set_blocking_writes_all(bool blocking);
// get the passthru ports if enabled
bool get_passthru(AP_HAL::UARTDriver *&port1, AP_HAL::UARTDriver *&port2, uint8_t &timeout_s,
uint32_t &baud1, uint32_t &baud2) const;