|
|
|
#!/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 (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"
|
|
|
|
|
|
|
|
#
|
|
|
|
# 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.
|
|
|
|
#
|
|
|
|
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"
|
|
|
|
|
|
|
|
#
|
|
|
|
# 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
|
|
|
|
|
|
|
|
safety_button start
|