diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2014-01-31 09:51:59 +0100 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2014-01-31 09:51:59 +0100 |
commit | d2b183c05bba5443d24e8df8b6fc5f52bd27275d (patch) | |
tree | 99b1ee91cbb108a35ce00c8cc632f635c6022f03 /ROMFS/px4fmu_common/init.d/4011_dji_f450 | |
parent | fb446c01b815b00f5da098d340557164fdbf78c9 (diff) | |
parent | 83df116c7aa21b6d68f2aa31c4526dd822495d70 (diff) | |
download | px4-firmware-d2b183c05bba5443d24e8df8b6fc5f52bd27275d.tar.gz px4-firmware-d2b183c05bba5443d24e8df8b6fc5f52bd27275d.tar.bz2 px4-firmware-d2b183c05bba5443d24e8df8b6fc5f52bd27275d.zip |
merge master
Diffstat (limited to 'ROMFS/px4fmu_common/init.d/4011_dji_f450')
-rw-r--r-- | ROMFS/px4fmu_common/init.d/4011_dji_f450 | 91 |
1 files changed, 27 insertions, 64 deletions
diff --git a/ROMFS/px4fmu_common/init.d/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/4011_dji_f450 index a1d253191..299771c1d 100644 --- a/ROMFS/px4fmu_common/init.d/4011_dji_f450 +++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450 @@ -1,74 +1,37 @@ #!nsh - -echo "[init] PX4FMU v1, v2 with or without IO on DJI F450" - # -# Load default params for this platform +# DJI Flame Wheel F450 Quadcopter +# +# Maintainers: Lorenz Meier <lm@inf.ethz.ch> # -if param compare SYS_AUTOCONFIG 1 -then - # Set all params here, then disable autoconfig - param set SYS_AUTOCONFIG 0 - param set MC_ATTRATE_D 0.004 - param set MC_ATTRATE_I 0.0 - param set MC_ATTRATE_P 0.12 - param set MC_ATT_D 0.0 - param set MC_ATT_I 0.0 +if [ $DO_AUTOCONFIG == yes ] +then + # + # Default parameters for this platform + # param set MC_ATT_P 7.0 - param set MC_YAWPOS_D 0.0 - param set MC_YAWPOS_I 0.0 + param set MC_ATT_I 0.0 + param set MC_ATT_D 0.0 + param set MC_ATTRATE_P 0.12 + param set MC_ATTRATE_I 0.0 + param set MC_ATTRATE_D 0.004 param set MC_YAWPOS_P 2.0 - param set MC_YAWRATE_D 0.005 - param set MC_YAWRATE_I 0.2 + param set MC_YAWPOS_I 0.0 + param set MC_YAWPOS_D 0.0 param set MC_YAWRATE_P 0.3 - - param save + param set MC_YAWRATE_I 0.2 + param set MC_YAWRATE_D 0.005 + + # TODO add default MPC parameters fi - -# -# Force some key parameters to sane values -# MAV_TYPE 2 = quadrotor -# -param set MAV_TYPE 2 -# -# Start and configure PX4IO or FMU interface -# -if px4io detect -then - # Start MAVLink (depends on orb) - mavlink start - usleep 5000 +set VEHICLE_TYPE mc +set MIXER FMU_quad_x - sh /etc/init.d/rc.io -else - # Start MAVLink (on UART1 / ttyS0) - mavlink start -d /dev/ttyS0 - usleep 5000 - fmu mode_pwm - param set BAT_V_SCALING 0.004593 - set EXIT_ON_END yes -fi - -# -# Load mixer -# -mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix - -# -# Set PWM output frequency -# -pwm rate -c 1234 -r 400 - -# -# Set disarmed, min and max PWM signals (for DJI ESCs) -# -pwm disarmed -c 1234 -p 900 -pwm min -c 1234 -p 1200 -pwm max -c 1234 -p 1800 - -# -# Start common multirotor apps -# -sh /etc/init.d/rc.multirotor +set PWM_OUTPUTS 1234 +set PWM_RATE 400 +# DJI ESC range +set PWM_DISARMED 900 +set PWM_MIN 1200 +set PWM_MAX 1900 |