From 9eb3a063d88c4314537742cf82c533ecc23783be Mon Sep 17 00:00:00 2001 From: Michelle Rossouw Date: Wed, 15 Sep 2021 00:38:38 +1000 Subject: [PATCH] autotest: Add usable default parameters for Blimp's position and velocity PIDs --- Tools/autotest/default_params/blimp.parm | 54 ++++++++++++++++++++++++ 1 file changed, 54 insertions(+) diff --git a/Tools/autotest/default_params/blimp.parm b/Tools/autotest/default_params/blimp.parm index 12d3cd8079..9db8476573 100644 --- a/Tools/autotest/default_params/blimp.parm +++ b/Tools/autotest/default_params/blimp.parm @@ -74,3 +74,57 @@ INS_ACC3SCAL_Z 1.000 ARMING_RUDDER 0 GCS_PID_MASK 255 + +# default PID params for position and velocity-controlled modes +MAX_POS_XY 0.3 +MAX_POS_YAW 0.3 +MAX_POS_Z 0.15 +MAX_VEL_XY 0.4 +MAX_VEL_YAW 0.5 +MAX_VEL_Z 0.2 + +VELXY_D 0.0 +VELXY_FF 0.0 +VELXY_FLTD 3.0 +VELXY_FLTE 3.0 +VELXY_I 1.5 +VELXY_IMAX 5.0 +VELXY_P 5.0 +VELYAW_D 0.0 +VELYAW_FF 0.0 +VELYAW_FLTD 3.0 +VELYAW_FLTE 3.0 +VELYAW_I 0.8 +VELYAW_IMAX 5.0 +VELYAW_P 15.0 +VELZ_D 0.0 +VELZ_FF 0.0 +VELZ_FLTD 3.0 +VELZ_FLTE 3.0 +VELZ_I 1.0 +VELZ_IMAX 2.0 +VELZ_P 15.0 + +POSXY_D 0.0 +POSXY_FF 0.0 +POSXY_FLTD 3.0 +POSXY_FLTE 3.0 +POSXY_I 0.05 +POSXY_IMAX 0.1 +POSXY_P 1.0 +POSYAW_D 0.0 +POSYAW_FF 0.0 +POSYAW_FLTD 3.0 +POSYAW_FLTE 3.0 +POSYAW_FLTT 3.0 +POSYAW_I 0.1 +POSYAW_IMAX 1.0 +POSYAW_P 1.0 +POSYAW_SMAX 0.0 +POSZ_D 0.0 +POSZ_FF 0.0 +POSZ_FLTD 3.0 +POSZ_FLTE 3.0 +POSZ_I 0.0 +POSZ_IMAX 0.0 +POSZ_P 0.7