Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

HAL_ChibiOS: added ALT(1) configs for more boards #13157

Merged
merged 5 commits into from
Jan 3, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 11 additions & 5 deletions libraries/AP_HAL/UARTDriver.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,14 +49,20 @@ class AP_HAL::UARTDriver : public AP_HAL::BetterStream {
virtual int16_t read_locked(uint32_t key) { return -1; }

// control optional features
virtual bool set_options(uint8_t options) { return options==0; }
virtual bool set_options(uint16_t options) { return options==0; }
virtual uint8_t get_options(void) const { return 0; }

enum {
OPTION_RXINV=(1U<<0), // invert RX line
OPTION_TXINV=(1U<<1), // invert TX line
OPTION_HDPLEX=(1U<<2), // half-duplex (one-wire) mode
OPTION_SWAP=(1U<<3), // swap RX and TX pins
OPTION_RXINV = (1U<<0), // invert RX line
OPTION_TXINV = (1U<<1), // invert TX line
OPTION_HDPLEX = (1U<<2), // half-duplex (one-wire) mode
OPTION_SWAP = (1U<<3), // swap RX and TX pins
OPTION_PULLDOWN_RX = (1U<<4), // apply pulldown to RX
OPTION_PULLUP_RX = (1U<<5), // apply pullup to RX
OPTION_PULLDOWN_TX = (1U<<6), // apply pulldown to TX
OPTION_PULLUP_TX = (1U<<7), // apply pullup to TX
OPTION_NODMA_RX = (1U<<8), // don't use DMA for RX
OPTION_NODMA_TX = (1U<<9), // don't use DMA for TX
};

enum flow_control {
Expand Down
39 changes: 32 additions & 7 deletions libraries/AP_HAL_ChibiOS/UARTDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -202,13 +202,15 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
}

#ifndef HAL_UART_NODMA
if (rx_bounce_buf[0] == nullptr && sdef.dma_rx) {
rx_bounce_buf[0] = (uint8_t *)hal.util->malloc_type(RX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE);
}
if (rx_bounce_buf[1] == nullptr && sdef.dma_rx) {
rx_bounce_buf[1] = (uint8_t *)hal.util->malloc_type(RX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE);
if (!half_duplex && !(_last_options & OPTION_NODMA_RX)) {
if (rx_bounce_buf[0] == nullptr && sdef.dma_rx) {
rx_bounce_buf[0] = (uint8_t *)hal.util->malloc_type(RX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE);
}
if (rx_bounce_buf[1] == nullptr && sdef.dma_rx) {
rx_bounce_buf[1] = (uint8_t *)hal.util->malloc_type(RX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE);
}
}
if (tx_bounce_buf == nullptr && sdef.dma_tx) {
if (tx_bounce_buf == nullptr && sdef.dma_tx && !(_last_options & OPTION_NODMA_TX)) {
tx_bounce_buf = (uint8_t *)hal.util->malloc_type(TX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE);
chVTObjectInit(&tx_timeout);
tx_bounce_buf_ready = true;
Expand Down Expand Up @@ -1298,8 +1300,29 @@ uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes)
return last_receive_us;
}

/*
set user specified PULLUP/PULLDOWN options from SERIALn_OPTIONS
*/
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_TX) && sdef.tx_line) {
palLineSetPushPull(sdef.tx_line, PAL_PUSHPULL_PULLDOWN);
}
if ((options & OPTION_PULLUP_RX) && sdef.rx_line) {
palLineSetPushPull(sdef.rx_line, PAL_PUSHPULL_PULLUP);
}
if ((options & OPTION_PULLUP_TX) && sdef.tx_line) {
palLineSetPushPull(sdef.tx_line, PAL_PUSHPULL_PULLUP);
}
#endif
}

