From 87b0fb05ce51773635233c948bdb4161bc593c13 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 14 Apr 2013 15:39:14 +1000 Subject: [PATCH] AHRS: changed default RP and YAW gain to 0.3 this reduces the impact of hard acceleration on takeoff, and reduces the impact of GPS lag Note that this doesn't affect copters, as they override to 0.1 --- libraries/AP_AHRS/AP_AHRS.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 7814620349..a938084c7a 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -32,14 +32,14 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = { // @Description: This controls the weight the compass or GPS has on the heading. A higher value means the heading will track the yaw source (GPS or compass) more rapidly. // @Range: 0.1 0.4 // @Increment: .01 - AP_GROUPINFO("YAW_P", 4, AP_AHRS, _kp_yaw, 0.4f), + AP_GROUPINFO("YAW_P", 4, AP_AHRS, _kp_yaw, 0.3f), // @Param: RP_P // @DisplayName: AHRS RP_P // @Description: This controls how fast the accelerometers correct the attitude // @Range: 0.1 0.4 // @Increment: .01 - AP_GROUPINFO("RP_P", 5, AP_AHRS, _kp, 0.4f), + AP_GROUPINFO("RP_P", 5, AP_AHRS, _kp, 0.3f), // @Param: WIND_MAX // @DisplayName: Maximum wind