mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: move serial re-mapping to driver array initialization
Saves a bit of flash and execution time.
This commit is contained in:
parent
de45437704
commit
8747ae539f
|
@ -15,11 +15,8 @@ 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
|
||||
{
|
||||
// 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) == ARRAY_SIZE(uart_array), "array size must match mapping");
|
||||
if (sernum >= ARRAY_SIZE(uart_array)) {
|
||||
if (sernum >= ARRAY_SIZE(serial_array)) {
|
||||
return nullptr;
|
||||
}
|
||||
return uart_array[mapping[sernum]];
|
||||
return serial_array[sernum];
|
||||
}
|
||||
|
|
|
@ -53,11 +53,11 @@ public:
|
|||
AP_HAL::CANIface** _can_ifaces)
|
||||
#endif
|
||||
:
|
||||
uart_array{
|
||||
serial_array{
|
||||
_uartA,
|
||||
_uartB,
|
||||
_uartC,
|
||||
_uartC, // ordering captures the historical use of uartB as SERIAL3
|
||||
_uartD,
|
||||
_uartB,
|
||||
_uartE,
|
||||
_uartF,
|
||||
_uartG,
|
||||
|
@ -140,7 +140,8 @@ public:
|
|||
static constexpr uint8_t num_serial = 10;
|
||||
|
||||
private:
|
||||
AP_HAL::UARTDriver* uart_array[num_serial];
|
||||
// UART drivers in SERIALn_ order
|
||||
AP_HAL::UARTDriver* serial_array[num_serial];
|
||||
|
||||
public:
|
||||
#if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
||||
|
|
Loading…
Reference in New Issue