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

Do PPP networking between Primary and Secondary MCU #27577

Merged
merged 4 commits into from
Jul 24, 2024
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
47 changes: 46 additions & 1 deletion libraries/AP_HAL_ChibiOS/UARTDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,9 @@ static const eventmask_t EVT_PARITY = EVENT_MASK(11);
// event for transmit end for half-duplex
static const eventmask_t EVT_TRANSMIT_END = EVENT_MASK(12);

// event for framing error
static const eventmask_t EVT_ERROR = EVENT_MASK(13);

// events for dma tx, thread per UART so can be from 0
static const eventmask_t EVT_TRANSMIT_DMA_START = EVENT_MASK(0);
static const eventmask_t EVT_TRANSMIT_DMA_COMPLETE = EVENT_MASK(1);
Expand Down Expand Up @@ -452,6 +455,13 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
sercfg.cr3 |= USART_CR3_DMAT;
}
sercfg.irq_cb = rx_irq_cb;
#if HAL_HAVE_LOW_NOISE_UART
if (sdef.low_noise_line) {
// we can mark UART to sample on one bit instead of default 3 bits
// this allows us to be slightly less sensitive to clock differences
sercfg.cr3 |= USART_CR3_ONEBIT;
}
#endif
#endif // HAL_UART_NODMA
if (!(sercfg.cr2 & USART_CR2_STOP2_BITS)) {
sercfg.cr2 |= USART_CR2_STOP1_BITS;
Expand Down Expand Up @@ -495,6 +505,16 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
vprintf_console_hook = hal_console_vprintf;
#endif
}

#if HAL_UART_STATS_ENABLED && CH_CFG_USE_EVENTS == TRUE
if (!err_listener_initialised) {
chEvtRegisterMaskWithFlags(chnGetEventSource((SerialDriver*)sdef.serial),
&err_listener,
EVT_ERROR,
SD_FRAMING_ERROR | SD_OVERRUN_ERROR | SD_NOISE_ERROR);
err_listener_initialised = true;
}
#endif
}

#ifndef HAL_UART_NODMA
Expand Down Expand Up @@ -1091,6 +1111,22 @@ void UARTDriver::_rx_timer_tick(void)

_in_rx_timer = true;

#if HAL_UART_STATS_ENABLED && CH_CFG_USE_EVENTS == TRUE
if (!sdef.is_usb) {
const auto err_flags = chEvtGetAndClearFlags(&err_listener);
// count the number of errors
if (err_flags & SD_FRAMING_ERROR) {
_rx_stats_framing_errors++;
}
if (err_flags & SD_OVERRUN_ERROR) {
_rx_stats_overrun_errors++;
}
if (err_flags & SD_NOISE_ERROR) {
_rx_stats_noise_errors++;
}
}
#endif

