diff options
Diffstat (limited to 'ROMFS/px4fmu_common/init.d/31_io_phantom')
-rw-r--r-- | ROMFS/px4fmu_common/init.d/31_io_phantom | 38 |
1 files changed, 12 insertions, 26 deletions
diff --git a/ROMFS/px4fmu_common/init.d/31_io_phantom b/ROMFS/px4fmu_common/init.d/31_io_phantom index 652833745..14607e2df 100644 --- a/ROMFS/px4fmu_common/init.d/31_io_phantom +++ b/ROMFS/px4fmu_common/init.d/31_io_phantom @@ -52,8 +52,6 @@ then # Start MAVLink (depends on orb) mavlink start - commander start - sh /etc/init.d/rc.io # Limit to 100 Hz updates and (implicit) 50 Hz PWM px4io limit 100 @@ -61,41 +59,29 @@ else # Start MAVLink (on UART1 / ttyS0) mavlink start -d /dev/ttyS0 - commander start - 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) +# Load mixer and start controllers (depends on px4io) # -sh /etc/init.d/rc.logging +if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ] +then + echo "Using /fs/microsd/etc/mixers/FMU_Q.mix" + mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix +else + echo "Using /etc/mixers/FMU_Q.mix" + mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix +fi # -# Start GPS interface (depends on orb) +Start common fixedwing apps # -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_Q.mix -fw_att_control start -fw_pos_control_l1 start +sh /etc/init.d/rc.fixedwing if [ $EXIT_ON_END == yes ] then exit -fi +fi
\ No newline at end of file |