aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common/init.d/1002_rc_fw_state.hil
blob: 7b9f41bf6d9f4c0ad53f88b91ed5007a2592d878 (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
#!nsh
#
# USB HIL start
#

echo "[HIL] HILStar starting in state-HIL mode.."

#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
	# Set all params here, then disable autoconfig
	
	param set FW_P_D 0
	param set FW_P_I 0
	param set FW_P_IMAX 15
	param set FW_P_LIM_MAX 50
	param set FW_P_LIM_MIN -50
	param set FW_P_P 60
	param set FW_P_RMAX_NEG 0
	param set FW_P_RMAX_POS 0
	param set FW_P_ROLLFF 1.1
	param set FW_R_D 0
	param set FW_R_I 5
	param set FW_R_IMAX 20
	param set FW_R_P 100
	param set FW_R_RMAX 100
	param set FW_THR_CRUISE 0.65
	param set FW_THR_MAX 1
	param set FW_THR_MIN 0
	param set FW_T_SINK_MAX 5.0
	param set FW_T_SINK_MIN 4.0
	param set FW_Y_ROLLFF 1.1

	param set SYS_AUTOCONFIG 0
	param save
fi

# Allow USB some time to come up
sleep 1
# Tell MAVLink that this link is "fast"
mavlink start -b 230400 -d /dev/ttyACM0

# Create a fake HIL /dev/pwm_output interface
hil mode_pwm

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

#
# Check if we got an IO
#
if px4io start
then
	echo "IO started"
else
	fmu mode_serial
	echo "FMU started"
fi

#
# Start the sensors (depends on orb, px4io)
#
sh /etc/init.d/rc.sensors
 
#
# Load mixer and start controllers (depends on px4io)
#
mixer load /dev/pwm_output /etc/mixers/FMU_AET.mix
fw_pos_control_l1 start
fw_att_control start

echo "[HIL] setup done, running"