diff --git a/ROMFS/px4fmu_common/init.d/10020_3dr_quad b/ROMFS/px4fmu_common/init.d/10020_3dr_quad index 0dbffba00f..896d9bd9c7 100644 --- a/ROMFS/px4fmu_common/init.d/10020_3dr_quad +++ b/ROMFS/px4fmu_common/init.d/10020_3dr_quad @@ -1,10 +1,10 @@ #!nsh # -# @name 3DR Iris Quadrotor +# @name 3DR Iris DIY Quad # -# @type Quadrotor Wide +# @type Quadrotor x # -# @maintainer Anton Babushkin +# @maintainer Lorenz Meier # sh /etc/init.d/rc.mc_defaults @@ -12,21 +12,15 @@ sh /etc/init.d/rc.mc_defaults if [ $AUTOCNF == yes ] then # TODO tune roll/pitch separately - param set MC_ROLL_P 7.0 - param set MC_ROLLRATE_P 0.13 - param set MC_ROLLRATE_I 0.05 + param set MC_ROLL_P 6.5 + param set MC_ROLLRATE_P 0.08 + param set MC_ROLLRATE_I 0.1 param set MC_ROLLRATE_D 0.004 - param set MC_PITCH_P 7.0 - param set MC_PITCHRATE_P 0.13 - param set MC_PITCHRATE_I 0.05 + param set MC_PITCH_P 6.0 + param set MC_PITCHRATE_P 0.16 + param set MC_PITCHRATE_I 0.09 param set MC_PITCHRATE_D 0.004 - param set MC_YAW_P 2.5 - param set MC_YAWRATE_P 0.25 - param set MC_YAWRATE_I 0.25 - param set MC_YAWRATE_D 0.0 - - param set BAT_V_SCALING 0.00989 - param set BAT_C_SCALING 0.0124 + param set MC_YAW_P 4 fi set MIXER quad_x