mirror of https://github.com/ArduPilot/ardupilot
AHRS: changed the docs for AHRS_YAW_P and AHRS_RP_P
a user had set AHRS_YAW_P to zero. Make it clear that zero is not a good value. MichaelO will change MP to give a warning for a value below 0.1
This commit is contained in:
parent
e0f85f63fb
commit
41baa09c96
|
@ -29,15 +29,15 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = {
|
|||
|
||||
// @Param: YAW_P
|
||||
// @DisplayName: Yaw P
|
||||
// @Description: This controls the weight the compass has on the overall heading
|
||||
// @Range: 0 .4
|
||||
// @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.4),
|
||||
|
||||
// @Param: RP_P
|
||||
// @DisplayName: AHRS RP_P
|
||||
// @Description: This controls how fast the accelerometers correct the attitude
|
||||
// @Range: 0 .4
|
||||
// @Range: 0.1 0.4
|
||||
// @Increment: .01
|
||||
AP_GROUPINFO("RP_P", 5, AP_AHRS, _kp, 0.4),
|
||||
|
||||
|
|
Loading…
Reference in New Issue