Use common rc.multirotor script (now only in 01_fmu_quad_x).

This commit is contained in:
Anton Babushkin 2013-08-24 20:32:46 +02:00
parent 8579d0b7c9
commit 41dfdfb1a4
2 changed files with 54 additions and 28 deletions

View File

@ -64,42 +64,19 @@ mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
# Start the sensors and test them.
# Start common for all multirotors apps
#
sh /etc/init.d/rc.sensors
sh /etc/init.d/rc.multirotor
#
# Start the commander.
# Start PWM output
#
commander start
#
# Start GPS interface (depends on orb)
#
gps 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
pwm -u 400 -m 0xff
#
# Start attitude control
#
multirotor_att_control start
#
# Start logging
#
sdlog2 start -r 50 -a -b 14
# Try to get an USB console
nshterm /dev/ttyACM0 &
# Exit, because /dev/ttyS0 is needed for MAVLink
exit
#exit

View File

@ -0,0 +1,49 @@
#!nsh
#
# Standard everything needed for multirotors except mixer, output and mavlink
#
#
# Start the sensors and test them.
#
sh /etc/init.d/rc.sensors
#
# Start the commander.
#
commander start
#
# Start GPS interface (depends on orb)
#
gps start
#
# Start the attitude estimator
#
attitude_estimator_ekf start
#
# Start position estimator
#
position_estimator_inav start
#
# Start attitude control
#
multirotor_att_control start
#
# Start position control
#
multirotor_pos_control start
#
# Start logging
#
if [ $BOARD == fmuv1 ]
then
sdlog2 start -r 50 -a -b 16
else
sdlog2 start -r 200 -a -b 16
fi