Fix hardware detection of Flight Core standalone configuration

This commit is contained in:
Travis Bottalico
2020-01-30 21:04:44 -08:00
committed by Daniel Agar
parent 9e38fee1c6
commit 9d2a37b35d
3 changed files with 19 additions and 19 deletions
+8 -8
View File
@@ -11,7 +11,7 @@
# this script has a bit more Logic (aka Bobby Tarantino) than normal.
#
# Flight Core Version Information:
# V100 - Flight Core Stand Alone configuration
# V106 - Flight Core Stand Alone configuration
# V110 - Flight Core VOXL-Flight configuration
#
@@ -22,7 +22,7 @@ if [ $AUTOCNF = yes ]
then
#
# Disable safety switch by default (pull high to 3.3V to enable)
# V100 - J13 pin 5
# V106 - J13 pin 5
# V110 - J1011 pin 5
#
param set CBRK_IO_SAFETY 22027
@@ -31,9 +31,9 @@ fi
#
# Stand Alone configuration
#
if ver hwtypecmp V100
if ver hwtypecmp V106
then
echo "Configuring Flight Core - V100"
echo "Configuring Flight Core - V106"
#
# In Flight Core, J1 and J4 can be setup to be used as serial ports for TELEM2
@@ -45,14 +45,14 @@ then
then
if param compare MAV_1_CONFIG 0
then
echo "V100 - Defualt configuration TELEM2 on /dev/ttyS4 at 921600 in Normal Mode"
echo "V106 - 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"
echo "V106 - 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
@@ -62,12 +62,12 @@ then
# 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"
echo "V106 - 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"
echo "V106 - 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
+1 -1
View File
@@ -262,7 +262,7 @@
#define BOARD_HAS_HW_VERSIONING
#define GPIO_HW_VER_REV_DRIVE /* PA4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
#define GPIO_HW_REV_SENSE /* PF5 */ ADC3_GPIO(15)
#define GPIO_HW_VER_SENSE /* PF4 */ ADC3_GPIO(14)
#define HW_INFO_INIT {'V','1','x', 'x',0}
+10 -10
View File
@@ -71,6 +71,14 @@ static const px4_hw_mft_item_t device_unsupported = {0, 0, 0};
// List of components on a specific board configuration
// The index of those components is given by the enum (px4_hw_mft_item_id_t)
// declared in board_common.h
static const px4_hw_mft_item_t hw_mft_list_fc0006[] = {
{
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
};
static const px4_hw_mft_item_t hw_mft_list_fc0100[] = {
{
.present = 0,
@@ -79,17 +87,9 @@ 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)},
{0x0100, hw_mft_list_fc0110, arraySize(hw_mft_list_fc0110)}
{0x0006, hw_mft_list_fc0006, arraySize(hw_mft_list_fc0006)},
{0x0100, hw_mft_list_fc0100, arraySize(hw_mft_list_fc0100)}
};