Plane: Fix parameter documentation

Fixes some problems with incorrect docs which would in turn generate
bad amp.pdef.xml files for ground stations.

merge with below
This commit is contained in:
Don Gagne 2014-01-08 18:34:10 -08:00 committed by Randy Mackay
parent 9f2f44f0f6
commit e68cf2d1c5
3 changed files with 14 additions and 5 deletions

View File

@ -12,7 +12,16 @@
#define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, &v, {group_info : class::var_info} }
const AP_Param::Info var_info[] PROGMEM = {
// @Param: FORMAT_VERSION
// @DisplayName: Eeprom format version number
// @Description: This value is incremented when changes are made to the eeprom format
// @User: Advanced
GSCALAR(format_version, "FORMAT_VERSION", 0),
// @Param: SYSID_SW_TYPE
// @DisplayName: Software Type
// @Description: This is used by the ground station to recognise the software type (eg ArduPlane vs ArduCopter)
// @User: Advanced
GSCALAR(software_type, "SYSID_SW_TYPE", Parameters::k_software_type),
// @Param: SYSID_THISMAV
@ -134,14 +143,14 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: User
GSCALAR(level_roll_limit, "LEVEL_ROLL_LIMIT", 5),
// @Param: land_pitch_cd
// @Param: LAND_PITCH_CD
// @DisplayName: Landing Pitch
// @Description: Used in autoland for planes without airspeed sensors in hundredths of a degree
// @Units: centi-Degrees
// @User: Advanced
GSCALAR(land_pitch_cd, "LAND_PITCH_CD", 0),
// @Param: land_flare_alt
// @Param: LAND_FLARE_ALT
// @DisplayName: Landing flare altitude
// @Description: Altitude in autoland at which to lock heading and flare to the LAND_PITCH_CD pitch
// @Units: meters
@ -149,7 +158,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Advanced
GSCALAR(land_flare_alt, "LAND_FLARE_ALT", 3.0),
// @Param: land_flare_sec
// @Param: LAND_FLARE_SEC
// @DisplayName: Landing flare time
// @Description: Time before landing point at which to lock heading and flare to the LAND_PITCH_CD pitch
// @Units: seconds

View File

@ -25,7 +25,7 @@
extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AP_SteerController::var_info[] PROGMEM = {
// @Param: T_CONST
// @Param: TCONST
// @DisplayName: Steering Time Constant
// @Description: This controls the time constant in seconds from demanded to achieved steering angle. A value of 0.75 is a good default and will work with nearly all rovers. Ground steering in aircraft needs a bit smaller time constant, and a value of 0.5 is recommended for best ground handling in fixed wing aircraft. A value of 0.75 means that the controller will try to correct any deviation between the desired and actual steering angle in 0.75 seconds. Advanced users may want to reduce this time to obtain a faster response but there is no point setting a time less than the vehicle can achieve.
// @Range: 0.4 1.0

View File

@ -108,7 +108,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
#if MNT_STABILIZE_OPTION == ENABLED
// @Param: STAB_ROLL
// @DisplayName: Stabilize mount's roll angle
// @Description:enable roll stabilisation relative to Earth
// @Description: enable roll stabilisation relative to Earth
// @Values: 0:Disabled,1:Enabled
// @User: Standard
AP_GROUPINFO("STAB_ROLL", 4, AP_Mount, _stab_roll, 0),