From 5a214acca3c1ce2e948348f7c466cc868b801c58 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 19 Nov 2012 22:49:36 +1100 Subject: [PATCH] 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 --- libraries/AP_AHRS/AP_AHRS.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 56fe27c634..0e9f1cbdf8 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -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), @@ -112,4 +112,4 @@ void AP_AHRS::add_trim(float roll_in_radians, float pitch_in_radians) // debug -- remove me! Serial.printf_P(PSTR("add_trim after R:%4.2f P:%4.2f\n"),ToDeg(trim.x),ToDeg(trim.y)); -} \ No newline at end of file +}