From 8c607d93fc59ffecc3a6b9cc3a6ea9964c064535 Mon Sep 17 00:00:00 2001
From: Adam M Rivera <a432511@gmail.com>
Date: Tue, 24 Apr 2012 11:37:33 -0500
Subject: [PATCH] Parameters.pde: Added new comment structure to a few
 parameters for testing.

---
 ArduCopter/Parameters.pde | 40 ++++++++++++++++++++++++++++++++++++---
 1 file changed, 37 insertions(+), 3 deletions(-)

diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde
index 8197465dd..f0677c47e 100644
--- a/ArduCopter/Parameters.pde
+++ b/ArduCopter/Parameters.pde
@@ -20,8 +20,19 @@ static const AP_Param::Info var_info[] PROGMEM = {
 	GSCALAR(sysid_this_mav,	"SYSID_THISMAV"),
 	GSCALAR(sysid_my_gcs,	"SYSID_MYGCS"),
 	GSCALAR(serial3_baud,	"SERIAL3_BAUD"),
+	
+	// @Param
+	// @DisplayName: Alt Hold RTL
+	// @Description: This is the altitude the model will move to before Returning to Launch
+	// @Units: Meters
+	// @Range: 0 400
 	GSCALAR(RTL_altitude,	"ALT_HOLD_RTL"),
+	
+	// @Param
+	// @DisplayName: Enable Sonar
+	// @Description: Setting this to true (1) will enable the sonar. Setting this to false(0) will disable the sonar
 	GSCALAR(sonar_enabled,	"SONAR_ENABLE"),
+	
 	GSCALAR(sonar_type,	"SONAR_TYPE"),
 	GSCALAR(battery_monitoring, "BATT_MONITOR"),
 	GSCALAR(volt_div_ratio,	"VOLT_DIVIDER"),
@@ -32,10 +43,23 @@ static const AP_Param::Info var_info[] PROGMEM = {
 	GSCALAR(optflow_enabled,	"FLOW_ENABLE"),
 	GSCALAR(low_voltage,	"LOW_VOLT"),
 	GSCALAR(super_simple,	"SUPER_SIMPLE"),
+	
+	// @Param
+	// @DisplayName: RTL Land
+	// @Description: Setting this to true (1) will enable landing after RTL. Setting this to false(0) will disable landing after RTL.
 	GSCALAR(rtl_land_enabled,	"RTL_LAND"),
+
+	// @Param
+	// @DisplayName: Alt Hold RTL
+	// @Description: This is the altitude the model will move to before Returning to Launch
+	// @Units: Meters
+	// @Range: 1 10
 	GSCALAR(rtl_approach_alt,	"APPROACH_ALT"),
-	GSCALAR(retro_loiter,	"RETRO_LOITER"),
 
+	// @Param
+	// @DisplayName: Retro Loiter
+	// @Description: Setting this to true (1) will enable the Loiter from 2.0.49. Setting this to false(0) will use the most recent Loiter routines.
+	GSCALAR(retro_loiter,	"RETRO_LOITER"),
 
 	GSCALAR(waypoint_mode,	"WP_MODE"),
 	GSCALAR(command_total,	"WP_TOTAL"),
@@ -91,8 +115,12 @@ static const AP_Param::Info var_info[] PROGMEM = {
 	GGROUP(rc_8,	"RC8_", RC_Channel),
 	GGROUP(rc_camera_pitch,	"CAM_P_", RC_Channel),
 	GGROUP(rc_camera_roll,	"CAM_R_", RC_Channel),
-
-	// speed of fast RC channels in Hz
+	
+	// @Param
+	// @DisplayName: ESC Update Speed
+	// @Description: This is the speed in Hertz that your ESCs will receive updates
+	// @Units: Hertz (Hz)
+	// @Values: 400,490
 	GSCALAR(rc_speed, "RC_SPEED"),
 
 	// variable
@@ -100,7 +128,13 @@ static const AP_Param::Info var_info[] PROGMEM = {
 	GSCALAR(camera_pitch_gain, 	"CAM_P_G"),
 	GSCALAR(camera_roll_gain, 	"CAM_R_G"),
 	GSCALAR(stabilize_d, 		"STAB_D"),
+	
+	// @Param
+	// @DisplayName: Stabilize D Schedule
+	// @Description: This value is a percentage of scheduling applied to the Stabilize D term.
+	// @Range: 0 1
 	GSCALAR(stabilize_d_schedule, "STAB_D_S"),
+
 	GSCALAR(acro_p, 			"ACRO_P"),
 	GSCALAR(axis_lock_p, 		"AXIS_P"),
 	GSCALAR(axis_enabled, 		"AXIS_ENABLE"),
-- 
GitLab