forked from Archive/PX4-Autopilot
67 lines
1.0 KiB
Plaintext
67 lines
1.0 KiB
Plaintext
#!nsh
|
|
#
|
|
# Flight startup script for PX4FMU with PWM outputs.
|
|
#
|
|
|
|
# Disable the USB interface
|
|
set USB no
|
|
|
|
# Disable autostarting other apps
|
|
set MODE custom
|
|
|
|
echo "[init] doing PX4FMU Quad startup..."
|
|
|
|
#
|
|
# Start the ORB
|
|
#
|
|
uorb start
|
|
|
|
#
|
|
# Load microSD params
|
|
#
|
|
echo "[init] loading microSD params"
|
|
param select /fs/microsd/parameters
|
|
if [ -f /fs/microsd/parameters ]
|
|
then
|
|
param load /fs/microsd/parameters
|
|
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
|
|
#
|
|
mavlink start -d /dev/ttyS0 -b 57600
|
|
usleep 5000
|
|
|
|
#
|
|
# Start the sensors and test them.
|
|
#
|
|
sh /etc/init.d/rc.sensors
|
|
|
|
#
|
|
# Start the commander.
|
|
#
|
|
commander start
|
|
|
|
#
|
|
# Start the attitude estimator
|
|
#
|
|
attitude_estimator_ekf start
|
|
|
|
echo "[init] starting PWM output"
|
|
fmu mode_pwm
|
|
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
|
|
|
#
|
|
# Start attitude control
|
|
#
|
|
multirotor_att_control start
|
|
|
|
echo "[init] startup done, exiting"
|
|
exit |