fix param config names

This commit is contained in:
Michael Oborne 2012-07-14 15:33:17 +08:00
parent ef9cd54035
commit 804898c2a5
1 changed files with 3 additions and 3 deletions

View File

@ -31,21 +31,21 @@
// table of user settable parameters // table of user settable parameters
const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = { const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = {
// @Param: AHRS_YAW_P // @Param: YAW_P
// @DisplayName: Yaw P // @DisplayName: Yaw P
// @Description: This controls the weight the compass has on the overall heading // @Description: This controls the weight the compass has on the overall heading
// @Range: 0 .4 // @Range: 0 .4
// @Increment: .01 // @Increment: .01
AP_GROUPINFO("YAW_P", 0, AP_AHRS_DCM, _kp_yaw), AP_GROUPINFO("YAW_P", 0, AP_AHRS_DCM, _kp_yaw),
// @Param: AHRS_RP_P // @Param: RP_P
// @DisplayName: AHRS RP_P // @DisplayName: AHRS RP_P
// @Description: This controls how fast the accelerometers correct the attitude // @Description: This controls how fast the accelerometers correct the attitude
// @Range: 0 .4 // @Range: 0 .4
// @Increment: .01 // @Increment: .01
AP_GROUPINFO("RP_P", 1, AP_AHRS_DCM, _kp), AP_GROUPINFO("RP_P", 1, AP_AHRS_DCM, _kp),
// @Param: AHRS_GPS_GAIN // @Param: GPS_GAIN
// @DisplayName: AHRS GPS gain // @DisplayName: AHRS GPS gain
// @Description: This controls how how much to use the GPS to correct the attitude // @Description: This controls how how much to use the GPS to correct the attitude
// @Range: 0.0 1.0 // @Range: 0.0 1.0