mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Empty: add HAL_UART_STATS_ENABLED to disable stats gathering
This commit is contained in:
parent
875f9a9497
commit
cea57f51c1
|
@ -30,7 +30,9 @@ size_t Empty::UARTDriver::write(const uint8_t *buffer, size_t size)
|
|||
return n;
|
||||
}
|
||||
|
||||
#if HAL_UART_STATS_ENABLED
|
||||
void Empty::UARTDriver::uart_info(ExpandingString &str)
|
||||
{
|
||||
str.printf("EMPTY\n");
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -24,6 +24,8 @@ public:
|
|||
size_t write(uint8_t c) override;
|
||||
size_t write(const uint8_t *buffer, size_t size) override;
|
||||
|
||||
#if HAL_UART_STATS_ENABLED
|
||||
// request information on uart I/O for one uart
|
||||
void uart_info(ExpandingString &str) override;
|
||||
#endif
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue