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

Don't show params for serial ports that don't exist #12836

Merged
merged 2 commits into from
Nov 18, 2019
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
4 changes: 4 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py
Original file line number Diff line number Diff line change
Expand Up @@ -1030,6 +1030,10 @@ def write_UART_config(f):
#define HAL_USE_SERIAL HAL_USE_SERIAL_USB
#endif
''')
num_uarts = len(devlist)
if 'IOMCU_UART' in config:
num_uarts -= 1
f.write('#define HAL_UART_NUM_SERIAL_PORTS %u\n' % num_uarts)

def write_UART_config_bootloader(f):
'''write UART config defines'''
Expand Down
48 changes: 47 additions & 1 deletion libraries/AP_SerialManager/AP_SerialManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ extern const AP_HAL::HAL& hal;
#endif

const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
#if SERIALMANAGER_NUM_PORTS > 0
// @Param: 0_BAUD
// @DisplayName: Serial0 baud rate
// @Description: The baud rate used on the USB console. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Expand All @@ -84,7 +85,9 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO("0_PROTOCOL", 11, AP_SerialManager, state[0].protocol, SerialProtocol_MAVLink2),

#endif

#if SERIALMANAGER_NUM_PORTS > 1
// @Param: 1_PROTOCOL
// @DisplayName: Telem1 protocol selection
// @Description: Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details.
Expand All @@ -99,7 +102,9 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
// @User: Standard
AP_GROUPINFO("1_BAUD", 2, AP_SerialManager, state[1].baud, AP_SERIALMANAGER_MAVLINK_BAUD/1000),
#endif

#if SERIALMANAGER_NUM_PORTS > 2
// @Param: 2_PROTOCOL
// @DisplayName: Telemetry 2 protocol selection
// @Description: Control what protocol to use on the Telem2 port. Note that the Frsky options require external converter hardware. See the wiki for details.
Expand All @@ -114,7 +119,9 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
// @User: Standard
AP_GROUPINFO("2_BAUD", 4, AP_SerialManager, state[2].baud, AP_SERIALMANAGER_MAVLINK_BAUD/1000),
#endif

#if SERIALMANAGER_NUM_PORTS > 3
// @Param: 3_PROTOCOL
// @DisplayName: Serial 3 (GPS) protocol selection
// @Description: Control what protocol Serial 3 (GPS) should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
Expand All @@ -129,7 +136,9 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
// @User: Standard
AP_GROUPINFO("3_BAUD", 6, AP_SerialManager, state[3].baud, AP_SERIALMANAGER_GPS_BAUD/1000),
#endif

#if SERIALMANAGER_NUM_PORTS > 4
// @Param: 4_PROTOCOL
// @DisplayName: Serial4 protocol selection
// @Description: Control what protocol Serial4 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
Expand All @@ -144,7 +153,9 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
// @User: Standard
AP_GROUPINFO("4_BAUD", 8, AP_SerialManager, state[4].baud, AP_SERIALMANAGER_GPS_BAUD/1000),
#endif

#if SERIALMANAGER_NUM_PORTS > 5
// @Param: 5_PROTOCOL
// @DisplayName: Serial5 protocol selection
// @Description: Control what protocol Serial5 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
Expand All @@ -159,9 +170,11 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
// @User: Standard
AP_GROUPINFO("5_BAUD", 10, AP_SerialManager, state[5].baud, SERIAL5_BAUD),
#endif

// index 11 used by 0_PROTOCOL

#if SERIALMANAGER_NUM_PORTS > 6
// @Param: 6_PROTOCOL
// @DisplayName: Serial6 protocol selection
// @Description: Control what protocol Serial6 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
Expand All @@ -176,54 +189,67 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
// @User: Standard
AP_GROUPINFO("6_BAUD", 13, AP_SerialManager, state[6].baud, SERIAL6_BAUD),
#endif

#if SERIALMANAGER_NUM_PORTS > 1
// @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
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("1_OPTIONS", 14, AP_SerialManager, state[1].options, 0),
#endif

#if SERIALMANAGER_NUM_PORTS > 2
// @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
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("2_OPTIONS", 15, AP_SerialManager, state[2].options, 0),
#endif

#if SERIALMANAGER_NUM_PORTS > 3
// @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
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("3_OPTIONS", 16, AP_SerialManager, state[3].options, 0),
#endif

#if SERIALMANAGER_NUM_PORTS > 4
// @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
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("4_OPTIONS", 17, AP_SerialManager, state[4].options, 0),
#endif

#if SERIALMANAGER_NUM_PORTS > 5
// @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
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("5_OPTIONS", 18, AP_SerialManager, state[5].options, 0),
#endif

#if SERIALMANAGER_NUM_PORTS > 6
// @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
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("6_OPTIONS", 19, AP_SerialManager, state[6].options, 0),
#endif

// @Param: _PASS1
// @DisplayName: Serial passthru first port
Expand All @@ -247,6 +273,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @User: Advanced
AP_GROUPINFO("_PASSTIMO", 22, AP_SerialManager, passthru_timeout, 15),

#if SERIALMANAGER_NUM_PORTS > 7
// @Param: 7_PROTOCOL
// @DisplayName: Serial7 protocol selection
// @Description: Control what protocol Serial7 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
Expand All @@ -269,6 +296,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("7_OPTIONS", 25, AP_SerialManager, state[7].options, 0),
#endif

AP_GROUPEND
};
Expand All @@ -288,10 +316,12 @@ AP_SerialManager::AP_SerialManager()
void AP_SerialManager::init_console()
{
// initialise console immediately at default size and baud
#if SERIALMANAGER_NUM_PORTS > 0
state[0].uart = hal.uartA; // serial0, uartA, always console
state[0].uart->begin(AP_SERIALMANAGER_CONSOLE_BAUD,
AP_SERIALMANAGER_CONSOLE_BUFSIZE_RX,
AP_SERIALMANAGER_CONSOLE_BUFSIZE_TX);
#endif
}

extern bool g_nsh_should_exit;
Expand All @@ -303,17 +333,33 @@ void AP_SerialManager::init()
passthru_port2.set_and_save_ifchanged(-1);

// initialise pointers to serial ports
#if SERIALMANAGER_NUM_PORTS > 1
state[1].uart = hal.uartC; // serial1, uartC, normally telem1
#endif
#if SERIALMANAGER_NUM_PORTS > 2
state[2].uart = hal.uartD; // serial2, uartD, normally telem2
#endif
#if SERIALMANAGER_NUM_PORTS > 3
state[3].uart = hal.uartB; // serial3, uartB, normally 1st GPS
#endif
#if SERIALMANAGER_NUM_PORTS > 4
state[4].uart = hal.uartE; // serial4, uartE, normally 2nd GPS
#endif
#if SERIALMANAGER_NUM_PORTS > 5
state[5].uart = hal.uartF; // serial5
#endif
#if SERIALMANAGER_NUM_PORTS > 6
state[6].uart = hal.uartG; // serial6
#endif
#if SERIALMANAGER_NUM_PORTS > 7
state[7].uart = hal.uartH; // serial7
#endif

#if SERIALMANAGER_NUM_PORTS > 0
if (state[0].uart == nullptr) {
init_console();
}
#endif

// initialise serial ports
for (uint8_t i=1; i<SERIALMANAGER_NUM_PORTS; i++) {
Expand Down
6 changes: 5 additions & 1 deletion libraries/AP_SerialManager/AP_SerialManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,12 @@
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Param/AP_Param.h>

// we have hal.uartA to hal.uartH
#ifdef HAL_UART_NUM_SERIAL_PORTS
#define SERIALMANAGER_NUM_PORTS HAL_UART_NUM_SERIAL_PORTS
#else
// assume max 8 ports
#define SERIALMANAGER_NUM_PORTS 8
#endif

// console default baud rates and buffer sizes
#ifdef HAL_SERIAL0_BAUD_DEFAULT
Expand Down