diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2013-08-28 08:14:13 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2013-08-28 08:14:13 +0200 |
commit | 5fe3c49ba0e7e3f64f5b6c9b64ced675c01b14fe (patch) | |
tree | 5f024477d370d92edacead7412f60f6757cbf082 /ROMFS/px4fmu_common/init.d/10_io_f330 | |
parent | e44d134c6c64535f67e26f9633206aba50a10613 (diff) | |
parent | 66c61fbe96e11ee7099431a8370d84f862543810 (diff) | |
download | px4-firmware-5fe3c49ba0e7e3f64f5b6c9b64ced675c01b14fe.tar.gz px4-firmware-5fe3c49ba0e7e3f64f5b6c9b64ced675c01b14fe.tar.bz2 px4-firmware-5fe3c49ba0e7e3f64f5b6c9b64ced675c01b14fe.zip |
Merged multirotor branch
Diffstat (limited to 'ROMFS/px4fmu_common/init.d/10_io_f330')
-rw-r--r-- | ROMFS/px4fmu_common/init.d/10_io_f330 | 91 |
1 files changed, 21 insertions, 70 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10_io_f330 b/ROMFS/px4fmu_common/init.d/10_io_f330 index 4450eb50d..7b6509bf8 100644 --- a/ROMFS/px4fmu_common/init.d/10_io_f330 +++ b/ROMFS/px4fmu_common/init.d/10_io_f330 @@ -1,11 +1,6 @@ #!nsh -# -# Flight startup script for PX4FMU+PX4IO -# - -# disable USB and autostart -set USB no -set MODE custom + +echo "[init] 10_io_f330: PX4FMU+PX4IO on a DJI F330 quad frame" # # Load default params for this platform @@ -15,27 +10,26 @@ then # Set all params here, then disable autoconfig param set SYS_AUTOCONFIG 0 - param set MC_ATTRATE_D 0.005 + param set MC_ATTRATE_D 0.004 param set MC_ATTRATE_I 0.0 - param set MC_ATTRATE_P 0.1 + param set MC_ATTRATE_P 0.12 param set MC_ATT_D 0.0 param set MC_ATT_I 0.0 - param set MC_ATT_P 4.5 + param set MC_ATT_P 7.0 param set MC_RCLOSS_THR 0.0 param set MC_YAWPOS_D 0.0 - param set MC_YAWPOS_I 0.3 - param set MC_YAWPOS_P 0.6 - param set MC_YAWRATE_D 0.0 - param set MC_YAWRATE_I 0.0 - param set MC_YAWRATE_P 0.1 + param set MC_YAWPOS_I 0.0 + param set MC_YAWPOS_P 2.0 + param set MC_YAWRATE_D 0.005 + param set MC_YAWRATE_I 0.2 + param set MC_YAWRATE_P 0.3 param save /fs/microsd/params fi # # Force some key parameters to sane values -# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor -# see https://pixhawk.ethz.ch/mavlink/ +# MAV_TYPE 2 = quadrotor # param set MAV_TYPE 2 @@ -44,73 +38,30 @@ param set MAV_TYPE 2 # mavlink start usleep 5000 - -# -# Start PX4IO interface (depends on orb, commander) -# -px4io start -pwm -u 400 -m 0xff - -# -# Allow PX4IO to recover from midair restarts. -# this is very unlikely, but quite safe and robust. -px4io recovery # -# Disable px4io topic limiting +# Start and configure PX4IO interface # -px4io limit 200 +sh /etc/init.d/rc.io # -# This sets a PWM right after startup (regardless of safety button) +# Set PWM values for DJI ESCs # px4io idle 900 900 900 900 - -# -# The values are for spinning motors when armed using DJI ESCs -# px4io min 1200 1200 1200 1200 - -# -# Upper limits could be higher, this is on the safe side -# px4io max 1800 1800 1800 1800 - -# -# Start the sensors (depends on orb, px4io) -# -sh /etc/init.d/rc.sensors # -# Start the commander (depends on orb, mavlink) -# -commander start - -# -# Start GPS interface (depends on orb) -# -gps start - -# -# Start the attitude estimator (depends on orb) -# -attitude_estimator_ekf start - -# -# Load mixer and start controllers (depends on px4io) +# Load mixer # mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix -multirotor_att_control start - + # -# Start logging +# Set PWM output frequency # -sdlog2 start -r 20 -a -b 16 - +pwm -u 400 -m 0xff + # -# Start system state +# Start common for all multirotors apps # -if blinkm start -then - blinkm systemstate -fi +sh /etc/init.d/rc.multirotor |