10016_3dr_iris 1.24 KB
Newer Older
1
2
#!nsh

3
echo "[init] 3DR Iris Quad"
Simon Wilks's avatar
Simon Wilks committed
4

5
6
7
8
9
10
11
12
#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
	# Set all params here, then disable autoconfig
	param set SYS_AUTOCONFIG 0

13
	param set MC_ATTRATE_D 0.004
14
	param set MC_ATTRATE_I 0.0
15
	param set MC_ATTRATE_P 0.13
16
17
	param set MC_ATT_D 0.0
	param set MC_ATT_I 0.0
18
	param set MC_ATT_P 9.0
19
20
21
22
23
24
	param set MC_YAWPOS_D 0.0
	param set MC_YAWPOS_I 0.15
	param set MC_YAWPOS_P 0.5
	param set MC_YAWRATE_D 0.0
	param set MC_YAWRATE_I 0.0
	param set MC_YAWRATE_P 0.2
25

26
	param save
27
fi
28

29
30
#
# Force some key parameters to sane values
31
# MAV_TYPE     2 = quadrotor
32
33
#
param set MAV_TYPE 2
34

35
#
36
# Start and configure PX4IO or FMU interface
37
#
38
39
40
41
42
43
44
45
46
47
48
49
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
Lorenz Meier's avatar
Lorenz Meier committed
50
	param set BAT_V_SCALING 0.0098
51
52
	set EXIT_ON_END yes
fi
53

54
#
55
# Load the mixer for a quad with wide arms
56
#
57
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
58

59
#
60
# Set PWM output frequency
61
#
62
63
64
65
66
67
pwm rate -c 1234 -r 400

#
# Set disarmed, min and max PWM signals
#
pwm disarmed -c 1234 -p 900
68
pwm min -c 1234 -p 1050
69

70
#
71
# Start common for all multirotors apps
72
#
73
sh /etc/init.d/rc.multirotor