#ifndef HAL_UART_NODMA
if (rx_dma_enabled && rxdma) {
chSysLock();
Expand Down Expand Up @@ -1748,13 +1784,22 @@ void UARTDriver::uart_info(ExpandingString &str, StatsTracker &stats, const uint
} else {
str.printf("UART%u ", unsigned(sdef.instance));
}
str.printf("TX%c=%8u RX%c=%8u TXBD=%6u RXBD=%6u FlowCtrl=%u\n",
str.printf("TX%c=%8u RX%c=%8u TXBD=%6u RXBD=%6u"
#if CH_CFG_USE_EVENTS == TRUE
" FE=%lu OE=%lu NE=%lu"
#endif
" FlowCtrl=%u\n",
tx_dma_enabled ? '*' : ' ',
unsigned(tx_bytes),
rx_dma_enabled ? '*' : ' ',
unsigned(rx_bytes),
unsigned((tx_bytes * 10000) / dt_ms),
unsigned((rx_bytes * 10000) / dt_ms),
#if CH_CFG_USE_EVENTS == TRUE
_rx_stats_framing_errors,
_rx_stats_overrun_errors,
_rx_stats_noise_errors,
#endif
_flow_control);
}
#endif
Expand Down
15 changes: 15 additions & 0 deletions libraries/AP_HAL_ChibiOS/UARTDriver.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,10 @@
// enough for serial0 to serial9, plus IOMCU
#define UART_MAX_DRIVERS 11

#ifndef HAL_HAVE_LOW_NOISE_UART
#define HAL_HAVE_LOW_NOISE_UART 0
#endif

class ChibiOS::UARTDriver : public AP_HAL::UARTDriver {
public:
UARTDriver(uint8_t serial_num);
Expand Down Expand Up @@ -79,6 +83,10 @@ class ChibiOS::UARTDriver : public AP_HAL::UARTDriver {
uint8_t get_index(void) const {
return uint8_t(this - &_serial_tab[0]);
}

#if HAL_HAVE_LOW_NOISE_UART
bool low_noise_line;
bugobliterator marked this conversation as resolved.
Show resolved Hide resolved
#endif
};

bool wait_timeout(uint16_t n, uint32_t timeout_ms) override;
Expand Down Expand Up @@ -282,6 +290,13 @@ class ChibiOS::UARTDriver : public AP_HAL::UARTDriver {
// Getters for cumulative tx and rx counts
uint32_t get_total_tx_bytes() const override { return _tx_stats_bytes; }
uint32_t get_total_rx_bytes() const override { return _rx_stats_bytes; }
#if CH_CFG_USE_EVENTS == TRUE
uint32_t _rx_stats_framing_errors;
uint32_t _rx_stats_overrun_errors;
uint32_t _rx_stats_noise_errors;
event_listener_t err_listener;
bool err_listener_initialised;
#endif
#endif
};

Expand Down
19 changes: 19 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/defaults.parm
Original file line number Diff line number Diff line change
Expand Up @@ -6,3 +6,22 @@ ADSB_TYPE 1
SERIAL5_BAUD 57
SERIAL5_PROTOCOL 1
EK3_PRIMARY 1

NET_ENABLE 1
NET_OPTIONS 1
NET_DHCP 0
NET_P1_TYPE 1
NET_P1_PROTOCOL 2
NET_P1_IP0 192
NET_P1_IP1 168
NET_P1_IP2 144
NET_P1_IP3 10
NET_P1_PORT 14553

NET_P2_TYPE 4
NET_P2_PROTOCOL 2
NET_P2_IP0 192
NET_P2_IP1 168
NET_P2_IP2 144
NET_P2_IP3 100
NET_P2_PORT 14554
19 changes: 11 additions & 8 deletions libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -274,17 +274,20 @@ PG15 USART6_CTS USART6
PG8 USART6_RTS USART6

# primary <-> secondary
PE7 UART7_RX UART7
PE8 UART7_TX UART7
PE7 UART7_RX UART7 SPEED_VERYLOW LOW_NOISE
PE8 UART7_TX UART7 SPEED_VERYLOW

# order of UARTs (and USB)
SERIAL_ORDER OTG1 USART2 USART6 USART3 UART4 UART8 EMPTY UART7
SERIAL_ORDER OTG1 USART2 USART6 USART3 UART4 UART8 OTG2 UART7

EXT_FLASH_SIZE_MB 32
INT_FLASH_PRIMARY 1

# forward Serial traffic from USB OTG2 to Serial7(UART7)
define HAL_FORWARD_OTG2_SERIAL 7
define HAL_HAVE_DUAL_USB_CDC 1
define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_MAVLink2
define DEFAULT_SERIAL7_BAUD 2000000
# set protocol for UART7 to SerialProtocol_PPP
define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_PPP
define DEFAULT_SERIAL7_BAUD 8000000

define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR "192.168.144.100"
define AP_NETWORKING_DEFAULT_STATIC_NETMASK "255.255.255.0"
define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR "192.168.144.11"
define AP_NETWORKING_BACKEND_PPP 1
10 changes: 10 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/defaults.parm
Original file line number Diff line number Diff line change
@@ -1,2 +1,12 @@
SERIAL3_OPTIONS 8
SERIAL4_OPTIONS 8
NET_ENABLE 1
NET_P1_TYPE 3
NET_P1_PROTOCOL 2
NET_P1_IP0 192
NET_P1_IP1 168
NET_P1_IP2 144
NET_P1_IP3 100
NET_P1_PORT 14554

SYSID_THISMAV 2
16 changes: 11 additions & 5 deletions libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@ MCU STM32H7xx STM32H757xx
define CORE_CM7
define SMPS_PWR

env OPTIMIZE -Os

# crystal frequency
OSCILLATOR_HZ 24000000

Expand Down Expand Up @@ -39,7 +41,8 @@ PA6 RSSI_IN ADC1 SCALE(2)

# CAN config
PB14 GPIOCAN2_TERM OUTPUT HIGH

PC12 GPIOCAN1_SHUTDOWN OUTPUT LOW
PF1 GPIOCAN2_SHUTDOWN OUTPUT LOW

PA12 CAN1_TX CAN1
PB8 CAN1_RX CAN1
Expand Down Expand Up @@ -118,8 +121,8 @@ PA7 HP_UNIDIR_ENABLED OUTPUT HIGH GPIO(5)


# UART connected to FMU, uses DMA
PE7 UART7_RX UART7 SPEED_HIGH
PE8 UART7_TX UART7 SPEED_HIGH
PE7 UART7_RX UART7 SPEED_VERYLOW LOW_NOISE
PE8 UART7_TX UART7 SPEED_VERYLOW

# UART for SBUS out
PC7 USART6_RX USART6 SPEED_HIGH LOW
Expand All @@ -144,13 +147,16 @@ PD4 USART2_RTS USART2 SPEED_HIGH
PD3 USART2_CTS USART2 SPEED_HIGH

# order of UARTs
SERIAL_ORDER UART7 UART8 USART3 USART6 UART4 USART2
SERIAL_ORDER UART8 UART7 USART3 USART6 UART4 USART2

# use 2 MBaud when talking to primary controller
define DEFAULT_SERIAL0_BAUD 2000000
define DEFAULT_SERIAL1_BAUD 8000000
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_PPP
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_Sbus1
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_RCIN

define AP_NETWORKING_BACKEND_PPP 1

# only use pulse input for PPM, other protocols
# are on serial
define HAL_RCIN_PULSE_PPM_ONLY
Expand Down
33 changes: 29 additions & 4 deletions libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py
Original file line number Diff line number Diff line change
Expand Up @@ -1865,6 +1865,7 @@ def write_UART_config(self, f):
OTG2_index = None
devlist = []
have_rts_cts = False
have_low_noise = False
crash_uart = None

# write config for CrashCatcher UART
Expand All @@ -1878,6 +1879,14 @@ def write_UART_config(self, f):
f.write('#define IRQ_DISABLE_HAL_CRASH_SERIAL_PORT() nvicDisableVector(STM32_%s_NUMBER)\n' % crash_uart)
f.write('#define RCC_RESET_HAL_CRASH_SERIAL_PORT() rccReset%s(); rccEnable%s(true)\n' % (crash_uart, crash_uart))
f.write('#define HAL_CRASH_SERIAL_PORT_CLOCK STM32_%sCLK\n' % crash_uart)
# check if we have a UART with a low noise RX pin
for num, dev in enumerate(serial_list):
if not dev.startswith('UART') and not dev.startswith('USART'):
continue
rx_port = dev + '_RX'
if rx_port in self.bylabel and self.bylabel[rx_port].has_extra('LOW_NOISE'):
have_low_noise = True
break
for num, dev in enumerate(serial_list):
if dev.startswith('UART'):
n = int(dev[4:])
Expand All @@ -1904,12 +1913,20 @@ def write_UART_config(self, f):

if dev.startswith('OTG2'):
f.write(
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU2, 2, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, UINT8_MAX}\n' % dev) # noqa
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU2, 2, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, UINT8_MAX,' % dev) # noqa
if have_low_noise:
f.write('false}\n')
else:
f.write('}\n')
OTG2_index = serial_list.index(dev)
self.dual_USB_enabled = True
elif dev.startswith('OTG'):
f.write(
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU1, 1, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, UINT8_MAX}\n' % dev) # noqa
'#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU1, 1, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, UINT8_MAX,' % dev) # noqa
if have_low_noise:
f.write('false}\n')
else:
f.write('}\n')
else:
need_uart_driver = True
f.write(
Expand Down Expand Up @@ -1948,9 +1965,17 @@ def get_RTS_alt_function():
if s not in lib.AltFunction_map:
return "UINT8_MAX"
return lib.AltFunction_map[s]
if have_low_noise:
low_noise = 'false'
rx_port = dev + '_RX'
if rx_port in self.bylabel and self.bylabel[rx_port].has_extra('LOW_NOISE'):
low_noise = 'true'
f.write("%s, %s}\n" % (get_RTS_alt_function(), low_noise))
else:
f.write("%s}\n" % get_RTS_alt_function())

f.write("%s}\n" % get_RTS_alt_function())

if have_low_noise:
f.write('#define HAL_HAVE_LOW_NOISE_UART 1\n')
if have_rts_cts:
f.write('#define AP_FEATURE_RTSCTS 1\n')
if OTG2_index is not None:
Expand Down
59 changes: 59 additions & 0 deletions libraries/AP_Networking/AP_Networking_PPP.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,9 @@ extern const AP_HAL::HAL& hal;
#define LWIP_TCPIP_UNLOCK()
#endif

#define PPP_DEBUG_TX 0
#define PPP_DEBUG_RX 0

/*
output some data to the uart
*/
Expand All @@ -34,6 +37,27 @@ uint32_t AP_Networking_PPP::ppp_output_cb(ppp_pcb *pcb, const void *data, uint32
LWIP_UNUSED_ARG(pcb);
uint32_t remaining = len;
const uint8_t *ptr = (const uint8_t *)data;
#if PPP_DEBUG_TX
bool flag_end = false;
if (ptr[len-1] == 0x7E) {
flag_end = true;
remaining--;
}
if (ptr[0] == 0x7E) {
// send byte size
if (pkt_size > 0) {
printf("PPP: tx[%lu] %u\n", tx_index++, pkt_size);
}
// dump the packet
if (!(tx_index % 10)) {
for (uint32_t i = 0; i < pkt_size; i++) {
printf(" %02X", tx_bytes[i]);
}
printf("\n");
}
pkt_size = 0;
}
#endif
while (remaining > 0) {
const auto n = driver.uart->write(ptr, remaining);
if (n > 0) {
Expand All @@ -43,6 +67,22 @@ uint32_t AP_Networking_PPP::ppp_output_cb(ppp_pcb *pcb, const void *data, uint32
hal.scheduler->delay_microseconds(100);
}
}
#if PPP_DEBUG_TX
memcpy(&tx_bytes[pkt_size], data, len);
pkt_size += len;
if (flag_end) {
driver.uart->write(0x7E);
printf("PPP: tx[%lu] %u\n", tx_index++, pkt_size);
// dump the packet
if (!(tx_index % 10)) {
for (uint32_t i = 0; i < pkt_size; i++) {
printf(" %02X", tx_bytes[i]);
}
printf("\n");
}
pkt_size = 0;
}
#endif
return len;
}

Expand Down Expand Up @@ -224,6 +264,25 @@ void AP_Networking_PPP::ppp_loop(void)
} else {
hal.scheduler->delay_microseconds(200);
}
#if PPP_DEBUG_RX
auto pppos = (pppos_pcb *)ppp->link_ctx_cb;
for (uint32_t i = 0; i < n; i++) {
if (buf[i] == 0x7E && last_ppp_frame_size != 1) {
// dump the packet
if (pppos->bad_pkt) {
printf("PPP: rx[%lu] %u\n", rx_index, last_ppp_frame_size);
for (uint32_t j = 0; j < last_ppp_frame_size; j++) {
printf("0x%02X,", rx_bytes[j]);
}
printf("\n");
hal.scheduler->delay(1);
}
rx_index++;
last_ppp_frame_size = 0;
}
rx_bytes[last_ppp_frame_size++] = buf[i];
}
#endif
}
}
}
Expand Down
Loading