aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common/init.d/15_io_tbs
blob: 237bb4267c90bc62f8e788bf8444e279d94fdc0f (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
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
#!nsh
#
# Flight startup script for PX4FMU+PX4IO on a Team Blacksheep Discovery quad
# with stock DJI ESCs, motors and props.
#
 
# disable USB and autostart
set USB no
set MODE custom

#
# Start the ORB (first app to start)
#
uorb start

#
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
then
	param load /fs/microsd/params
fi

#
# 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.006
	param set MC_ATTRATE_I	         0.0
	param set MC_ATTRATE_P	         0.17
	param set MC_ATT_D	         0.0
	param set MC_ATT_I	         0.0
	param set MC_ATT_P	         5.0
	param set MC_RCLOSS_THR	         0.0
	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

	param save /fs/microsd/params
fi
 
#
# Force some key parameters to sane values
# MAV_TYPE     1 = fixed wing, 2 = quadrotor, 13 = hexarotor
#              see https://pixhawk.ethz.ch/mavlink/
#
param set MAV_TYPE 2
 
#
# Start MAVLink (depends on orb)
#
mavlink start
usleep 5000

#
# Start the commander (depends on orb, mavlink)
#
commander start

#
# Start PX4IO interface (depends on orb, commander)
#
px4io start
pwm -u 400 -m 0xff
 
#
# Allow PX4IO to recover from midair restarts.
# This is very unlikely, but quite safe and robust.
px4io recovery

#
# This sets a PWM right after startup (regardless of safety button)
#
px4io idle 900 900 900 900

#
# The values are for spinning motors when armed using DJI ESCs
#
px4io min 1180 1180 1180 1180

#
# Upper limits could be higher, this is on the safe side
#
px4io max 1800 1800 1800 1800

#
# Load the mixer for a quad with wide arms
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
 
#
# Start the sensors (depends on orb, px4io)
#
sh /etc/init.d/rc.sensors
 
#
# Start GPS interface (depends on orb)
#
gps start
 
#
# Start the attitude estimator (depends on orb)
#
attitude_estimator_ekf start

#
# Start the controllers (depends on orb)
#
multirotor_att_control start

#
# Disable px4io topic limiting and start logging
#
if [ $BOARD == fmuv1 ]
then
	px4io limit 200
	sdlog2 start -r 50 -a -b 16
	if blinkm start
	then
		blinkm systemstate
	fi
else
	px4io limit 400
	sdlog2 start -r 200 -a -b 16
	if rgbled start
	then
		#rgbled systemstate
	fi
fi