forked from Archive/PX4-Autopilot
83 lines
1.3 KiB
Plaintext
83 lines
1.3 KiB
Plaintext
#!nsh
|
|
|
|
echo "[init] PX4FMU v1, v2 with or without IO on HK Bixler"
|
|
|
|
#
|
|
# Load default params for this platform
|
|
#
|
|
if param compare SYS_AUTOCONFIG 1
|
|
then
|
|
# Set all params here, then disable autoconfig
|
|
# TODO
|
|
|
|
param set SYS_AUTOCONFIG 0
|
|
param save
|
|
fi
|
|
|
|
#
|
|
# Force some key parameters to sane values
|
|
# MAV_TYPE 1 = fixed wing
|
|
#
|
|
param set MAV_TYPE 1
|
|
|
|
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
|
|
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
|
px4io limit 100
|
|
else
|
|
# Start MAVLink (on UART1 / ttyS0)
|
|
mavlink start -d /dev/ttyS0
|
|
usleep 5000
|
|
fmu mode_pwm
|
|
param set BAT_V_SCALING 0.004593
|
|
set EXIT_ON_END yes
|
|
fi
|
|
|
|
#
|
|
# Start the sensors and test them.
|
|
#
|
|
sh /etc/init.d/rc.sensors
|
|
|
|
#
|
|
# Start logging (depends on sensors)
|
|
#
|
|
sh /etc/init.d/rc.logging
|
|
|
|
#
|
|
# Start the commander.
|
|
#
|
|
commander start
|
|
|
|
#
|
|
# Start GPS interface (depends on orb)
|
|
#
|
|
gps start
|
|
|
|
#
|
|
# Start the attitude and position estimator
|
|
#
|
|
att_pos_estimator_ekf start
|
|
|
|
#
|
|
# Load mixer and start controllers (depends on px4io)
|
|
#
|
|
mixer load /dev/pwm_output /etc/mixers/FMU_AERT.mix
|
|
fw_att_control start
|
|
# Not ready yet for prime-time
|
|
#fw_pos_control_l1 start
|
|
|
|
if [ $EXIT_ON_END == yes ]
|
|
then
|
|
exit
|
|
fi
|