From 804898c2a55bd188424ecf9326d79ffbc98aba06 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Sat, 14 Jul 2012 15:33:17 +0800 Subject: [PATCH] fix param config names --- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index 7a920fbfcb..38301a9e7e 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -31,21 +31,21 @@ // table of user settable parameters const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = { - // @Param: AHRS_YAW_P + // @Param: YAW_P // @DisplayName: Yaw P // @Description: This controls the weight the compass has on the overall heading // @Range: 0 .4 // @Increment: .01 AP_GROUPINFO("YAW_P", 0, AP_AHRS_DCM, _kp_yaw), - // @Param: AHRS_RP_P + // @Param: RP_P // @DisplayName: AHRS RP_P // @Description: This controls how fast the accelerometers correct the attitude // @Range: 0 .4 // @Increment: .01 AP_GROUPINFO("RP_P", 1, AP_AHRS_DCM, _kp), - // @Param: AHRS_GPS_GAIN + // @Param: GPS_GAIN // @DisplayName: AHRS GPS gain // @Description: This controls how how much to use the GPS to correct the attitude // @Range: 0.0 1.0