aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
blob: acd8027fb594247918296c93baaab309ae209a6d (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
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
#!nsh

echo "[init] 666_fmu_q_x550: PX4FMU Quad X550 with or without IO"

#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
	# Set all params here, then disable autoconfig
	param set MC_ATTRATE_P 0.14
	param set MC_ATTRATE_I 0
	param set MC_ATTRATE_D 0.006
	param set MC_ATT_P 5.5
	param set MC_ATT_I 0
	param set MC_ATT_D 0
	param set MC_YAWPOS_D 0
	param set MC_YAWPOS_I 0
	param set MC_YAWPOS_P 0.6
	param set MC_YAWRATE_D 0
	param set MC_YAWRATE_I 0
	param set MC_YAWRATE_P 0.08
	param set RC_SCALE_PITCH 1
	param set RC_SCALE_ROLL 1
	param set RC_SCALE_YAW 3

	param set SYS_AUTOCONFIG 0
	param save
fi

#
# Force some key parameters to sane values
# MAV_TYPE     2 = quadrotor
#
param set MAV_TYPE 2

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

	sh /etc/init.d/rc.io
else
	# Start MAVLink (on UART1 / ttyS0)
	mavlink start -d /dev/ttyS0
	usleep 5000
	fmu mode_pwm
	param set BAT_V_SCALING 0.004593
	set EXIT_ON_END yes
fi

#
# Load mixer
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix

#
# Set PWM output frequency
#
pwm rate -c 1234 -r 400

#
# Set disarmed, min and max PWM signals
#
pwm disarmed -c 1234 -p 900
pwm min -c 1234 -p 1100
pwm max -c 1234 -p 1900

#
# Start common for all multirotors apps
#
sh /etc/init.d/rc.multirotor