// set optional features, return true on success
bool UARTDriver::set_options(uint8_t options)
bool UARTDriver::set_options(uint16_t options)
{
if (sdef.is_usb) {
// no options allowed on USB
Expand Down Expand Up @@ -1395,6 +1418,8 @@ bool UARTDriver::set_options(uint8_t options)
cr3 &= ~USART_CR3_HDSEL;
}

set_pushpull(options);

if (sd->usart->CR2 == cr2 &&
sd->usart->CR3 == cr3) {
// no change
Expand Down
7 changes: 5 additions & 2 deletions libraries/AP_HAL_ChibiOS/UARTDriver.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class ChibiOS::UARTDriver : public AP_HAL::UARTDriver {
bool lock_port(uint32_t write_key, uint32_t read_key) override;

// control optional features
bool set_options(uint8_t options) override;
bool set_options(uint16_t options) override;
uint8_t get_options(void) const override;

// write to a locked port. If port is locked and key is not correct then 0 is returned
Expand Down Expand Up @@ -189,7 +189,7 @@ class ChibiOS::UARTDriver : public AP_HAL::UARTDriver {
uint32_t _cr1_options;
uint32_t _cr2_options;
uint32_t _cr3_options;
uint8_t _last_options;
uint16_t _last_options;

// half duplex control. After writing we throw away bytes for 4 byte widths to
// prevent reading our own bytes back
Expand Down Expand Up @@ -232,6 +232,9 @@ class ChibiOS::UARTDriver : public AP_HAL::UARTDriver {

void receive_timestamp_update(void);

// set SERIALn_OPTIONS for pullup/pulldown
void set_pushpull(uint16_t options);

void thread_init();
static void uart_thread(void *);
};
10 changes: 7 additions & 3 deletions libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -99,9 +99,13 @@ PB10 USART3_TX USART3
PA0 UART4_TX UART4 NODMA
PA1 UART4_RX UART4 NODMA

# USART6, RX only for RCIN
PC7 TIM8_CH2 TIM8 RCININT FLOAT LOW
PC6 USART6_TX USART6 NODMA LOW
# RC input defaults to timer capture
PC7 TIM8_CH2 TIM8 RCININT PULLDOWN

# alternative config using USART for protocols
# like FPort
PC7 USART6_RX USART6 NODMA ALT(1)
PC6 USART6_TX USART6 NODMA

# UART7 USED BY ESC FROM ORIGINAL DESIGN
PE7 UART7_RX UART7
Expand Down
10 changes: 7 additions & 3 deletions libraries/AP_HAL_ChibiOS/hwdef/KakuteF7Mini/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -99,9 +99,13 @@ PB10 USART3_TX USART3
PA0 UART4_TX UART4 NODMA
PA1 UART4_RX UART4 NODMA

# USART6, RX only for RCIN
PC7 TIM8_CH2 TIM8 RCININT FLOAT LOW
PC6 USART6_TX USART6 NODMA LOW
# RC input defaults to timer capture
PC7 TIM8_CH2 TIM8 RCININT PULLDOWN
PC6 USART6_TX USART6 NODMA

# alt config to allow RCIN on UART for bi-directional
# protocols like FPort
PC7 USART6_RX USART6 NODMA ALT(1)

# UART7, RX only for ESC Telemetry
PE7 UART7_RX UART7
Expand Down
10 changes: 6 additions & 4 deletions libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ STM32_VDD 330U
I2C_ORDER I2C1 I2C2

# order of UARTs
UART_ORDER OTG1 USART3 USART1 EMPTY UART4 UART5 USART6
UART_ORDER OTG1 USART3 USART1 EMPTY UART4 UART5 USART6 USART2

#################################################
### PIN DEFINITIONS ###
Expand All @@ -57,11 +57,13 @@ UART_ORDER OTG1 USART3 USART1 EMPTY UART4 UART5 USART6
PA0 UART4_TX UART4
PA1 UART4_RX UART4

# USART 2 is used for RC Input
# PA2 USART2_TX USART2
# PA3 USART2_RX USART2
# default to timer for RC input
PA3 TIM2_CH4 TIM2 RCININT FLOAT LOW

# alternative using USART2
PA2 USART2_TX USART2 NODMA
PA3 USART2_RX USART2 NODMA ALT(1)

PA4 MPU_CS CS

# IMU SPI
Expand Down
12 changes: 6 additions & 6 deletions libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ STM32_VDD 330U
I2C_ORDER I2C1

# order of UARTs (and USB)
UART_ORDER OTG1 USART1 USART3 UART4 UART5
UART_ORDER OTG1 USART1 USART3 UART4 UART5 USART2

# LEDs
PB9 LED_BLUE OUTPUT LOW GPIO(0)
Expand Down Expand Up @@ -88,12 +88,12 @@ define BOARD_RSSI_ANA_PIN 9
PA9 USART1_TX USART1
PA10 USART1_RX USART1

# USART2 (RCIN)
#PA2 USART3_TX USART3
#PA3 USART3_RX USART3
# RC input using timer
PA3 TIM9_CH2 TIM9 RCININT PULLDOWN

# rcinput
PA3 TIM9_CH2 TIM9 RCININT FLOAT LOW
# alternative RC input using UART
PA2 USART2_TX USART2 NODMA
PA3 USART2_RX USART2 NODMA ALT(1)

# USART3
PC10 USART3_TX USART3
Expand Down
9 changes: 6 additions & 3 deletions libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ STM32_VDD 330U
I2C_ORDER I2C2

# order of UARTs (and USB)
UART_ORDER OTG1 USART6 USART1 USART3
UART_ORDER OTG1 USART6 USART1 USART3 USART2

PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
Expand Down Expand Up @@ -94,8 +94,11 @@ IMU Invensense SPI:mpu6500 ROTATION_YAW_90
PA10 USART1_RX USART1
PA9 USART1_TX USART1

# USART2 for RC input, RX only
PA3 TIM9_CH2 TIM9 RCININT FLOAT LOW
# RC input using timer by default
PA3 TIM9_CH2 TIM9 RCININT PULLDOWN

# alternative RC input using USART2
PA3 USART2_RX USART2 NODMA ALT(1)

# USART3
PD9 USART3_RX USART3
Expand Down
9 changes: 7 additions & 2 deletions libraries/AP_HAL_ChibiOS/hwdef/mindpx-v2/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ FLASH_RESERVE_END_KB 0
I2C_ORDER I2C1 I2C2

# order of UARTs (and USB)
UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1 UART7
UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1 UART7 USART6

# UART4 is GPS
PA0 UART4_TX UART4
Expand Down Expand Up @@ -110,7 +110,12 @@ PC2 BAT_VOLT_SENS ADC1
PC3 FMU_ADC1 ADC1
PC4 FMU_ADC2 ADC1
PC5 FMU_ADC3 ADC1
PC6 TIM8_CH1 TIM8 RCIN PULLDOWN LOW # also USART6_RX for serial RC

# RC input default to timer
PC6 TIM8_CH1 TIM8 RCININT PULLDOWN

# alternative RC input using USART6
PC6 USART6_TX USART6 NODMA ALT(1)

PC8 SDIO_D0 SDIO
PC9 SDIO_D1 SDIO
Expand Down
9 changes: 7 additions & 2 deletions libraries/AP_HAL_ChibiOS/hwdef/mini-pix/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ STM32_VDD 330U
I2C_ORDER I2C2 I2C1

# order of UARTs (and USB)
UART_ORDER OTG1 UART4 USART3 USART2
UART_ORDER OTG1 UART4 USART3 USART2 USART6

# UART4 serial GPS
PA0 UART4_TX UART4
Expand Down Expand Up @@ -74,7 +74,12 @@ PC2 LPS22HB_CS CS
PC3 LED_SAFETY OUTPUT
PC4 SAFETY_IN INPUT

PC7 TIM8_CH2 TIM8 RCIN PULLUP LOW # also USART6_RX for serial RC
# default to RCIN using timer capture
PC7 TIM8_CH2 TIM8 RCININT PULLDOWN

# alternative using USART6
PC7 USART6_RX USART6 NODMA ALT(1)

PC8 SDIO_D0 SDIO
PC9 SDIO_D1 SDIO
PC10 SDIO_D2 SDIO
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py
Original file line number Diff line number Diff line change
Expand Up @@ -1122,6 +1122,8 @@ def write_UART_config(f):
num_uarts = len(devlist)
if 'IOMCU_UART' in config:
num_uarts -= 1
if num_uarts > 8:
error("Exceeded max num UARTs of 8 (%u)" % num_uarts)
f.write('#define HAL_UART_NUM_SERIAL_PORTS %u\n' % (num_uarts+num_empty_uarts))


Expand Down
16 changes: 8 additions & 8 deletions libraries/AP_SerialManager/AP_SerialManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,7 +195,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Param: 1_OPTIONS
// @DisplayName: Telem1 options
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire. The Swap option allows the RX and TX pins to be swapped on STM32F7 based boards.
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 3:Swap, 4: RX_PullDown, 5: RX_PullUp, 6: TX_PullDown, 7: TX_PullUp, 8: RX_NoDMA, 9: TX_NoDMA
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("1_OPTIONS", 14, AP_SerialManager, state[1].options, 0),
Expand All @@ -205,7 +205,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Param: 2_OPTIONS
// @DisplayName: Telem2 options
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 3:Swap, 4: RX_PullDown, 5: RX_PullUp, 6: TX_PullDown, 7: TX_PullUp, 8: RX_NoDMA, 9: TX_NoDMA
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("2_OPTIONS", 15, AP_SerialManager, state[2].options, 0),
Expand All @@ -215,7 +215,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Param: 3_OPTIONS
// @DisplayName: Serial3 options
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 3:Swap, 4: RX_PullDown, 5: RX_PullUp, 6: TX_PullDown, 7: TX_PullUp, 8: RX_NoDMA, 9: TX_NoDMA
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("3_OPTIONS", 16, AP_SerialManager, state[3].options, 0),
Expand All @@ -225,7 +225,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Param: 4_OPTIONS
// @DisplayName: Serial4 options
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 3:Swap, 4: RX_PullDown, 5: RX_PullUp, 6: TX_PullDown, 7: TX_PullUp, 8: RX_NoDMA, 9: TX_NoDMA
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("4_OPTIONS", 17, AP_SerialManager, state[4].options, 0),
Expand All @@ -235,7 +235,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Param: 5_OPTIONS
// @DisplayName: Serial5 options
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 3:Swap, 4: RX_PullDown, 5: RX_PullUp, 6: TX_PullDown, 7: TX_PullUp, 8: RX_NoDMA, 9: TX_NoDMA
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("5_OPTIONS", 18, AP_SerialManager, state[5].options, 0),
Expand All @@ -245,7 +245,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Param: 6_OPTIONS
// @DisplayName: Serial6 options
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 3:Swap, 4: RX_PullDown, 5: RX_PullUp, 6: TX_PullDown, 7: TX_PullUp, 8: RX_NoDMA, 9: TX_NoDMA
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("6_OPTIONS", 19, AP_SerialManager, state[6].options, 0),
Expand Down Expand Up @@ -292,7 +292,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Param: 7_OPTIONS
// @DisplayName: Serial7 options
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 3:Swap, 4: RX_PullDown, 5: RX_PullUp, 6: TX_PullDown, 7: TX_PullUp, 8: RX_NoDMA, 9: TX_NoDMA
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("7_OPTIONS", 25, AP_SerialManager, state[7].options, 0),
Expand Down Expand Up @@ -638,7 +638,7 @@ bool AP_SerialManager::protocol_match(enum SerialProtocol protocol1, enum Serial
}

// setup any special options
void AP_SerialManager::set_options(uint8_t i)
void AP_SerialManager::set_options(uint16_t i)
{
struct UARTState &opt = state[i];
// pass through to HAL
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_SerialManager/AP_SerialManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,7 @@ class AP_SerialManager {
bool protocol_match(enum SerialProtocol protocol1, enum SerialProtocol protocol2) const;

// setup any special options
void set_options(uint8_t i);
void set_options(uint16_t i);
};

namespace AP {
Expand Down