diff options
Diffstat (limited to 'ROMFS')
-rw-r--r-- | ROMFS/px4fmu_common/init.d/900_bottle_drop_test | 75 | ||||
-rwxr-xr-x | ROMFS/px4fmu_common/init.d/rcS | 6 |
2 files changed, 81 insertions, 0 deletions
diff --git a/ROMFS/px4fmu_common/init.d/900_bottle_drop_test b/ROMFS/px4fmu_common/init.d/900_bottle_drop_test new file mode 100644 index 000000000..c0f50fec0 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/900_bottle_drop_test @@ -0,0 +1,75 @@ +#!nsh + +echo "[init] bottle drop test + +# +# Load default params for this platform +# +if param compare SYS_AUTOCONFIG 1 +then + # Set all params here, then disable autoconfig + param set SYS_AUTOCONFIG 0 + + param save +fi + +# +# Force some key parameters to sane values +# MAV_TYPE 2 = quadrotor +# +param set MAV_TYPE 2 + +set EXIT_ON_END no + +# +# Start and configure PX4IO and FMU interface +# +# Start MAVLink (depends on orb) +mavlink start +usleep 5000 + +# +# Start the sensors and test them. +# +sh /etc/init.d/rc.sensors + +# +# Start logging (depends on sensors) +# +#sh /etc/init.d/rc.logging +sdlog2 start -r 200 -e -b 16 + + +# +# Start GPS interface (depends on orb) +# +gps start + +# +# Start the attitude estimator +# +attitude_estimator_ekf start + +# +# Start position estimator +# +position_estimator_inav start + +sh /etc/init.d/rc.io + +fmu mode_pwm + +mixer load /dev/px4fmu /etc/mixers/FMU_pass.mix + +pwm min -d /dev/px4fmu -c 123 -p 900 +pwm max -d /dev/px4fmu -c 123 -p 2100 + +pwm arm -d /dev/px4fmu + +bottle_drop start + + +if [ $EXIT_ON_END == yes ] +then + exit +fi diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 5f52969d1..46bb6d866 100755 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -319,6 +319,12 @@ then set MODE custom fi + if param compare SYS_AUTOSTART 900 + then + sh /etc/init.d/900_bottle_drop_test + set MODE custom + fi + # Start any custom extensions that might be missing if [ -f /fs/microsd/etc/rc.local ] then |