1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 16:55:29 +03:00

range of yaw_p_limit increased to 100-500

This commit is contained in:
Pawel Spychalski (DzikuVx) 2016-05-23 16:41:28 +02:00
parent 0c089ec58a
commit 821dd67a7c
2 changed files with 3 additions and 2 deletions

View file

@ -187,7 +187,7 @@ void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->dterm_lpf_hz = 40;
pidProfile->yaw_lpf_hz = 30;
pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
pidProfile->yaw_p_limit = YAW_P_LIMIT_DEFAULT;
pidProfile->mag_hold_rate_limit = MAG_HOLD_RATE_LIMIT_DEFAULT;
pidProfile->max_angle_inclination[FD_ROLL] = 300; // 30 degrees

View file

@ -26,7 +26,8 @@
#define GYRO_SATURATION_LIMIT 1800 // 1800dps
#define PID_MAX_OUTPUT 1000
#define YAW_P_LIMIT_MIN 100 // Maximum value for yaw P limiter
#define YAW_P_LIMIT_MAX 300 // Maximum value for yaw P limiter
#define YAW_P_LIMIT_MAX 500 // Maximum value for yaw P limiter
#define YAW_P_LIMIT_DEFAULT 300 // Default value for yaw P limiter
#define MAG_HOLD_RATE_LIMIT_MIN 10
#define MAG_HOLD_RATE_LIMIT_MAX 250