mirror of https://github.com/ArduPilot/ardupilot
AP_NMEA_Output: use a fixed maximum number of NMEA outputs
this improves ccache performance
This commit is contained in:
parent
ad88f3e1e8
commit
ada6554578
|
@ -27,6 +27,10 @@
|
||||||
|
|
||||||
#if HAL_NMEA_OUTPUT_ENABLED
|
#if HAL_NMEA_OUTPUT_ENABLED
|
||||||
|
|
||||||
|
#ifndef NMEA_MAX_OUTPUTS
|
||||||
|
#define NMEA_MAX_OUTPUTS 3
|
||||||
|
#endif
|
||||||
|
|
||||||
#include <AP_SerialManager/AP_SerialManager.h>
|
#include <AP_SerialManager/AP_SerialManager.h>
|
||||||
|
|
||||||
class AP_NMEA_Output {
|
class AP_NMEA_Output {
|
||||||
|
@ -45,7 +49,7 @@ private:
|
||||||
uint8_t _nmea_checksum(const char *str);
|
uint8_t _nmea_checksum(const char *str);
|
||||||
|
|
||||||
uint8_t _num_outputs;
|
uint8_t _num_outputs;
|
||||||
AP_HAL::UARTDriver* _uart[SERIALMANAGER_NUM_PORTS];
|
AP_HAL::UARTDriver* _uart[NMEA_MAX_OUTPUTS];
|
||||||
|
|
||||||
uint32_t _last_run_ms;
|
uint32_t _last_run_ms;
|
||||||
};
|
};
|
||||||
|
|
Loading…
Reference in New Issue