diff options
author | Julian Oes <julian@oes.ch> | 2013-11-05 16:59:34 +0100 |
---|---|---|
committer | Julian Oes <julian@oes.ch> | 2013-11-05 16:59:34 +0100 |
commit | 857c3d2efd49085dfd28827b06d96776340e5a09 (patch) | |
tree | e0af3b417227d15398d649aabf26479b9631aa52 /ROMFS/px4fmu_common/init.d/12-13_hex | |
parent | d3b267c06e53aaf119b66717ac33e78834ea0d69 (diff) | |
download | px4-firmware-857c3d2efd49085dfd28827b06d96776340e5a09.tar.gz px4-firmware-857c3d2efd49085dfd28827b06d96776340e5a09.tar.bz2 px4-firmware-857c3d2efd49085dfd28827b06d96776340e5a09.zip |
Startup scripts: Corrected cases where commander was not started, updated several outdated scripts
Diffstat (limited to 'ROMFS/px4fmu_common/init.d/12-13_hex')
-rw-r--r-- | ROMFS/px4fmu_common/init.d/12-13_hex | 15 |
1 files changed, 9 insertions, 6 deletions
diff --git a/ROMFS/px4fmu_common/init.d/12-13_hex b/ROMFS/px4fmu_common/init.d/12-13_hex index 0f0bb05ce..f83f6cfd0 100644 --- a/ROMFS/px4fmu_common/init.d/12-13_hex +++ b/ROMFS/px4fmu_common/init.d/12-13_hex @@ -61,10 +61,6 @@ then usleep 5000 sh /etc/init.d/rc.io - # Set PWM values for DJI ESCs - px4io idle 900 900 900 900 900 900 - px4io min 1200 1200 1200 1200 1200 1200 - px4io max 1900 1900 1900 1900 1900 1900 else # Start MAVLink (on UART1 / ttyS0) mavlink start -d /dev/ttyS0 @@ -77,12 +73,19 @@ fi # # Load mixer # -mixer load /dev/pwm_output $MIXER +mixer load /dev/pwm_output /etc/mixers/FMU_hex_x.mix # # Set PWM output frequency to 400 Hz # -pwm -u 400 -m 0xff +pwm rate -c 123456 -r 400 + +# +# Set disarmed, min and max PWM signals +# +pwm disarmed -c 123456 -p 900 +pwm min -c 123456 -p 1100 +pwm max -c 123456 -p 1900 # # Start common for all multirotors apps |