rc.board_defaults
2.72 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
#
# 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:
# V106 - Flight Core Stand Alone configuration
# V110 - Flight Core VOXL-Flight configuration
#
#
# Common settings across Flight Core configurations
#
# Disable safety switch by default (pull high to 3.3V to enable)
# V106 - J13 pin 5
# V110 - J1011 pin 5
param set-default CBRK_IO_SAFETY 22027
#
# Stand Alone configuration
#
if ver hwtypecmp V106
then
echo "Configuring Flight Core - V106"
#
# In Flight Core, J1 can be setup to be used as a serial port for TELEM2
# 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 "V106 - Defualt configuration TELEM2 on /dev/ttyS4 at 921600 in Normal Mode"
# TELEM2
param set-default MAV_1_CONFIG 102
# Onboard
param set-default MAV_1_MODE 2
# VIO data
param set-default SER_TEL2_BAUD 921600
fi
fi
# User is setting defaults, so let's do it!
if [ $AUTOCNF = yes ]
then
echo "V106 - Auto Configuring TELEM2 on /dev/ttyS4 at 921600 in Normal Mode"
# TELEM2
param set-default MAV_1_CONFIG 102
# Onboard
param set-default MAV_1_MODE 2
# VIO data
param set-default SER_TEL2_BAUD 921600
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 and mode 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 - Default configuration TELEM2 on /dev/ttyS4 at 921600 in Normal Mode"
# TELEM2
param set-default MAV_1_CONFIG 102
# Onboard
param set-default MAV_1_MODE 2
param set-default SER_TEL2_BAUD 921600
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"
# TELEM2
param set-default MAV_1_CONFIG 102
# Onboard
param set-default MAV_1_MODE 2
param set-default SER_TEL2_BAUD 921600
fi
fi
safety_button start