diff --git a/libraries/AP_HAL/HAL.cpp b/libraries/AP_HAL/HAL.cpp index a2d1216d2b389..92fa3588e698f 100644 --- a/libraries/AP_HAL/HAL.cpp +++ b/libraries/AP_HAL/HAL.cpp @@ -15,7 +15,6 @@ HAL::FunCallbacks::FunCallbacks(void (*setup_fun)(void), void (*loop_fun)(void)) // access serial ports using SERIALn numbering AP_HAL::UARTDriver* AP_HAL::HAL::serial(uint8_t sernum) const { - UARTDriver **uart_array = const_cast(&uartA); // this mapping captures the historical use of uartB as SERIAL3 const uint8_t mapping[] = { 0, 2, 3, 1, 4, 5, 6, 7, 8, 9 }; static_assert(sizeof(mapping) == num_serial, "num_serial must match mapping"); diff --git a/libraries/AP_HAL/HAL.h b/libraries/AP_HAL/HAL.h index d17409bcf0a5c..a3701eb349555 100644 --- a/libraries/AP_HAL/HAL.h +++ b/libraries/AP_HAL/HAL.h @@ -53,16 +53,17 @@ class AP_HAL::HAL { AP_HAL::CANIface** _can_ifaces) #endif : - uartA(_uartA), - uartB(_uartB), - uartC(_uartC), - uartD(_uartD), - uartE(_uartE), - uartF(_uartF), - uartG(_uartG), - uartH(_uartH), - uartI(_uartI), - uartJ(_uartJ), + uart_array{ + _uartA, + _uartB, + _uartC, + _uartD, + _uartE, + _uartF, + _uartG, + _uartH, + _uartI, + _uartJ}, i2c_mgr(_i2c_mgr), spi(_spi), wspi(_wspi), @@ -112,19 +113,6 @@ class AP_HAL::HAL { virtual void run(int argc, char * const argv[], Callbacks* callbacks) const = 0; -private: - // the uartX ports must be contiguous in ram for the serial() method to work - AP_HAL::UARTDriver* uartA; - AP_HAL::UARTDriver* uartB UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartC UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartD UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartE UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartF UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartG UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartH UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartI UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartJ UNUSED_PRIVATE_MEMBER; - public: AP_HAL::I2CDeviceManager* i2c_mgr; AP_HAL::SPIDeviceManager* spi; @@ -151,6 +139,10 @@ class AP_HAL::HAL { static constexpr uint8_t num_serial = 10; +private: + AP_HAL::UARTDriver* uart_array[num_serial]; + +public: #if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL AP_HAL::SIMState *simstate; #endif