mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
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
This commit is contained in:
parent
8c7a1597dc
commit
87b0fb05ce
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user