From be6923be0f165dfd5d67bbfc0a825500048fbe16 Mon Sep 17 00:00:00 2001 From: Amilcar Lucas Date: Thu, 21 Jun 2012 00:20:37 +0200 Subject: [PATCH] Improve parameters descriptive text --- ArduPlane/Parameters.pde | 68 +++++++++++++------------ libraries/RC_Channel/RC_Channel_aux.cpp | 6 +-- 2 files changed, 38 insertions(+), 36 deletions(-) diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index eda4a70697..9f957c2fa0 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -18,14 +18,14 @@ static const AP_Param::Info var_info[] PROGMEM = { GSCALAR(software_type, "SYSID_SW_TYPE"), GSCALAR(sysid_this_mav, "SYSID_THISMAV"), GSCALAR(sysid_my_gcs, "SYSID_MYGCS"), - + // @Param: SERIAL3_BAUD // @DisplayName: Telemetry Baud Rate // @Description: The baud rate used on the telemetry port // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200 // @User: Standard GSCALAR(serial3_baud, "SERIAL3_BAUD"), - + // @Param: KFF_PTCHCOMP // @DisplayName: Pitch Compensation // @Description: Adds pitch input to compensate for the loss of lift due to roll control. 0 = 0 %, 1 = 100% @@ -33,7 +33,7 @@ static const AP_Param::Info var_info[] PROGMEM = { // @Increment: 0.01 // @User: Advanced GSCALAR(kff_pitch_compensation, "KFF_PTCHCOMP"), - + // @Param: KFF_RDDRMIX // @DisplayName: Rudder Mix // @Description: The amount of rudder mix to apply during aileron movement 0 = 0 %, 1 = 100% @@ -41,23 +41,23 @@ static const AP_Param::Info var_info[] PROGMEM = { // @Increment: 0.01 // @User: Standard GSCALAR(kff_rudder_mix, "KFF_RDDRMIX"), - + // @Param: KFF_PTCH2THR // @DisplayName: Pitch to Throttle Mix - // @Description: Pitch to throttle feed-forward gain. + // @Description: Pitch to throttle feed-forward gain. // @Range: 0 5 // @Increment: 0.01 - // @User: Advanced + // @User: Advanced GSCALAR(kff_pitch_to_throttle, "KFF_PTCH2THR"), - + // @Param: KFF_THR2PTCH // @DisplayName: Throttle to Pitch Mix // @Description: Throttle to pitch feed-forward gain. // @Range: 0 5 // @Increment: 0.01 - // @User: Advanced + // @User: Advanced GSCALAR(kff_throttle_to_pitch, "KFF_THR2PTCH"), - + // @Param: MANUAL_LEVEL // @DisplayName: Manual Level // @Description: Setting this to Disabled(0) will enable autolevel on every boot. Setting it to Enabled(1) will do a calibration only when you tell it to @@ -72,14 +72,14 @@ static const AP_Param::Info var_info[] PROGMEM = { // @Increment: 1 // @User: Standard GSCALAR(crosstrack_gain, "XTRK_GAIN_SC"), - + // @Param: XTRK_ANGLE_CD // @DisplayName: Crosstrack Entry Angle // @Description: Maximum angle used to correct for track following. // @Units: Degrees // @Range: 0 90 // @Increment: 1 - // @User: Standard + // @User: Standard GSCALAR(crosstrack_entry_angle, "XTRK_ANGLE_CD"), // @Param: ALT_MIX @@ -90,37 +90,37 @@ static const AP_Param::Info var_info[] PROGMEM = { // @Increment: 0.1 // @User: Advanced GSCALAR(altitude_mix, "ALT_MIX"), - + // @Param: ARSPD_RATIO // @DisplayName: Airspeed Ratio // @Description: Used to scale raw adc airspeed sensor to a SI Unit (m/s) // @Units: Scale // @Range: 0 5 // @Increment: 0.001 - // @User: Advanced + // @User: Advanced GSCALAR(airspeed_ratio, "ARSPD_RATIO"), - + GSCALAR(airspeed_offset, "ARSPD_OFFSET"), GSCALAR(command_total, "CMD_TOTAL"), GSCALAR(command_index, "CMD_INDEX"), - + // @Param: WP_RADIUS // @DisplayName: Waypoint Radius // @Description: Defines the distance from a waypoint, that when crossed indicates the wp has been hit. // @Units: Meters // @Range: 1 127 // @Increment: 1 - // @User: Standard + // @User: Standard GSCALAR(waypoint_radius, "WP_RADIUS"), - + // @Param: WP_LOITER_RAD // @DisplayName: Waypoint Loiter Radius // @Description: Defines the distance from the waypoint center, the plane will maintain during a loiter // @Units: Meters // @Range: 1 127 // @Increment: 1 - // @User: Standard + // @User: Standard GSCALAR(loiter_radius, "WP_LOITER_RAD"), #if GEOFENCE_ENABLED == ENABLED @@ -130,16 +130,16 @@ static const AP_Param::Info var_info[] PROGMEM = { GSCALAR(fence_minalt, "FENCE_MINALT"), GSCALAR(fence_maxalt, "FENCE_MAXALT"), #endif - + // @Param: ARSPD_FBW_MIN // @DisplayName: Fly By Wire Minimum Airspeed // @Description: Airspeed corresponding to minimum throttle in Fly By Wire B mode. // @Units: m/s // @Range: 5 50 // @Increment: 1 - // @User: Standard + // @User: Standard GSCALAR(flybywire_airspeed_min, "ARSPD_FBW_MIN"), - + // @Param: ARSPD_FBW_MAX // @DisplayName: Fly By Wire Maximum Airspeed // @Description: Airspeed corresponding to maximum throttle in Fly By Wire B mode. @@ -157,7 +157,7 @@ static const AP_Param::Info var_info[] PROGMEM = { // @Increment: 1 // @User: Standard GSCALAR(throttle_min, "THR_MIN"), - + // @Param: THR_MAX // @DisplayName: Maximum Throttle // @Description: The maximum throttle setting to which the autopilot will apply. @@ -167,7 +167,7 @@ static const AP_Param::Info var_info[] PROGMEM = { // @User: Standard GSCALAR(throttle_max, "THR_MAX"), GSCALAR(throttle_slewrate, "THR_SLEWRATE"), - + // @Param: THR_FAILSAFE // @DisplayName: Throttle Failsafe Enable // @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel @@ -175,8 +175,8 @@ static const AP_Param::Info var_info[] PROGMEM = { // @Values: 0:Disabled,1:Enabled // @User: Standard GSCALAR(throttle_fs_enabled, "THR_FAILSAFE"), - - + + GSCALAR(throttle_fs_value, "THR_FS_VALUE"), GSCALAR(throttle_cruise, "TRIM_THROTTLE"), @@ -200,7 +200,7 @@ static const AP_Param::Info var_info[] PROGMEM = { // @Increment: 1 // @User: Standard GSCALAR(roll_limit, "LIM_ROLL_CD"), - + // @Param: LIM_PITCH_MAX // @DisplayName: Maximum Pitch Angle // @Description: The maximum commanded pitch up angle @@ -209,7 +209,7 @@ static const AP_Param::Info var_info[] PROGMEM = { // @Increment: 1 // @User: Standard GSCALAR(pitch_limit_max, "LIM_PITCH_MAX"), - + // @Param: LIM_PITCH_MIN // @DisplayName: Minimum Pitch Angle // @Description: The minimum commanded pitch down angle @@ -236,7 +236,7 @@ static const AP_Param::Info var_info[] PROGMEM = { GSCALAR(FBWB_min_altitude, "ALT_HOLD_FBWCM"), GSCALAR(ground_temperature, "GND_TEMP"), GSCALAR(ground_pressure, "GND_ABS_PRESS"), - + // @Param: MAG_ENABLE // @DisplayName: Enable Compass // @Description: Setting this to Enabled(1) will enable the compass. Setting this to Disabled(0) will disable the compass @@ -255,14 +255,14 @@ static const AP_Param::Info var_info[] PROGMEM = { GSCALAR(input_voltage, "INPUT_VOLTS"), GSCALAR(pack_capacity, "BATT_CAPACITY"), GSCALAR(inverted_flight_ch, "INVERTEDFLT_CH"), - + // @Param: SONAR_ENABLE // @DisplayName: Enable Sonar // @Description: Setting this to Enabled(1) will enable the sonar. Setting this to Disabled(0) will disable the sonar // @Values: 0:Disabled,1:Enabled // @User: Standard GSCALAR(sonar_enabled, "SONAR_ENABLE"), - + // @Param: ARSPD_ENABLE // @DisplayName: Enable Airspeed // @Description: Setting this to Enabled(1) will enable the Airspeed sensor. Setting this to Disabled(0) will disable the Airspeed sensor @@ -278,6 +278,8 @@ static const AP_Param::Info var_info[] PROGMEM = { GSCALAR(airspeed_use, "ARSPD_USE"), #if CAMERA == ENABLED + // @Group: CAM_ + // @Path: ../libraries/AP_Camera/AP_Camera.cpp GGROUP(camera, "CAM_", AP_Camera), #endif @@ -309,17 +311,17 @@ static const AP_Param::Info var_info[] PROGMEM = { GGROUP(pidNavPitchAltitude, "ALT2PTCH_", PID), // variables not in the g class which contain EEPROM saved variables - + // @Group: COMPASS_ // @Path: ../libraries/AP_Compass/Compass.cpp GOBJECT(compass, "COMPASS_", Compass), GOBJECT(gcs0, "SR0_", GCS_MAVLINK), GOBJECT(gcs3, "SR3_", GCS_MAVLINK), - + // @Group: IMU_ // @Path: ../libraries/AP_IMU/IMU.cpp GOBJECT(imu, "IMU_", IMU), - + // @Group: AHRS_ // @Path: ../libraries/AP_AHRS/AP_AHRS_DCM.cpp, ../libraries/AP_AHRS/AP_AHRS_Quaternion.cpp GOBJECT(ahrs, "AHRS_", AP_AHRS) diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp index f5d85d3d22..b498869262 100644 --- a/libraries/RC_Channel/RC_Channel_aux.cpp +++ b/libraries/RC_Channel/RC_Channel_aux.cpp @@ -6,13 +6,13 @@ const AP_Param::GroupInfo RC_Channel_aux::var_info[] PROGMEM = { AP_NESTEDGROUPINFO(RC_Channel, 0), // @Param: FUNCTION - // @DisplayName: Function assigned to this APM servo output + // @DisplayName: APM servo output function // @Description: Setting this to Disabled(0) will disable this output, any other value will enable the corresponding function // @Values: 0:Disabled,1:Manual,2:Flap,3:Flap_auto,4:Aileron,5:flaperon,6:mount_pan,7:mount_tilt,8:mount_roll,9:mount_open,10:camera_trigger,11:release // @User: Standard AP_GROUPINFO("FUNCTION", 1, RC_Channel_aux, function), // @Param: ANGLE_MIN - // @DisplayName: Minimum physical angular position of the object that this servo output controls + // @DisplayName: Minimum object position // @Description: Minimum physical angular position of the object that this servo output controls, this could be for example a camera pan angle, an aileron angle, etc // @Units: Degrees // @Range: -180 180 @@ -20,7 +20,7 @@ const AP_Param::GroupInfo RC_Channel_aux::var_info[] PROGMEM = { // @User: Standard AP_GROUPINFO("ANGLE_MIN", 2, RC_Channel_aux, angle_min), // @Param: ANGLE_MAX - // @DisplayName: Maximum physical angular position of the object that this servo output controls + // @DisplayName: Maximum object position // @Description: Maximum physical angular position of the object that this servo output controls, this could be for example a camera pan angle, an aileron angle, etc // @Units: Degrees // @Range: -180 180