From c5de2cfe0d005fe77ec0a23304a4e3efd02c0e10 Mon Sep 17 00:00:00 2001 From: modaltb <50114502+modaltb@users.noreply.github.com> Date: Mon, 9 Dec 2019 09:39:17 -0800 Subject: [PATCH] modalai_fc-v1: Add support for VOXL Flight board defaults, handle default MAVLink setups (#13677) - Handle out of box config for Flight Core and VOXL Flight - Handle AUTOCNF use case - Hard code TELEM2 MAVLink Instace 1 for VOXL Flight --- boards/modalai/fc-v1/init/rc.board_defaults | 118 ++++++++++++++++++-- boards/modalai/fc-v1/src/manifest.c | 11 +- 2 files changed, 120 insertions(+), 9 deletions(-) diff --git a/boards/modalai/fc-v1/init/rc.board_defaults b/boards/modalai/fc-v1/init/rc.board_defaults index 081c965070..197a39dded 100644 --- a/boards/modalai/fc-v1/init/rc.board_defaults +++ b/boards/modalai/fc-v1/init/rc.board_defaults @@ -1,24 +1,126 @@ #!/bin/sh # # ModalAI FC-v1 specific board defaults +# Maintainer: travis@modalai.com #------------------------------------------------------------------------------ +# +# Summary: +# Flight Core can be used on many airframes, but is meant to be paired with +# VOXL (either through a cable or in the combo board flavor). For this reason +# this script has a bit more Logic (aka Bobby Tarantino) than normal. +# +# Flight Core Version Information: +# V100 - Flight Core Stand Alone configuration +# V110 - Flight Core VOXL-Flight configuration +# +# +# Common settings across Flight Core configurations +# if [ $AUTOCNF = yes ] then - # Disable safety switch by default + # + # Disable safety switch by default (pull high to 3.3V to enable) + # V100 - J13 pin 5 + # V110 - J1011 pin 5 + # param set CBRK_IO_SAFETY 22027 +fi + +# +# Stand Alone configuration +# +if ver hwtypecmp V100 +then + echo "Configuring Flight Core - V100" # - # TELEM2 /dev/ttyS4 + # In Flight Core, J1 and J4 can be setup to be used as serial ports for TELEM2 + # and TELEM3 respectively, and connected to VOXL via cables. We'll configure + # this out of the box. The user can later change this if they want, as these + # are configurable and not necessarily required to be used with VOXL. # - # In the VOXL-FMU, this port is connect to the VOXL internally - # In the FMU, this J1 port can connect to the VOXL J12 - # By default, we use this UART connection with MAVLink at 921.6kHz + if [ $AUTOCNF = no ] + then + if param compare MAV_1_CONFIG 0 + then + echo "V100 - Defualt configuration TELEM2 on /dev/ttyS4 at 921600 in Normal Mode" + param set MAV_1_CONFIG 102 # TELEM2 + param set MAV_1_MODE 0 # normal + param set SER_TEL2_BAUD 921600 # VIO data + fi + if param compare MAV_2_CONFIG 0 + then + echo "V100 - Defualt configuration TELEM3 on /dev/ttyS1 at 57600 in Normal Mode" + param set MAV_2_CONFIG 103 # TELEM3 + param set MAV_2_MODE 0 # normal + param set SER_TEL3_BAUD 57600 # standard data + fi + fi + + # User is setting defaults, so let's do it! + if [ $AUTOCNF = yes ] + then + echo "V100 - Auto Configuring TELEM2 on /dev/ttyS4 at 921600 in Normal Mode" + param set MAV_1_CONFIG 102 # TELEM2 + param set MAV_1_MODE 0 # normal + param set SER_TEL2_BAUD 921600 # VIO data + + echo "V100 - Auto Configuring TELEM3 on /dev/ttyS1 at 57600 in Normal Mode" + param set MAV_2_CONFIG 103 # TELEM3 + param set MAV_2_MODE 0 # normal + param set SER_TEL3_BAUD 57600 # standard data + fi +fi + +# +# VOXL-Flight configuration +# +if ver hwtypecmp V110 +then + echo "Configuring VOXL-Flight - V110" + # - param set MAV_1_CONFIG 102 # TELEM2 - param set MAV_1_MODE 0 # normal - param set SER_TEL2_BAUD 921600 + # TELEM2 port is physically routed in the PCB, thus not configurable. + # The following will detect a fresh install, or if the user has changed the setting + # and revert to the VOXL-Flight defaults. This does allow the user to change the mode + # and baud rates if they choose to do so, although VOXL is expecting what is set below + # + if [ $AUTOCNF = no ] + then + if ! param compare MAV_1_CONFIG 102 + then + echo "V110 - Defualt configuration TELEM2 on /dev/ttyS4 at 921600 in Normal Mode" + param set MAV_1_CONFIG 102 # TELEM2 + param set MAV_1_MODE 0 # normal + param set SER_TEL2_BAUD 921600 + fi + # + # J1002 is setup as a spare serial port, if not setup by the user let's default it to TELEM3 + # + if param compare MAV_2_CONFIG 0 + then + echo "V110 - Defualt configuration TELEM3 on /dev/ttyS1 at 57600 in Normal Mode" + param set MAV_2_CONFIG 103 # TELEM3 + param set MAV_2_MODE 0 # normal + param set SER_TEL3_BAUD 57600 # standard data + fi + fi + + # User is setting defaults, so let's do it! + if [ $AUTOCNF = yes ] + then + echo "V110 - Auto Configuring TELEM2 on /dev/ttyS4 at 921600 in Normal Mode" + param set MAV_1_CONFIG 102 # TELEM2 + param set MAV_1_MODE 0 # normal + param set SER_TEL2_BAUD 921600 + + echo "V110 - Auto Configuring TELEM3 on /dev/ttyS1 at 57600 in Normal Mode" + param set MAV_2_CONFIG 103 # TELEM3 + param set MAV_2_MODE 0 # normal + param set SER_TEL3_BAUD 57600 + fi fi set LOGGER_BUF 64 diff --git a/boards/modalai/fc-v1/src/manifest.c b/boards/modalai/fc-v1/src/manifest.c index 344aa46250..26c7b0d5f3 100644 --- a/boards/modalai/fc-v1/src/manifest.c +++ b/boards/modalai/fc-v1/src/manifest.c @@ -79,8 +79,17 @@ static const px4_hw_mft_item_t hw_mft_list_fc0100[] = { }, }; +static const px4_hw_mft_item_t hw_mft_list_fc0110[] = { + { + .present = 0, + .mandatory = 0, + .connection = px4_hw_con_unknown, + }, +}; + static px4_hw_mft_list_entry_t mft_lists[] = { - {0x0000, hw_mft_list_fc0100, arraySize(hw_mft_list_fc0100)} + {0x0000, hw_mft_list_fc0100, arraySize(hw_mft_list_fc0100)}, + {0x0100, hw_mft_list_fc0110, arraySize(hw_mft_list_fc0110)} };