From a32b25eb52fd9575873fc3b9c78e24736749a004 Mon Sep 17 00:00:00 2001 From: Hyon Lim Date: Thu, 19 Sep 2013 05:33:57 +1000 Subject: Update 1001_rc_quad.hil Default gain set --- ROMFS/px4fmu_common/init.d/1001_rc_quad.hil | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) (limited to 'ROMFS') diff --git a/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil b/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil index 82efeb2e1..bbe3b7e28 100644 --- a/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil +++ b/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil @@ -13,22 +13,22 @@ then # Set all params here, then disable autoconfig param set SYS_AUTOCONFIG 0 - param set MC_ATTRATE_D 0.002 + param set MC_ATTRATE_D 0.0 param set MC_ATTRATE_I 0.0 - param set MC_ATTRATE_P 0.09 + param set MC_ATTRATE_P 0.05 param set MC_ATT_D 0.0 param set MC_ATT_I 0.0 - param set MC_ATT_P 6.8 + param set MC_ATT_P 3.0 param set MC_YAWPOS_D 0.0 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 MC_YAWPOS_P 2.1 + param set MC_YAWRATE_D 0.0 + param set MC_YAWRATE_I 0.0 + param set MC_YAWRATE_P 0.05 param set NAV_TAKEOFF_ALT 3.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.5 + param set MPC_THR_MIN 0.1 param set MPC_XY_D 0 param set MPC_XY_P 0.5 param set MPC_XY_VEL_D 0 -- cgit v1.2.3