diff options
author | Anton Babushkin <anton.babushkin@me.com> | 2014-01-08 20:55:12 +0100 |
---|---|---|
committer | Anton Babushkin <anton.babushkin@me.com> | 2014-01-08 20:55:12 +0100 |
commit | 4cffd99db940a9f0cda7643842ccf17d8a3f1b48 (patch) | |
tree | c5347e39d858bcaf2d21cdb3d7de665781573a46 /ROMFS/px4fmu_common/init.d/4010_dji_f330 | |
parent | 255d91d8d49ce06f065b6a0269bdfabeaa40fae4 (diff) | |
download | px4-firmware-4cffd99db940a9f0cda7643842ccf17d8a3f1b48.tar.gz px4-firmware-4cffd99db940a9f0cda7643842ccf17d8a3f1b48.tar.bz2 px4-firmware-4cffd99db940a9f0cda7643842ccf17d8a3f1b48.zip |
Major autostart rewrite
Diffstat (limited to 'ROMFS/px4fmu_common/init.d/4010_dji_f330')
-rw-r--r-- | ROMFS/px4fmu_common/init.d/4010_dji_f330 | 67 |
1 files changed, 22 insertions, 45 deletions
diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330 index 7054210e2..58c6d99bb 100644 --- a/ROMFS/px4fmu_common/init.d/4010_dji_f330 +++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330 @@ -2,30 +2,27 @@ echo "[init] PX4FMU v1, v2 with or without IO on DJI F330" -# -# Load default params for this platform -# -if param compare SYS_AUTOCONFIG 1 +if [ $DO_AUTOCONFIG == yes ] 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 + # + # Default parameters for this platform + # param set MC_ATTRATE_P 0.12 - param set MC_ATT_D 0.0 - param set MC_ATT_I 0.0 + param set MC_ATTRATE_I 0.0 + param set MC_ATTRATE_D 0.004 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_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 set NAV_TAKEOFF_ALT 3.0 + param set MC_YAWRATE_I 0.2 + param set MC_YAWRATE_D 0.005 + 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 +35,12 @@ 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 - -sh /etc/init.d/rc.mc_interface - -# -# Start common for all multirotors apps -# -sh /etc/init.d/rc.multirotor +set FRAME_TYPE mc +set FRAME_GEOMETRY x +set FRAME_COUNT 4 +set PWM_RATE 400 +set PWM_MIN 1200 +set PWM_MAX 1900 +set PWM_DISARMED 900 |