aboutsummaryrefslogtreecommitdiff
path: root/src/modules/navigator
diff options
context:
space:
mode:
authorDon Gagne <don@thegagnes.com>2015-04-15 11:29:37 -0700
committerDon Gagne <don@thegagnes.com>2015-04-15 11:29:37 -0700
commit05c351183f0425f1c4feba60bf68b28d73eee51f (patch)
treecedf4dde1f5b5a41fd26e7c060a4ce7d74cb8cd1 /src/modules/navigator
parentd84ac41cd355f6c907e0a6e71a1ee12536bfb95e (diff)
downloadpx4-firmware-05c351183f0425f1c4feba60bf68b28d73eee51f.tar.gz
px4-firmware-05c351183f0425f1c4feba60bf68b28d73eee51f.tar.bz2
px4-firmware-05c351183f0425f1c4feba60bf68b28d73eee51f.zip
Parameter meta data fixes
Diffstat (limited to 'src/modules/navigator')
-rw-r--r--src/modules/navigator/datalinkloss_params.c14
-rw-r--r--src/modules/navigator/gpsfailure_params.c8
-rw-r--r--src/modules/navigator/navigator_params.c6
-rw-r--r--src/modules/navigator/rcloss_params.c2
-rw-r--r--src/modules/navigator/rtl_params.c8
5 files changed, 19 insertions, 19 deletions
diff --git a/src/modules/navigator/datalinkloss_params.c b/src/modules/navigator/datalinkloss_params.c
index 4591ec38a..9abc012cf 100644
--- a/src/modules/navigator/datalinkloss_params.c
+++ b/src/modules/navigator/datalinkloss_params.c
@@ -54,7 +54,7 @@
*
* @unit seconds
* @min 0.0
- * @group DLL
+ * @group Data Link Loss
*/
PARAM_DEFINE_FLOAT(NAV_DLL_CH_T, 120.0f);
@@ -65,7 +65,7 @@ PARAM_DEFINE_FLOAT(NAV_DLL_CH_T, 120.0f);
*
* @unit degrees * 1e7
* @min 0
- * @group DLL
+ * @group Data Link Loss
*/
PARAM_DEFINE_INT32(NAV_DLL_CH_LAT, -266072120);
@@ -76,7 +76,7 @@ PARAM_DEFINE_INT32(NAV_DLL_CH_LAT, -266072120);
*
* @unit degrees * 1e7
* @min 0
- * @group DLL
+ * @group Data Link Loss
*/
PARAM_DEFINE_INT32(NAV_DLL_CH_LON, 1518453890);
@@ -87,7 +87,7 @@ PARAM_DEFINE_INT32(NAV_DLL_CH_LON, 1518453890);
*
* @unit m
* @min 0.0
- * @group DLL
+ * @group Data Link Loss
*/
PARAM_DEFINE_FLOAT(NAV_DLL_CH_ALT, 600.0f);
@@ -98,7 +98,7 @@ PARAM_DEFINE_FLOAT(NAV_DLL_CH_ALT, 600.0f);
*
* @unit seconds
* @min 0.0
- * @group DLL
+ * @group Data Link Loss
*/
PARAM_DEFINE_FLOAT(NAV_DLL_AH_T, 120.0f);
@@ -107,7 +107,7 @@ PARAM_DEFINE_FLOAT(NAV_DLL_AH_T, 120.0f);
*
* After more than this number of data link timeouts the aircraft returns home directly
*
- * @group DLL
+ * @group Data Link Loss
* @min 0
* @max 1000
*/
@@ -119,7 +119,7 @@ PARAM_DEFINE_INT32(NAV_DLL_N, 2);
* If set to 1 the system will skip the comms hold wp on data link loss and will directly fly to
* airfield home
*
- * @group DLL
+ * @group Data Link Loss
* @min 0
* @max 1
*/
diff --git a/src/modules/navigator/gpsfailure_params.c b/src/modules/navigator/gpsfailure_params.c
index 39d179eed..98104af29 100644
--- a/src/modules/navigator/gpsfailure_params.c
+++ b/src/modules/navigator/gpsfailure_params.c
@@ -55,7 +55,7 @@
*
* @unit seconds
* @min 0.0
- * @group GPSF
+ * @group GPS Failure Navigation
*/
PARAM_DEFINE_FLOAT(NAV_GPSF_LT, 30.0f);
@@ -67,7 +67,7 @@ PARAM_DEFINE_FLOAT(NAV_GPSF_LT, 30.0f);
* @unit deg
* @min 0.0
* @max 30.0
- * @group GPSF
+ * @group GPS Failure Navigation
*/
PARAM_DEFINE_FLOAT(NAV_GPSF_R, 15.0f);
@@ -79,7 +79,7 @@ PARAM_DEFINE_FLOAT(NAV_GPSF_R, 15.0f);
* @unit deg
* @min -30.0
* @max 30.0
- * @group GPSF
+ * @group GPS Failure Navigation
*/
PARAM_DEFINE_FLOAT(NAV_GPSF_P, 0.0f);
@@ -90,7 +90,7 @@ PARAM_DEFINE_FLOAT(NAV_GPSF_P, 0.0f);
*
* @min 0.0
* @max 1.0
- * @group GPSF
+ * @group GPS Failure Navigation
*/
PARAM_DEFINE_FLOAT(NAV_GPSF_TR, 0.7f);
diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c
index b15f4e7e7..ef4a8dc0c 100644
--- a/src/modules/navigator/navigator_params.c
+++ b/src/modules/navigator/navigator_params.c
@@ -95,7 +95,7 @@ PARAM_DEFINE_INT32(NAV_RCL_OBC, 0);
*
* @unit degrees * 1e7
* @min 0
- * @group DLL
+ * @group Data Link Loss
*/
PARAM_DEFINE_INT32(NAV_AH_LAT, -265847810);
@@ -106,7 +106,7 @@ PARAM_DEFINE_INT32(NAV_AH_LAT, -265847810);
*
* @unit degrees * 1e7
* @min 0
- * @group DLL
+ * @group Data Link Loss
*/
PARAM_DEFINE_INT32(NAV_AH_LON, 1518423250);
@@ -117,6 +117,6 @@ PARAM_DEFINE_INT32(NAV_AH_LON, 1518423250);
*
* @unit m
* @min 0.0
- * @group DLL
+ * @group Data Link Loss
*/
PARAM_DEFINE_FLOAT(NAV_AH_ALT, 600.0f);
diff --git a/src/modules/navigator/rcloss_params.c b/src/modules/navigator/rcloss_params.c
index f1a01c73b..f48aabc80 100644
--- a/src/modules/navigator/rcloss_params.c
+++ b/src/modules/navigator/rcloss_params.c
@@ -55,6 +55,6 @@
*
* @unit seconds
* @min -1.0
- * @group RCL
+ * @group Radio Signal Loss
*/
PARAM_DEFINE_FLOAT(NAV_RCL_LT, 120.0f);
diff --git a/src/modules/navigator/rtl_params.c b/src/modules/navigator/rtl_params.c
index 10394fed1..7800a6f03 100644
--- a/src/modules/navigator/rtl_params.c
+++ b/src/modules/navigator/rtl_params.c
@@ -55,7 +55,7 @@
* @unit meters
* @min 20
* @max 200
- * @group RTL
+ * @group Return To Land
*/
PARAM_DEFINE_FLOAT(RTL_LOITER_RAD, 50.0f);
@@ -67,7 +67,7 @@ PARAM_DEFINE_FLOAT(RTL_LOITER_RAD, 50.0f);
* @unit meters
* @min 0
* @max 150
- * @group RTL
+ * @group Return To Land
*/
PARAM_DEFINE_FLOAT(RTL_RETURN_ALT, 60);
@@ -81,7 +81,7 @@ PARAM_DEFINE_FLOAT(RTL_RETURN_ALT, 60);
* @unit meters
* @min 2
* @max 100
- * @group RTL
+ * @group Return To Land
*/
PARAM_DEFINE_FLOAT(RTL_DESCEND_ALT, 30);
@@ -94,6 +94,6 @@ PARAM_DEFINE_FLOAT(RTL_DESCEND_ALT, 30);
* @unit seconds
* @min -1
* @max 300
- * @group RTL
+ * @group Return To Land
*/
PARAM_DEFINE_FLOAT(RTL_LAND_DELAY, -1.0f);