diff options
-rw-r--r-- | Tools/px4params/srcparser.py | 35 | ||||
-rwxr-xr-x | src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c | 22 | ||||
-rw-r--r-- | src/modules/commander/commander_params.c | 16 | ||||
-rw-r--r-- | src/modules/mavlink/mavlink.c | 4 | ||||
-rw-r--r-- | src/modules/navigator/datalinkloss_params.c | 14 | ||||
-rw-r--r-- | src/modules/navigator/gpsfailure_params.c | 8 | ||||
-rw-r--r-- | src/modules/navigator/navigator_params.c | 6 | ||||
-rw-r--r-- | src/modules/navigator/rcloss_params.c | 2 | ||||
-rw-r--r-- | src/modules/navigator/rtl_params.c | 8 | ||||
-rw-r--r-- | src/modules/sensors/sensor_params.c | 69 |
10 files changed, 116 insertions, 68 deletions
diff --git a/Tools/px4params/srcparser.py b/Tools/px4params/srcparser.py index 8e6092195..891db7ecd 100644 --- a/Tools/px4params/srcparser.py +++ b/Tools/px4params/srcparser.py @@ -83,6 +83,7 @@ class SourceParser(object): re_comment_tag = re.compile(r'@([a-zA-Z][a-zA-Z0-9_]*)\s*(.*)') re_comment_end = re.compile(r'(.*?)\s*\*\/') re_parameter_definition = re.compile(r'PARAM_DEFINE_([A-Z_][A-Z0-9_]*)\s*\(([A-Z_][A-Z0-9_]*)\s*,\s*([^ ,\)]+)\s*\)\s*;') + re_px4_parameter_definition = re.compile(r'PX4_PARAM_DEFINE_([A-Z_][A-Z0-9_]*)\s*\(([A-Z_][A-Z0-9_]*)\s*\)\s*;') re_cut_type_specifier = re.compile(r'[a-z]+$') re_is_a_number = re.compile(r'^-?[0-9\.]') re_remove_dots = re.compile(r'\.+$') @@ -206,8 +207,38 @@ class SourceParser(object): if group not in self.param_groups: self.param_groups[group] = ParameterGroup(group) self.param_groups[group].AddParameter(param) - # Reset parsed comment. - state = None + else: + # Nasty code dup, but this will all go away soon, so quick and dirty (DonLakeFlyer) + m = self.re_px4_parameter_definition.match(line) + if m: + tp, code = m.group(1, 2) + param = Parameter() + param.SetField("code", code) + param.SetField("short_desc", code) + param.SetField("type", tp) + # If comment was found before the parameter declaration, + # inject its data into the newly created parameter. + group = "Miscellaneous" + if state == "comment-processed": + if short_desc is not None: + param.SetField("short_desc", + self.re_remove_dots.sub('', short_desc)) + if long_desc is not None: + param.SetField("long_desc", long_desc) + for tag in tags: + if tag == "group": + group = tags[tag] + elif tag not in self.valid_tags: + sys.stderr.write("Skipping invalid " + "documentation tag: '%s'\n" % tag) + else: + param.SetField(tag, tags[tag]) + # Store the parameter + if group not in self.param_groups: + self.param_groups[group] = ParameterGroup(group) + self.param_groups[group].AddParameter(param) + # Reset parsed comment. + state = None def GetParamGroups(self): """ diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c index e143f37b9..fe480e12b 100755 --- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c +++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c @@ -48,49 +48,49 @@ /** * Body angular rate process noise * - * @group attitude_ekf + * @group Attitude EKF estimator */ PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q0, 1e-4f); /** * Body angular acceleration process noise * - * @group attitude_ekf + * @group Attitude EKF estimator */ PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q1, 0.08f); /** * Acceleration process noise * - * @group attitude_ekf + * @group Attitude EKF estimator */ PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q2, 0.009f); /** * Magnet field vector process noise * - * @group attitude_ekf + * @group Attitude EKF estimator */ PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q3, 0.005f); /** * Gyro measurement noise * - * @group attitude_ekf + * @group Attitude EKF estimator */ PARAM_DEFINE_FLOAT(EKF_ATT_V4_R0, 0.0008f); /** * Accel measurement noise * - * @group attitude_ekf + * @group Attitude EKF estimator */ PARAM_DEFINE_FLOAT(EKF_ATT_V4_R1, 10000.0f); /** * Mag measurement noise * - * @group attitude_ekf + * @group Attitude EKF estimator */ PARAM_DEFINE_FLOAT(EKF_ATT_V4_R2, 100.0f); @@ -102,7 +102,7 @@ PARAM_DEFINE_INT32(ATT_ACC_COMP, 2); /** * Moment of inertia matrix diagonal entry (1, 1) * - * @group attitude_ekf + * @group Attitude EKF estimator * @unit kg*m^2 */ PARAM_DEFINE_FLOAT(ATT_J11, 0.0018); @@ -110,7 +110,7 @@ PARAM_DEFINE_FLOAT(ATT_J11, 0.0018); /** * Moment of inertia matrix diagonal entry (2, 2) * - * @group attitude_ekf + * @group Attitude EKF estimator * @unit kg*m^2 */ PARAM_DEFINE_FLOAT(ATT_J22, 0.0018); @@ -118,7 +118,7 @@ PARAM_DEFINE_FLOAT(ATT_J22, 0.0018); /** * Moment of inertia matrix diagonal entry (3, 3) * - * @group attitude_ekf + * @group Attitude EKF estimator * @unit kg*m^2 */ PARAM_DEFINE_FLOAT(ATT_J33, 0.0037); @@ -128,7 +128,7 @@ PARAM_DEFINE_FLOAT(ATT_J33, 0.0037); * * If set to != 0 the moment of inertia will be used in the estimator * - * @group attitude_ekf + * @group Attitude EKF estimator * @min 0 * @max 1 */ diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 2682e5f59..6663525cc 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -105,7 +105,7 @@ PARAM_DEFINE_FLOAT(BAT_CAPACITY, -1.0f); * * Set to 1 to enable actions triggered when the datalink is lost. * - * @group commander + * @group Commander * @min 0 * @max 1 */ @@ -115,7 +115,7 @@ PARAM_DEFINE_INT32(COM_DL_LOSS_EN, 0); * * After this amount of seconds without datalink the data link lost mode triggers * - * @group commander + * @group Commander * @unit second * @min 0 * @max 30 @@ -127,7 +127,7 @@ PARAM_DEFINE_INT32(COM_DL_LOSS_T, 10); * After a data link loss: after this this amount of seconds with a healthy datalink the 'datalink loss' * flag is set back to false * - * @group commander + * @group Commander * @unit second * @min 0 * @max 30 @@ -138,7 +138,7 @@ PARAM_DEFINE_INT32(COM_DL_REG_T, 0); * * Engine failure triggers only above this throttle value * - * @group commander + * @group Commander * @min 0.0 * @max 1.0 */ @@ -148,7 +148,7 @@ PARAM_DEFINE_FLOAT(COM_EF_THROT, 0.5f); * * Engine failure triggers only below this current/throttle value * - * @group commander + * @group Commander * @min 0.0 * @max 7.0 */ @@ -159,7 +159,7 @@ PARAM_DEFINE_FLOAT(COM_EF_C2T, 5.0f); * Engine failure triggers only if the throttle threshold and the * current to throttle threshold are violated for this time * - * @group commander + * @group Commander * @unit second * @min 0.0 * @max 7.0 @@ -170,7 +170,7 @@ PARAM_DEFINE_FLOAT(COM_EF_TIME, 10.0f); * * After this amount of seconds without RC connection the rc lost flag is set to true * - * @group commander + * @group Commander * @unit second * @min 0 * @max 35 @@ -183,7 +183,7 @@ PARAM_DEFINE_FLOAT(COM_RC_LOSS_T, 0.5); * Default is on, as the interoperability with currently deployed GCS solutions depends on parameters * being sticky. Developers can default it to off. * - * @group commander + * @group Commander * @min 0 * @max 1 */ diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c index 9afe74af1..796d5cbf2 100644 --- a/src/modules/mavlink/mavlink.c +++ b/src/modules/mavlink/mavlink.c @@ -64,14 +64,18 @@ PARAM_DEFINE_INT32(MAV_COMP_ID, 50); PARAM_DEFINE_INT32(MAV_TYPE, MAV_TYPE_FIXED_WING); /** * Use/Accept HIL GPS message (even if not in HIL mode) + * * If set to 1 incomming HIL GPS messages are parsed. + * * @group MAVLink */ PARAM_DEFINE_INT32(MAV_USEHILGPS, 0); /** * Forward external setpoint messages + * * If set to 1 incomming external setpoint messages will be directly forwarded to the controllers if in offboard * control mode + * * @group MAVLink */ PARAM_DEFINE_INT32(MAV_FWDEXTSP, 1); 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); diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index 1acc14fc6..18e47865b 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -1099,7 +1099,7 @@ PARAM_DEFINE_INT32(RC_MAP_YAW, 4); * * @min 0 * @max 18 - * @group Radio Calibration + * @group Radio Switches */ PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0); @@ -1108,7 +1108,7 @@ PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0); * * @min 0 * @max 18 - * @group Radio Calibration + * @group Radio Switches */ PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0); @@ -1117,7 +1117,7 @@ PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0); * * @min 0 * @max 18 - * @group Radio Calibration + * @group Radio Switches */ PARAM_DEFINE_INT32(RC_MAP_POSCTL_SW, 0); @@ -1126,7 +1126,7 @@ PARAM_DEFINE_INT32(RC_MAP_POSCTL_SW, 0); * * @min 0 * @max 18 - * @group Radio Calibration + * @group Radio Switches */ PARAM_DEFINE_INT32(RC_MAP_LOITER_SW, 0); @@ -1135,7 +1135,7 @@ PARAM_DEFINE_INT32(RC_MAP_LOITER_SW, 0); * * @min 0 * @max 18 - * @group Radio Calibration + * @group Radio Switches */ PARAM_DEFINE_INT32(RC_MAP_ACRO_SW, 0); @@ -1144,7 +1144,7 @@ PARAM_DEFINE_INT32(RC_MAP_ACRO_SW, 0); * * @min 0 * @max 18 - * @group Radio Calibration + * @group Radio Switches */ PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0); @@ -1153,7 +1153,7 @@ PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0); * * @min 0 * @max 18 - * @group Radio Calibration + * @group Radio Switches */ PARAM_DEFINE_INT32(RC_MAP_FLAPS, 0); @@ -1238,9 +1238,6 @@ PARAM_DEFINE_INT32(RC_FAILS_THR, 0); /** * Threshold for selecting assist mode * - * min:-1 - * max:+1 - * * 0-1 indicate where in the full channel range the threshold sits * 0 : min * 1 : max @@ -1248,15 +1245,17 @@ PARAM_DEFINE_INT32(RC_FAILS_THR, 0); * positive : true when channel>th * negative : true when channel<th * + * @min -1 + * @max 1 + * @group Radio Switches + * + * */ PARAM_DEFINE_FLOAT(RC_ASSIST_TH, 0.25f); /** * Threshold for selecting auto mode * - * min:-1 - * max:+1 - * * 0-1 indicate where in the full channel range the threshold sits * 0 : min * 1 : max @@ -1264,15 +1263,17 @@ PARAM_DEFINE_FLOAT(RC_ASSIST_TH, 0.25f); * positive : true when channel>th * negative : true when channel<th * + * @min -1 + * @max 1 + * @group Radio Switches + * + * */ PARAM_DEFINE_FLOAT(RC_AUTO_TH, 0.75f); /** * Threshold for selecting posctl mode * - * min:-1 - * max:+1 - * * 0-1 indicate where in the full channel range the threshold sits * 0 : min * 1 : max @@ -1280,15 +1281,16 @@ PARAM_DEFINE_FLOAT(RC_AUTO_TH, 0.75f); * positive : true when channel>th * negative : true when channel<th * + * @min -1 + * @max 1 + * + * */ PARAM_DEFINE_FLOAT(RC_POSCTL_TH, 0.5f); /** * Threshold for selecting return to launch mode * - * min:-1 - * max:+1 - * * 0-1 indicate where in the full channel range the threshold sits * 0 : min * 1 : max @@ -1296,15 +1298,17 @@ PARAM_DEFINE_FLOAT(RC_POSCTL_TH, 0.5f); * positive : true when channel>th * negative : true when channel<th * + * @min -1 + * @max 1 + * @group Radio Switches + * + * */ PARAM_DEFINE_FLOAT(RC_RETURN_TH, 0.5f); /** * Threshold for selecting loiter mode * - * min:-1 - * max:+1 - * * 0-1 indicate where in the full channel range the threshold sits * 0 : min * 1 : max @@ -1312,15 +1316,17 @@ PARAM_DEFINE_FLOAT(RC_RETURN_TH, 0.5f); * positive : true when channel>th * negative : true when channel<th * + * @min -1 + * @max 1 + * @group Radio Switches + * + * */ PARAM_DEFINE_FLOAT(RC_LOITER_TH, 0.5f); /** * Threshold for selecting acro mode * - * min:-1 - * max:+1 - * * 0-1 indicate where in the full channel range the threshold sits * 0 : min * 1 : max @@ -1328,6 +1334,11 @@ PARAM_DEFINE_FLOAT(RC_LOITER_TH, 0.5f); * positive : true when channel>th * negative : true when channel<th * + * @min -1 + * @max 1 + * @group Radio Switches + * + * */ PARAM_DEFINE_FLOAT(RC_ACRO_TH, 0.5f); @@ -1335,9 +1346,6 @@ PARAM_DEFINE_FLOAT(RC_ACRO_TH, 0.5f); /** * Threshold for selecting offboard mode * - * min:-1 - * max:+1 - * * 0-1 indicate where in the full channel range the threshold sits * 0 : min * 1 : max @@ -1345,5 +1353,10 @@ PARAM_DEFINE_FLOAT(RC_ACRO_TH, 0.5f); * positive : true when channel>th * negative : true when channel<th * + * @min -1 + * @max 1 + * @group Radio Switches + * + * */ PARAM_DEFINE_FLOAT(RC_OFFB_TH, 0.5f); |