aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common/init.d/10_dji_f330
blob: 743dce9ef6f69542d1b978880a867f34cd189d7f (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
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
#!nsh

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

#
# 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

	param set MC_ATTRATE_D		0.004
	param set MC_ATTRATE_I		0.0
	param set MC_ATTRATE_P		0.12
	param set MC_ATT_D		0.0
	param set MC_ATT_I		0.0
	param set MC_ATT_P		7.0
	param set MC_YAWPOS_D		0.0
	param set MC_YAWPOS_I		0.0
	param set MC_YAWPOS_P		2.0
	param set MC_YAWRATE_D		0.005
	param set MC_YAWRATE_I		0.2
	param set MC_YAWRATE_P		0.3
	param set NAV_TAKEOFF_ALT	1.0
	param set MPC_TILT_MAX		0.5
	param set MPC_THR_MAX		0.7
	param set MPC_THR_MIN		0.3
	param set MPC_XY_D		0
	param set MPC_XY_P		0.5
	param set MPC_XY_VEL_D		0
	param set MPC_XY_VEL_I		0
	param set MPC_XY_VEL_MAX	2
	param set MPC_XY_VEL_P		0.2
	param set MPC_Z_D		0
	param set MPC_Z_P		1
	param set MPC_Z_VEL_D		0
	param set MPC_Z_VEL_I		0.10
	param set MPC_Z_VEL_MAX		2
	param set MPC_Z_VEL_P		0.20

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

set EXIT_ON_END no

#
# 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
	# Set PWM values for DJI ESCs
	px4io idle 900 900 900 900
	px4io min 1200 1200 1200 1200
	px4io max 1800 1800 1800 1800
else
	# Start MAVLink (on UART1 / ttyS0)
	mavlink start -d /dev/ttyS0
	usleep 5000
	fmu mode_pwm
	set EXIT_ON_END yes
fi

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

#
# Set PWM output frequency
#
pwm -u 400 -m 0xff

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

if [ $EXIT_ON_END == yes ]
then
	exit
fi