diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 762d2ff289..3aa3407b7c 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -114,7 +114,6 @@ extern const AP_HAL::HAL& hal; #define SERIAL9_PROTOCOL SerialProtocol_None #endif // HAL_BUILD_AP_PERIPH - const AP_Param::GroupInfo AP_SerialManager::var_info[] = { #if SERIALMANAGER_NUM_PORTS > 0 // @Param: 0_BAUD @@ -807,7 +806,7 @@ void AP_SerialManager::disable_passthru(void) // accessor for AP_Periph to set baudrate and type void AP_SerialManager::set_protocol_and_baud(uint8_t sernum, enum SerialProtocol protocol, uint32_t baudrate) { - if (sernum <= ARRAY_SIZE(state)) { + if (sernum < SERIALMANAGER_NUM_PORTS) { state[sernum].protocol.set(protocol); state[sernum].baud.set(baudrate); } diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index e7c8097ef1..c60be5648a 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -38,6 +38,19 @@ #define SERIALMANAGER_NUM_PORTS 8 #endif +/* + array size for state[]. This needs to be at least + SERIALMANAGER_NUM_PORTS, but we want it to be the same length on + similar boards to get the ccache efficiency up. This wastes a small + amount of memory, but makes a huge difference to the build times + */ +#if SERIALMANAGER_NUM_PORTS > 10 || SERIALMANAGER_NUM_PORTS < 5 +#define SERIALMANAGER_MAX_PORTS SERIALMANAGER_NUM_PORTS +#else +#define SERIALMANAGER_MAX_PORTS 10 +#endif + + // console default baud rates and buffer sizes #ifdef HAL_SERIAL0_BAUD_DEFAULT # define AP_SERIALMANAGER_CONSOLE_BAUD HAL_SERIAL0_BAUD_DEFAULT @@ -223,12 +236,13 @@ public: private: static AP_SerialManager *_singleton; - // array of uart info + // array of uart info. See comment above about + // SERIALMANAGER_MAX_PORTS struct UARTState { - AP_Int8 protocol; AP_Int32 baud; AP_Int16 options; - } state[SERIALMANAGER_NUM_PORTS]; + AP_Int8 protocol; + } state[SERIALMANAGER_MAX_PORTS]; // pass-through serial support AP_Int8 passthru_port1;