mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
autotest: Add usable default parameters for Blimp's position and velocity PIDs
This commit is contained in:
parent
c9a3b16aa7
commit
9eb3a063d8
@ -74,3 +74,57 @@ INS_ACC3SCAL_Z 1.000
|
|||||||
|
|
||||||
ARMING_RUDDER 0
|
ARMING_RUDDER 0
|
||||||
GCS_PID_MASK 255
|
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
|
||||||
|
Loading…
Reference in New Issue
Block a user