Browse Source

AP_HAL_ChibiOS: add HAL_UART_STATS_ENABLED to disable stats gathering

gps-1.3.1
Peter Barker 3 years ago committed by Andrew Tridgell
parent
commit
875f9a9497
  1. 2
      libraries/AP_HAL_ChibiOS/UARTDriver.cpp
  2. 2
      libraries/AP_HAL_ChibiOS/UARTDriver.h
  3. 4
      libraries/AP_HAL_ChibiOS/Util.cpp
  4. 2
      libraries/AP_HAL_ChibiOS/Util.h

2
libraries/AP_HAL_ChibiOS/UARTDriver.cpp

@ -1745,6 +1745,7 @@ uint16_t UARTDriver::get_options(void) const @@ -1745,6 +1745,7 @@ uint16_t UARTDriver::get_options(void) const
return _last_options;
}
#if HAL_UART_STATS_ENABLED
// request information on uart I/O for @SYS/uarts.txt for this uart
void UARTDriver::uart_info(ExpandingString &str)
{
@ -1765,6 +1766,7 @@ void UARTDriver::uart_info(ExpandingString &str) @@ -1765,6 +1766,7 @@ void UARTDriver::uart_info(ExpandingString &str)
_rx_stats_bytes = 0;
_last_stats_ms = now_ms;
}
#endif
/*
software control of the CTS pin if available. Return false if

2
libraries/AP_HAL_ChibiOS/UARTDriver.h

@ -141,8 +141,10 @@ public: @@ -141,8 +141,10 @@ public:
return _baudrate/(9*1024);
}
#if HAL_UART_STATS_ENABLED
// request information on uart I/O for one uart
void uart_info(ExpandingString &str) override;
#endif
/*
return true if this UART has DMA enabled on both RX and TX

4
libraries/AP_HAL_ChibiOS/Util.cpp

@ -586,10 +586,10 @@ void Util::apply_persistent_params(void) const @@ -586,10 +586,10 @@ void Util::apply_persistent_params(void) const
extern ChibiOS::UARTDriver uart_io;
#endif
#if HAL_UART_STATS_ENABLED
// request information on uart I/O
void Util::uart_info(ExpandingString &str)
{
#if !defined(HAL_NO_UARTDRIVER)
// a header to allow for machine parsers to determine format
str.printf("UARTV1\n");
for (uint8_t i = 0; i < HAL_UART_NUM_SERIAL_PORTS; i++) {
@ -603,8 +603,8 @@ void Util::uart_info(ExpandingString &str) @@ -603,8 +603,8 @@ void Util::uart_info(ExpandingString &str)
str.printf("IOMCU ");
uart_io.uart_info(str);
#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()

2
libraries/AP_HAL_ChibiOS/Util.h

@ -87,8 +87,10 @@ public: @@ -87,8 +87,10 @@ public:
// save/load key persistent parameters in bootloader sector
bool load_persistent_params(ExpandingString &str) const override;
#endif
#if HAL_UART_STATS_ENABLED
// request information on uart I/O
virtual void uart_info(ExpandingString &str) override;
#endif
// returns random values
bool get_random_vals(uint8_t* data, size_t size) override;

Loading…
Cancel
Save