From 41dfdfb1a4b974b5d32788852768513d0dac7a67 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 24 Aug 2013 20:32:46 +0200 Subject: [PATCH] Use common rc.multirotor script (now only in 01_fmu_quad_x). --- ROMFS/px4fmu_common/init.d/01_fmu_quad_x | 33 +++------------- ROMFS/px4fmu_common/init.d/rc.multirotor | 49 ++++++++++++++++++++++++ 2 files changed, 54 insertions(+), 28 deletions(-) create mode 100644 ROMFS/px4fmu_common/init.d/rc.multirotor diff --git a/ROMFS/px4fmu_common/init.d/01_fmu_quad_x b/ROMFS/px4fmu_common/init.d/01_fmu_quad_x index c1f3187f93..8223b3ea5a 100644 --- a/ROMFS/px4fmu_common/init.d/01_fmu_quad_x +++ b/ROMFS/px4fmu_common/init.d/01_fmu_quad_x @@ -62,44 +62,21 @@ param set MAV_TYPE 2 # 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 GPS interface (depends on orb) +# Start common for all multirotors apps # -gps start - +sh /etc/init.d/rc.multirotor + # -# Start the attitude estimator +# Start PWM output # -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 diff --git a/ROMFS/px4fmu_common/init.d/rc.multirotor b/ROMFS/px4fmu_common/init.d/rc.multirotor new file mode 100644 index 0000000000..81184f3632 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/rc.multirotor @@ -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