diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface index e305713377..b19ec75ff8 100644 --- a/ROMFS/px4fmu_common/init.d/rc.interface +++ b/ROMFS/px4fmu_common/init.d/rc.interface @@ -123,9 +123,9 @@ then fi fi - if [ $MIXER_AUX_FILE != none -a $FMU_MODE == pwm ] + if [ $MIXER_AUX_FILE != none ] then - if fmu mode_pwm + if fmu mode_$AUX_MODE then if [ -e $OUTPUT_AUX_DEV ] then diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 910f5f6291..dac23fe6b7 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -127,6 +127,7 @@ then set FAILSAFE_AUX none set MK_MODE none set FMU_MODE pwm + set AUX_MODE pwm set MAVLINK_F default set EXIT_ON_END no set MAV_TYPE none @@ -451,17 +452,6 @@ then fi fi - # Start sensors depending on the interface being up - if param compare SENS_EN_LL40LS 1 - then - if pwm_input start - then - if ll40ls start pwm - then - fi - fi - fi - if [ $MAVLINK_F == default ] then # Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s @@ -517,6 +507,19 @@ then # sh /etc/init.d/rc.logging + # Sensors on the PWM interface bank + if param compare SENS_EN_LL40LS 1 + then + if pwm_input start + then + if ll40ls start pwm + then + # Reserve the last two pins + set AUX_MODE pwm4 + fi + fi + fi + # # Start up ARDrone Motor interface #