Browse Source

HAL_ChibiOS: fixed remapping of ioline_t with BRD_ALT_CONFIG

when a peripheral is made available via BRD_ALT_CONFIG we need to
remap the existing ioline_t in the UART and I2C drivers to use the new
pin.

This fixes an issue with half-duplex, inverted, swapped UART pins for
protocols like FPort and FPort2
c415-sdk
Andrew Tridgell 4 years ago
parent
commit
46976c4358
  1. 56
      libraries/AP_HAL_ChibiOS/GPIO.cpp
  2. 19
      libraries/AP_HAL_ChibiOS/GPIO.h
  3. 26
      libraries/AP_HAL_ChibiOS/I2CDevice.cpp
  4. 39
      libraries/AP_HAL_ChibiOS/UARTDriver.cpp
  5. 7
      libraries/AP_HAL_ChibiOS/UARTDriver.h
  6. 38
      libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py

56
libraries/AP_HAL_ChibiOS/GPIO.cpp

@ -79,6 +79,9 @@ void GPIO::init() @@ -79,6 +79,9 @@ void GPIO::init()
}
#ifdef HAL_PIN_ALT_CONFIG
// chosen alternative config
uint8_t GPIO::alt_config;
/*
alternative config table, selected using BRD_ALT_CONFIG
*/
@ -86,6 +89,8 @@ static const struct alt_config { @@ -86,6 +89,8 @@ static const struct alt_config {
uint8_t alternate;
uint16_t mode;
ioline_t line;
PERIPH_TYPE periph_type;
uint8_t periph_instance;
} alternate_config[] HAL_PIN_ALT_CONFIG;
/*
@ -97,22 +102,59 @@ void GPIO::setup_alt_config(void) @@ -97,22 +102,59 @@ void GPIO::setup_alt_config(void)
if (!bc) {
return;
}
const uint8_t alt = bc->get_alt_config();
if (alt == 0) {
alt_config = bc->get_alt_config();
if (alt_config == 0) {
// use defaults
return;
}
for (uint8_t i=0; i<ARRAY_SIZE(alternate_config); i++) {
if (alt == alternate_config[i].alternate) {
const iomode_t mode = alternate_config[i].mode & ~PAL_STM32_HIGH;
const uint8_t odr = (alternate_config[i].mode & PAL_STM32_HIGH)?1:0;
palSetLineMode(alternate_config[i].line, mode);
palWriteLine(alternate_config[i].line, odr);
const struct alt_config &alt = alternate_config[i];
if (alt_config == alt.alternate) {
const iomode_t mode = alt.mode & ~PAL_STM32_HIGH;
const uint8_t odr = (alt.mode & PAL_STM32_HIGH)?1:0;
palSetLineMode(alt.line, mode);
palWriteLine(alt.line, odr);
}
}
}
#endif // HAL_PIN_ALT_CONFIG
/*
resolve an ioline_t to take account of alternative
configurations. This allows drivers to get the right ioline_t for an
alternative config. Note that this may return 0, meaning the pin is
not mapped to this peripheral in the active config
*/
ioline_t GPIO::resolve_alt_config(ioline_t base, PERIPH_TYPE ptype, uint8_t instance)
{
#ifdef HAL_PIN_ALT_CONFIG
if (alt_config == 0) {
// unchanged
return base;
}
for (uint8_t i=0; i<ARRAY_SIZE(alternate_config); i++) {
const struct alt_config &alt = alternate_config[i];
if (alt_config == alt.alternate) {
if (ptype == alt.periph_type && instance == alt.periph_instance) {
// we've reconfigured this peripheral with a different line
return alt.line;
}
}
}
// now search for pins that have been configured off via BRD_ALT_CONFIG
for (uint8_t i=0; i<ARRAY_SIZE(alternate_config); i++) {
const struct alt_config &alt = alternate_config[i];
if (alt_config == alt.alternate) {
if (alt.line == base) {
// this line is no longer available in this config
return 0;
}
}
}
#endif
return base;
}
void GPIO::pinMode(uint8_t pin, uint8_t output)
{

19
libraries/AP_HAL_ChibiOS/GPIO.h

@ -26,6 +26,17 @@ @@ -26,6 +26,17 @@
#define HAL_GPIO_LED_OFF 1
#endif
/*
pin types for alternative configuration
*/
enum class PERIPH_TYPE : uint8_t {
UART_RX,
UART_TX,
I2C_SDA,
I2C_SCL,
OTHER,
};
class ChibiOS::GPIO : public AP_HAL::GPIO {
public:
GPIO();
@ -66,7 +77,12 @@ public: @@ -66,7 +77,12 @@ public:
// timer tick
void timer_tick(void) override;
#endif
/*
resolve an ioline to take account of alternative configurations
*/
static ioline_t resolve_alt_config(ioline_t base, PERIPH_TYPE ptype, uint8_t instance);
private:
bool _usb_connected;
bool _ext_started;
@ -75,6 +91,7 @@ private: @@ -75,6 +91,7 @@ private:
bool _attach_interrupt(ioline_t line, palcallback_t cb, void *p, uint8_t mode);
#ifdef HAL_PIN_ALT_CONFIG
void setup_alt_config(void);
static uint8_t alt_config;
#endif
};

26
libraries/AP_HAL_ChibiOS/I2CDevice.cpp

@ -17,6 +17,7 @@ @@ -17,6 +17,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include "Util.h"
#include "GPIO.h"
#if HAL_USE_I2C == TRUE && defined(HAL_I2C_DEVICE_LIST)
@ -29,6 +30,7 @@ @@ -29,6 +30,7 @@
static const struct I2CInfo {
struct I2CDriver *i2c;
uint8_t instance;
uint8_t dma_channel_rx;
uint8_t dma_channel_tx;
ioline_t scl_line;
@ -90,13 +92,17 @@ void I2CBus::clear_bus(uint8_t busidx) @@ -90,13 +92,17 @@ void I2CBus::clear_bus(uint8_t busidx)
{
#if HAL_I2C_CLEAR_ON_TIMEOUT
const struct I2CInfo &info = I2CD[busidx];
const iomode_t mode_saved = palReadLineMode(info.scl_line);
palSetLineMode(info.scl_line, PAL_MODE_OUTPUT_PUSHPULL);
const ioline_t scl_line = GPIO::resolve_alt_config(info.scl_line, PERIPH_TYPE::I2C_SCL, info.instance);
if (scl_line == 0) {
return;
}
const iomode_t mode_saved = palReadLineMode(scl_line);
palSetLineMode(scl_line, PAL_MODE_OUTPUT_PUSHPULL);
for(uint8_t j = 0; j < 20; j++) {
palToggleLine(info.scl_line);
palToggleLine(scl_line);
hal.scheduler->delay_microseconds(10);
}
palSetLineMode(info.scl_line, mode_saved);
palSetLineMode(scl_line, mode_saved);
#endif
}
@ -107,10 +113,14 @@ void I2CBus::clear_bus(uint8_t busidx) @@ -107,10 +113,14 @@ void I2CBus::clear_bus(uint8_t busidx)
uint8_t I2CBus::read_sda(uint8_t busidx)
{
const struct I2CInfo &info = I2CD[busidx];
const iomode_t mode_saved = palReadLineMode(info.sda_line);
palSetLineMode(info.sda_line, PAL_MODE_INPUT);
uint8_t ret = palReadLine(info.sda_line);
palSetLineMode(info.sda_line, mode_saved);
const ioline_t sda_line = GPIO::resolve_alt_config(info.sda_line, PERIPH_TYPE::I2C_SDA, info.instance);
if (sda_line == 0) {
return 0;
}
const iomode_t mode_saved = palReadLineMode(sda_line);
palSetLineMode(sda_line, PAL_MODE_INPUT);
uint8_t ret = palReadLine(sda_line);
palSetLineMode(sda_line, mode_saved);
return ret;
}
#endif

39
libraries/AP_HAL_ChibiOS/UARTDriver.cpp

@ -1346,17 +1346,17 @@ uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes) @@ -1346,17 +1346,17 @@ uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes)
void UARTDriver::set_pushpull(uint16_t options)
{
#if HAL_USE_SERIAL == TRUE && !defined(STM32F1)
if ((options & OPTION_PULLDOWN_RX) && sdef.rx_line) {
palLineSetPushPull(sdef.rx_line, PAL_PUSHPULL_PULLDOWN);
if ((options & OPTION_PULLDOWN_RX) && arx_line) {
palLineSetPushPull(arx_line, PAL_PUSHPULL_PULLDOWN);
}
if ((options & OPTION_PULLDOWN_TX) && sdef.tx_line) {
palLineSetPushPull(sdef.tx_line, PAL_PUSHPULL_PULLDOWN);
if ((options & OPTION_PULLDOWN_TX) && atx_line) {
palLineSetPushPull(atx_line, PAL_PUSHPULL_PULLDOWN);
}
if ((options & OPTION_PULLUP_RX) && sdef.rx_line) {
palLineSetPushPull(sdef.rx_line, PAL_PUSHPULL_PULLUP);
if ((options & OPTION_PULLUP_RX) && arx_line) {
palLineSetPushPull(arx_line, PAL_PUSHPULL_PULLUP);
}
if ((options & OPTION_PULLUP_TX) && sdef.tx_line) {
palLineSetPushPull(sdef.tx_line, PAL_PUSHPULL_PULLUP);
if ((options & OPTION_PULLUP_TX) && atx_line) {
palLineSetPushPull(atx_line, PAL_PUSHPULL_PULLUP);
}
#endif
}
@ -1378,10 +1378,29 @@ bool UARTDriver::set_options(uint16_t options) @@ -1378,10 +1378,29 @@ bool UARTDriver::set_options(uint16_t options)
uint32_t cr3 = sd->usart->CR3;
bool was_enabled = (sd->usart->CR1 & USART_CR1_UE);
#ifdef HAL_PIN_ALT_CONFIG
/*
allow for RX and TX pins to be remapped via BRD_ALT_CONFIG
*/
arx_line = GPIO::resolve_alt_config(sdef.rx_line, PERIPH_TYPE::UART_RX, sdef.instance);
atx_line = GPIO::resolve_alt_config(sdef.tx_line, PERIPH_TYPE::UART_TX, sdef.instance);
#else
arx_line = sdef.rx_line;
atx_line = sdef.tx_line;
#endif
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3)
// F7 has built-in support for inversion in all uarts
ioline_t rx_line = (options & OPTION_SWAP)?sdef.tx_line:sdef.rx_line;
ioline_t tx_line = (options & OPTION_SWAP)?sdef.rx_line:sdef.tx_line;
ioline_t rx_line = (options & OPTION_SWAP)?atx_line:arx_line;
ioline_t tx_line = (options & OPTION_SWAP)?arx_line:atx_line;
// if we are half-duplex then treat either inversion option as
// both being enabled. This is easier to understand for users, who
// can be confused as to which pin is the one that needs inversion
if ((options & OPTION_HDPLEX) && (options & (OPTION_TXINV|OPTION_RXINV)) != 0) {
options |= OPTION_TXINV|OPTION_RXINV;
}
if (options & OPTION_RXINV) {
cr2 |= USART_CR2_RXINV;
_cr2_options |= USART_CR2_RXINV;

7
libraries/AP_HAL_ChibiOS/UARTDriver.h

@ -68,6 +68,7 @@ public: @@ -68,6 +68,7 @@ public:
struct SerialDef {
BaseSequentialStream* serial;
uint8_t instance;
bool is_usb;
#ifndef HAL_UART_NODMA
bool dma_rx;
@ -127,6 +128,12 @@ private: @@ -127,6 +128,12 @@ private:
bool rx_dma_enabled;
bool tx_dma_enabled;
/*
copy of rx_line and tx_line with alternative configs resolved
*/
ioline_t atx_line;
ioline_t arx_line;
// thread used for all UARTs
static thread_t *uart_thread_ctx;

38
libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py

@ -525,6 +525,28 @@ class generic_pin(object): @@ -525,6 +525,28 @@ class generic_pin(object):
return ret
def periph_type(self):
'''return peripheral type from GPIO_PIN_TYPE class'''
patterns = {
'USART*RX' : 'PERIPH_TYPE::UART_RX',
'UART*RX' : 'PERIPH_TYPE::UART_RX',
'USART*TX' : 'PERIPH_TYPE::UART_TX',
'UART*TX' : 'PERIPH_TYPE::UART_TX',
'I2C*SDA' : 'PERIPH_TYPE::I2C_SDA',
'I2C*SCL' : 'PERIPH_TYPE::I2C_SCL',
}
for k in patterns.keys():
if fnmatch.fnmatch(self.label, k):
return patterns[k]
return 'PERIPH_TYPE::OTHER'
def periph_instance(self):
'''return peripheral instance'''
result = re.match(r'[A-Z]*([0-9]*)', self.type)
if result:
return int(result.group(1))
return 0
def __str__(self):
str = ''
if self.af is not None:
@ -1186,19 +1208,19 @@ def write_UART_config(f): @@ -1186,19 +1208,19 @@ def write_UART_config(f):
if dev.startswith('OTG2'):
f.write(
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU2, true, false, 0, 0, false, 0, 0}\n'
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU2, 2, true, false, 0, 0, false, 0, 0}\n'
% dev)
OTG2_index = uart_list.index(dev)
dual_USB_enabled = True
elif dev.startswith('OTG'):
f.write(
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU1, true, false, 0, 0, false, 0, 0}\n'
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU1, 1, true, false, 0, 0, false, 0, 0}\n'
% dev)
else:
need_uart_driver = True
f.write(
"#define HAL_%s_CONFIG { (BaseSequentialStream*) &SD%u, false, "
% (dev, n))
"#define HAL_%s_CONFIG { (BaseSequentialStream*) &SD%u, %u, false, "
% (dev, n, n))
if mcu_series.startswith("STM32F1"):
f.write("%s, %s, %s, " % (tx_line, rx_line, rts_line))
else:
@ -1300,12 +1322,12 @@ def write_I2C_config(f): @@ -1300,12 +1322,12 @@ def write_I2C_config(f):
scl_line = make_line('I2C%u_SCL' % n)
f.write('''
#if defined(STM32_I2C_I2C%u_RX_DMA_STREAM) && defined(STM32_I2C_I2C%u_TX_DMA_STREAM)
#define HAL_I2C%u_CONFIG { &I2CD%u, STM32_I2C_I2C%u_RX_DMA_STREAM, STM32_I2C_I2C%u_TX_DMA_STREAM, %s, %s }
#define HAL_I2C%u_CONFIG { &I2CD%u, %u, STM32_I2C_I2C%u_RX_DMA_STREAM, STM32_I2C_I2C%u_TX_DMA_STREAM, %s, %s }
#else
#define HAL_I2C%u_CONFIG { &I2CD%u, SHARED_DMA_NONE, SHARED_DMA_NONE, %s, %s }
#define HAL_I2C%u_CONFIG { &I2CD%u, %u, SHARED_DMA_NONE, SHARED_DMA_NONE, %s, %s }
#endif
'''
% (n, n, n, n, n, n, scl_line, sda_line, n, n, scl_line, sda_line))
% (n, n, n, n, n, n, n, scl_line, sda_line, n, n, n, scl_line, sda_line))
f.write('\n#define HAL_I2C_DEVICE_LIST %s\n\n' % ','.join(devlist))
@ -1657,7 +1679,7 @@ def write_alt_config(f): @@ -1657,7 +1679,7 @@ def write_alt_config(f):
for alt in altmap.keys():
for pp in altmap[alt].keys():
p = altmap[alt][pp]
f.write(" { %u, %s, PAL_LINE(GPIO%s,%uU)}, /* %s */ \\\n" % (alt, p.pal_modeline(), p.port, p.pin, str(p)))
f.write(" { %u, %s, PAL_LINE(GPIO%s,%uU), %s, %u}, /* %s */ \\\n" % (alt, p.pal_modeline(), p.port, p.pin, p.periph_type(), p.periph_instance(), str(p)))
f.write('}\n\n')
def write_all_lines(hwdat):

Loading…
Cancel
Save