diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2014-01-20 04:20:04 -0800 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2014-01-20 04:20:04 -0800 |
commit | c58b68d3773e4c2ad38b052d36a132439e32d59b (patch) | |
tree | abe5f202816e37ffb8ce8a9868725cf0c0f9b631 /ROMFS/px4fmu_common/init.d/4010_dji_f330 | |
parent | 13822b35e75cb6a76798159a3f7210d297528243 (diff) | |
parent | f8c5a6cc50cb848a60fd8d359ab4695f18b7d761 (diff) | |
download | px4-firmware-c58b68d3773e4c2ad38b052d36a132439e32d59b.tar.gz px4-firmware-c58b68d3773e4c2ad38b052d36a132439e32d59b.tar.bz2 px4-firmware-c58b68d3773e4c2ad38b052d36a132439e32d59b.zip |
Merge pull request #584 from PX4/autostart_cleanup
Autostart cleanup
Diffstat (limited to 'ROMFS/px4fmu_common/init.d/4010_dji_f330')
-rw-r--r-- | ROMFS/px4fmu_common/init.d/4010_dji_f330 | 76 |
1 files changed, 29 insertions, 47 deletions
diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330 index 7054210e2..ab1db94d0 100644 --- a/ROMFS/px4fmu_common/init.d/4010_dji_f330 +++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330 @@ -1,31 +1,31 @@ #!nsh - -echo "[init] PX4FMU v1, v2 with or without IO on DJI F330" - # -# Load default params for this platform +# DJI Flame Wheel F330 Quadcopter +# +# Maintainers: Anton Babushkin <anton.babushkin@me.com> # -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_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.8 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 set NAV_TAKEOFF_ALT 3.0 + param set MC_YAWPOS_D 0.0 + param set MC_YAWRATE_P 0.2 + param set MC_YAWRATE_I 0.05 + param set MC_YAWRATE_D 0.0 + param set MPC_TILT_MAX 0.5 - param set MPC_THR_MAX 0.7 - param set MPC_THR_MIN 0.3 + param set MPC_THR_MAX 0.8 + param set MPC_THR_MIN 0.2 param set MPC_XY_D 0 param set MPC_XY_P 0.5 param set MPC_XY_VEL_D 0 @@ -38,32 +38,14 @@ then param set MPC_Z_VEL_I 0.1 param set MPC_Z_VEL_MAX 2 param set MPC_Z_VEL_P 0.20 - - param save fi -# -# Start and configure PX4IO or FMU interface -# -if px4io detect -then - # Start MAVLink (depends on orb) - mavlink start - usleep 5000 - - 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 +set VEHICLE_TYPE mc +set MIXER FMU_quad_x -sh /etc/init.d/rc.mc_interface - -# -# Start common for all multirotors 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 |