mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_HAL: added hal.serial() access to uarts
this gives access to serial ports in the SERIALn_ order. It is inlined by the compiler so using hal.uartB and hal.serial(3) generates idential code on stm32 (tested on H7). This is a step towards eliminating hal.uartX completely and the horrible uartB ordering
This commit is contained in:
parent
4ec1c2ea67
commit
8678759da4
@ -101,6 +101,7 @@ public:
|
||||
|
||||
virtual void run(int argc, char * const argv[], Callbacks* callbacks) const = 0;
|
||||
|
||||
// the uartX ports must be contiguous in ram for the serial() method to work
|
||||
AP_HAL::UARTDriver* uartA;
|
||||
AP_HAL::UARTDriver* uartB;
|
||||
AP_HAL::UARTDriver* uartC;
|
||||
@ -128,4 +129,15 @@ public:
|
||||
#else
|
||||
AP_HAL::CANIface** can;
|
||||
#endif
|
||||
|
||||
// access to serial ports using SERIALn_ numbering
|
||||
UARTDriver* serial(uint8_t sernum) const {
|
||||
UARTDriver **uart_array = const_cast<UARTDriver**>(&uartA);
|
||||
// this mapping captures the historical use of uartB as SERIAL3
|
||||
const uint8_t mapping[] = { 0, 2, 3, 1, 4, 5, 6, 7, 8 };
|
||||
if (sernum >= ARRAY_SIZE(mapping)) {
|
||||
return nullptr;
|
||||
}
|
||||
return uart_array[mapping[sernum]];
|
||||
}
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user