mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_HAL_ChibiOS: add HAL_UART_STATS_ENABLED to disable stats gathering
This commit is contained in:
parent
aaf8de88d8
commit
875f9a9497
@ -1745,6 +1745,7 @@ uint16_t UARTDriver::get_options(void) const
|
|||||||
return _last_options;
|
return _last_options;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_UART_STATS_ENABLED
|
||||||
// request information on uart I/O for @SYS/uarts.txt for this uart
|
// request information on uart I/O for @SYS/uarts.txt for this uart
|
||||||
void UARTDriver::uart_info(ExpandingString &str)
|
void UARTDriver::uart_info(ExpandingString &str)
|
||||||
{
|
{
|
||||||
@ -1765,6 +1766,7 @@ void UARTDriver::uart_info(ExpandingString &str)
|
|||||||
_rx_stats_bytes = 0;
|
_rx_stats_bytes = 0;
|
||||||
_last_stats_ms = now_ms;
|
_last_stats_ms = now_ms;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
software control of the CTS pin if available. Return false if
|
software control of the CTS pin if available. Return false if
|
||||||
|
@ -141,8 +141,10 @@ public:
|
|||||||
return _baudrate/(9*1024);
|
return _baudrate/(9*1024);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_UART_STATS_ENABLED
|
||||||
// request information on uart I/O for one uart
|
// request information on uart I/O for one uart
|
||||||
void uart_info(ExpandingString &str) override;
|
void uart_info(ExpandingString &str) override;
|
||||||
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
return true if this UART has DMA enabled on both RX and TX
|
return true if this UART has DMA enabled on both RX and TX
|
||||||
|
@ -586,10 +586,10 @@ void Util::apply_persistent_params(void) const
|
|||||||
extern ChibiOS::UARTDriver uart_io;
|
extern ChibiOS::UARTDriver uart_io;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAL_UART_STATS_ENABLED
|
||||||
// request information on uart I/O
|
// request information on uart I/O
|
||||||
void Util::uart_info(ExpandingString &str)
|
void Util::uart_info(ExpandingString &str)
|
||||||
{
|
{
|
||||||
#if !defined(HAL_NO_UARTDRIVER)
|
|
||||||
// a header to allow for machine parsers to determine format
|
// a header to allow for machine parsers to determine format
|
||||||
str.printf("UARTV1\n");
|
str.printf("UARTV1\n");
|
||||||
for (uint8_t i = 0; i < HAL_UART_NUM_SERIAL_PORTS; i++) {
|
for (uint8_t i = 0; i < HAL_UART_NUM_SERIAL_PORTS; i++) {
|
||||||
@ -603,8 +603,8 @@ void Util::uart_info(ExpandingString &str)
|
|||||||
str.printf("IOMCU ");
|
str.printf("IOMCU ");
|
||||||
uart_io.uart_info(str);
|
uart_io.uart_info(str);
|
||||||
#endif
|
#endif
|
||||||
#endif // HAL_NO_UARTDRIVER
|
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* This method will generate random values with set size. It will fall back to AP_Math's get_random16()
|
* This method will generate random values with set size. It will fall back to AP_Math's get_random16()
|
||||||
|
@ -87,8 +87,10 @@ public:
|
|||||||
// save/load key persistent parameters in bootloader sector
|
// save/load key persistent parameters in bootloader sector
|
||||||
bool load_persistent_params(ExpandingString &str) const override;
|
bool load_persistent_params(ExpandingString &str) const override;
|
||||||
#endif
|
#endif
|
||||||
|
#if HAL_UART_STATS_ENABLED
|
||||||
// request information on uart I/O
|
// request information on uart I/O
|
||||||
virtual void uart_info(ExpandingString &str) override;
|
virtual void uart_info(ExpandingString &str) override;
|
||||||
|
#endif
|
||||||
|
|
||||||
// returns random values
|
// returns random values
|
||||||
bool get_random_vals(uint8_t* data, size_t size) override;
|
bool get_random_vals(uint8_t* data, size_t size) override;
|
||||||
|
Loading…
Reference in New Issue
Block a user