10_io_f330 2.06 KB
Newer Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
#!nsh
#
# Flight startup script for PX4FMU+PX4IO
#
 
# disable USB and autostart
set USB no
set MODE custom

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

18
	param set MC_ATTRATE_D	         0.005
19
	param set MC_ATTRATE_I	         0.0
20
	param set MC_ATTRATE_P	         0.1
21
22
	param set MC_ATT_D	         0.0
	param set MC_ATT_I	         0.0
23
	param set MC_ATT_P	         4.5
24
25
	param set MC_RCLOSS_THR	         0.0
	param set MC_YAWPOS_D	         0.0
26
27
	param set MC_YAWPOS_I	         0.3
	param set MC_YAWPOS_P	         0.6
28
29
	param set MC_YAWRATE_D	         0.0
	param set MC_YAWRATE_I	         0.0
30
	param set MC_YAWRATE_P	         0.1
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46

	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
47
48
49
50
51

#
# Start the commander (depends on orb, mavlink)
#
commander start
52
53
54
55
 
#
# Start PX4IO interface (depends on orb, commander)
#
56
57
58
59
60
61
62
if px4io start
then
	pwm -u 400 -m 0xff
else
	# SOS
	tone_alarm 6
fi
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
 
#
# 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 1200 1200 1200 1200

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

mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
 
#
# 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
100

101
multirotor_att_control start
102

103
#
104
# Disable px4io topic limiting and start logging
105
#
106
if [ $BOARD == fmuv1 ]
107
then
108
109
110
111
	px4io limit 200
	sdlog2 start -r 50 -a -b 16
else
	px4io limit 400
112
	sdlog2 start -r 200 -a -b 16
113
fi