aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common/init.d/3030_io_camflyer
blob: 65f01c97437ba0c7aeb2b03235c825ecb9bf3ad7 (plain) (blame)
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
#!nsh

echo "[init] PX4FMU v1, v2 with or without IO on Camflyer"

#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
	# Set all params here, then disable autoconfig
	# TODO
	
	param set SYS_AUTOCONFIG 0
	param save
fi
 
#
# Force some key parameters to sane values
# MAV_TYPE     1 = fixed wing
#
param set MAV_TYPE 1

#
# Start and configure PX4IO or FMU interface
#
if px4io detect
then
	# Start MAVLink (depends on orb)
	mavlink start

	sh /etc/init.d/rc.io
	# Limit to 100 Hz updates and (implicit) 50 Hz PWM
	px4io limit 100
else
	# Start MAVLink (on UART1 / ttyS0)
	mavlink start -d /dev/ttyS0

	fmu mode_pwm
	param set BAT_V_SCALING 0.004593
	set EXIT_ON_END yes
fi

#
# Load mixer and start controllers (depends on px4io)
#
if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ]
then
	echo "Using /fs/microsd/etc/mixers/FMU_Q.mix"
	mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix
else
	echo "Using /etc/mixers/FMU_Q.mix"
	mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
fi

#
# Start common fixedwing apps
#
sh /etc/init.d/rc.fixedwing