From c748eb67574963798d4a96c0a0b99165aed902d4 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 25 Mar 2016 16:28:51 -0400 Subject: [PATCH 1/8] cleanup mission params --- src/modules/navigator/mission_params.c | 15 +-------------- 1 file changed, 1 insertion(+), 14 deletions(-) diff --git a/src/modules/navigator/mission_params.c b/src/modules/navigator/mission_params.c index ef44cda38d..1ee45bdbfe 100644 --- a/src/modules/navigator/mission_params.c +++ b/src/modules/navigator/mission_params.c @@ -102,13 +102,8 @@ PARAM_DEFINE_FLOAT(MIS_DIST_1WP, 900); * @unit enum * @min 0 * @max 1 -<<<<<<< e22e0b28b61a7b4f7d10756678b8f4b533b3622e * @value 0 Zero Order Hold * @value 1 First Order Hold -======= - * @value 0 zero order - * @value 1 first order ->>>>>>> mission param @unit * @group Mission */ PARAM_DEFINE_INT32(MIS_ALTMODE, 1); @@ -121,17 +116,10 @@ PARAM_DEFINE_INT32(MIS_ALTMODE, 1); * @unit enum * @min 0 * @max 3 -<<<<<<< e22e0b28b61a7b4f7d10756678b8f4b533b3622e * @value 0 Heading as set by waypoint * @value 1 Heading towards waypoint * @value 2 Heading towards home * @value 3 Heading away from home -======= - * @value 0 destination - * @value 1 next - * @value 2 home - * @value 3 home back ->>>>>>> mission param @unit * @group Mission */ PARAM_DEFINE_INT32(MIS_YAWMODE, 1); @@ -144,9 +132,9 @@ PARAM_DEFINE_INT32(MIS_YAWMODE, 1); * Mainly useful for VTOLs that have less yaw authority and might not reach target * yaw in wind. Disabled by default. * + * @unit s * @min -1 * @max 20 - * @unit second * @increment 1 * @group Mission */ @@ -158,7 +146,6 @@ PARAM_DEFINE_FLOAT(MIS_YAW_TMT, -1.0f); * @unit deg * @min 0 * @max 90 - * @unit degree * @increment 1 * @group Mission */ From b26f90406bebafdd5ba1dd07ae7b93326f18d61d Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 25 Mar 2016 17:04:59 -0400 Subject: [PATCH 2/8] group l1 control and tecs as FW --- .../fw_pos_control_l1_params.c | 74 +++++++++---------- 1 file changed, 37 insertions(+), 37 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c index 6069e3cbf9..d5fed52e7c 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c @@ -54,7 +54,7 @@ * @unit m * @min 12.0 * @max 50.0 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_L1_PERIOD, 20.0f); @@ -65,7 +65,7 @@ PARAM_DEFINE_FLOAT(FW_L1_PERIOD, 20.0f); * * @min 0.6 * @max 0.9 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f); @@ -76,7 +76,7 @@ PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f); * * @min 0.0 * @max 1.0 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_THR_CRUISE, 0.6f); @@ -87,7 +87,7 @@ PARAM_DEFINE_FLOAT(FW_THR_CRUISE, 0.6f); * * @min 0.0 * @max 1.0 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f); @@ -99,7 +99,7 @@ PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f); * @unit deg * @min -60.0 * @max 0.0 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -45.0f); @@ -111,7 +111,7 @@ PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -45.0f); * @unit deg * @min 0.0 * @max 60.0 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 45.0f); @@ -123,7 +123,7 @@ PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 45.0f); * @unit deg * @min 35.0 * @max 65.0 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_R_LIM, 50.0f); @@ -136,7 +136,7 @@ PARAM_DEFINE_FLOAT(FW_R_LIM, 50.0f); * * @min 0.0 * @max 1.0 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f); @@ -154,7 +154,7 @@ PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f); * * @min 0.0 * @max 1.0 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f); @@ -168,7 +168,7 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f); * * @min 0.0 * @max 0.4 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_THR_IDLE, 0.15f); @@ -180,7 +180,7 @@ PARAM_DEFINE_FLOAT(FW_THR_IDLE, 0.15f); * * @min 0.0 * @max 1.0 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f); @@ -195,7 +195,7 @@ PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f); * @unit m * @min 0.0 * @max 150.0 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_CLMBOUT_DIFF, 10.0f); @@ -218,7 +218,7 @@ PARAM_DEFINE_FLOAT(FW_CLMBOUT_DIFF, 10.0f); * @unit m/s * @min 2.0 * @max 10.0 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f); @@ -230,7 +230,7 @@ PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f); * to measure FW_T_CLMB_MAX. * * @unit m/s - * @group Fixed Wing TECS + * @group FW TECS */ PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f); @@ -244,7 +244,7 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f); * the aircraft. * * @unit m/s - * @group Fixed Wing TECS + * @group FW TECS */ PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f); @@ -256,7 +256,7 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f); * to respond. * * @unit s - * @group Fixed Wing TECS + * @group FW TECS */ PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f); @@ -268,7 +268,7 @@ PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f); * to respond. * * @unit s - * @group Fixed Wing TECS + * @group FW TECS */ PARAM_DEFINE_FLOAT(FW_T_THRO_CONST, 8.0f); @@ -278,7 +278,7 @@ PARAM_DEFINE_FLOAT(FW_T_THRO_CONST, 8.0f); * This is the damping gain for the throttle demand loop. * Increase to add damping to correct for oscillations in speed and height. * - * @group Fixed Wing TECS + * @group FW TECS */ PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f); @@ -290,7 +290,7 @@ PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f); * and height offsets are trimmed out, but reduces damping and * increases overshoot. * - * @group Fixed Wing TECS + * @group FW TECS */ PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f); @@ -304,7 +304,7 @@ PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f); * from under-speed conditions. * * @unit m/s/s - * @group Fixed Wing TECS + * @group FW TECS */ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); @@ -318,7 +318,7 @@ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); * the solution more towards use of the accelerometer data. * * @unit rad/s - * @group Fixed Wing TECS + * @group FW TECS */ PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f); @@ -332,7 +332,7 @@ PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f); * solution more towards use of the accelerometer data. * * @unit rad/s - * @group Fixed Wing TECS + * @group FW TECS */ PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f); @@ -348,7 +348,7 @@ PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f); * aircraft (eg powered sailplanes) can use a lower value, whereas * inefficient low aspect-ratio models (eg delta wings) can use a higher value. * - * @group Fixed Wing TECS + * @group FW TECS */ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f); @@ -368,7 +368,7 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f); * * @min 0.0 * @max 2.0 - * @group Fixed Wing TECS + * @group FW TECS */ PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f); @@ -380,28 +380,28 @@ PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f); * will work well provided the pitch to servo controller has been tuned * properly. * - * @group Fixed Wing TECS + * @group FW TECS */ PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f); /** * Height rate P factor * - * @group Fixed Wing TECS + * @group FW TECS */ PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f); /** * Height rate FF factor * - * @group Fixed Wing TECS + * @group FW TECS */ PARAM_DEFINE_FLOAT(FW_T_HRATE_FF, 0.0f); /** * Speed rate P factor * - * @group Fixed Wing TECS + * @group FW TECS */ PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.02f); @@ -411,7 +411,7 @@ PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.02f); * @unit deg * @min 1.0 * @max 15.0 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_LND_ANG, 5.0f); @@ -419,7 +419,7 @@ PARAM_DEFINE_FLOAT(FW_LND_ANG, 5.0f); * * * @unit m - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_LND_HVIRT, 10.0f); @@ -429,7 +429,7 @@ PARAM_DEFINE_FLOAT(FW_LND_HVIRT, 10.0f); * @unit m * @min 0.0 * @max 25.0 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_LND_FLALT, 8.0f); @@ -442,7 +442,7 @@ PARAM_DEFINE_FLOAT(FW_LND_FLALT, 8.0f); * @unit m * @min -1.0 * @max 30.0 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_LND_TLALT, -1.0f); @@ -452,7 +452,7 @@ PARAM_DEFINE_FLOAT(FW_LND_TLALT, -1.0f); * @unit m * @min 0 * @max 30.0 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f); @@ -462,7 +462,7 @@ PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f); * 0: disabled, 1: enabled * * @unit boolean - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_INT32(FW_LND_USETER, 0); @@ -475,7 +475,7 @@ PARAM_DEFINE_INT32(FW_LND_USETER, 0); * @unit deg * @min 0 * @max 15.0 - * @group L1 Control + * @group FW L1 Control * */ PARAM_DEFINE_FLOAT(FW_LND_FL_PMIN, 2.5f); @@ -489,7 +489,7 @@ PARAM_DEFINE_FLOAT(FW_LND_FL_PMIN, 2.5f); * @unit deg * @min 0 * @max 45.0 - * @group L1 Control + * @group FW L1 Control * */ PARAM_DEFINE_FLOAT(FW_LND_FL_PMAX, 15.0f); @@ -502,6 +502,6 @@ PARAM_DEFINE_FLOAT(FW_LND_FL_PMAX, 15.0f); * * @min 1.0 * @max 1.5 - * @group L1 Control + * @group FW L1 Control */ PARAM_DEFINE_FLOAT(FW_LND_AIRSPD_SC, 1.3f); From ff9b8118ab6f1e6ba9896b5c525e90a0e620c6d2 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 25 Mar 2016 17:24:48 -0400 Subject: [PATCH 3/8] fw_att_control add units --- .../fw_att_control/fw_att_control_params.c | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/src/modules/fw_att_control/fw_att_control_params.c b/src/modules/fw_att_control/fw_att_control_params.c index ee4f56588b..d592a6c796 100644 --- a/src/modules/fw_att_control/fw_att_control_params.c +++ b/src/modules/fw_att_control/fw_att_control_params.c @@ -83,6 +83,7 @@ PARAM_DEFINE_FLOAT(FW_P_TC, 0.4f); * This defines how much the elevator input will be commanded depending on the * current body angular rate error. * + * @unit %/rad/s * @min 0.005 * @max 1.0 * @group FW Attitude Control @@ -95,6 +96,7 @@ PARAM_DEFINE_FLOAT(FW_PR_P, 0.08f); * This gain defines how much control response will result out of a steady * state error. It trims any constant error. * + * @unit %/rad * @min 0.005 * @max 0.5 * @group FW Attitude Control @@ -133,6 +135,7 @@ PARAM_DEFINE_FLOAT(FW_P_RMAX_NEG, 60.0f); * The portion of the integrator part in the control surface deflection is * limited to this value * + * @unit % * @min 0.0 * @max 1.0 * @group FW Attitude Control @@ -145,6 +148,7 @@ PARAM_DEFINE_FLOAT(FW_PR_IMAX, 0.4f); * This defines how much the aileron input will be commanded depending on the * current body angular rate error. * + * @unit %/rad/s * @min 0.005 * @max 1.0 * @group FW Attitude Control @@ -157,6 +161,7 @@ PARAM_DEFINE_FLOAT(FW_RR_P, 0.05f); * This gain defines how much control response will result out of a steady * state error. It trims any constant error. * + * @unit %/rad * @min 0.005 * @max 0.2 * @group FW Attitude Control @@ -168,6 +173,7 @@ PARAM_DEFINE_FLOAT(FW_RR_I, 0.01f); * * The portion of the integrator part in the control surface deflection is limited to this value. * + * @unit % * @min 0.0 * @max 1.0 * @group FW Attitude Control @@ -193,6 +199,7 @@ PARAM_DEFINE_FLOAT(FW_R_RMAX, 70.0f); * This defines how much the rudder input will be commanded depending on the * current body angular rate error. * + * @unit %/rad/s * @min 0.005 * @max 1.0 * @group FW Attitude Control @@ -205,6 +212,7 @@ PARAM_DEFINE_FLOAT(FW_YR_P, 0.05f); * This gain defines how much control response will result out of a steady * state error. It trims any constant error. * + * @unit %/rad * @min 0.0 * @max 50.0 * @group FW Attitude Control @@ -217,6 +225,7 @@ PARAM_DEFINE_FLOAT(FW_YR_I, 0.0f); * The portion of the integrator part in the control surface deflection is * limited to this value * + * @unit % * @min 0.0 * @max 1.0 * @group FW Attitude Control @@ -242,6 +251,7 @@ PARAM_DEFINE_FLOAT(FW_Y_RMAX, 0.0f); * This defines how much the wheel steering input will be commanded depending on the * current body angular rate error. * + * @unit %/rad/s * @min 0.005 * @max 1.0 * @group FW Attitude Control @@ -254,6 +264,7 @@ PARAM_DEFINE_FLOAT(FW_WR_P, 0.5f); * This gain defines how much control response will result out of a steady * state error. It trims any constant error. * + * @unit %/rad * @min 0.0 * @max 50.0 * @group FW Attitude Control @@ -266,6 +277,7 @@ PARAM_DEFINE_FLOAT(FW_WR_I, 0.1f); * The portion of the integrator part in the control surface deflection is * limited to this value * + * @unit % * @min 0.0 * @max 1.0 * @group FW Attitude Control @@ -292,6 +304,7 @@ PARAM_DEFINE_FLOAT(FW_W_RMAX, 0.0f); * to obtain a tigher response of the controller without introducing * noise amplification. * + * @unit %/rad/s * @min 0.0 * @max 10.0 * @group FW Attitude Control @@ -303,6 +316,7 @@ PARAM_DEFINE_FLOAT(FW_RR_FF, 0.5f); * * Direct feed forward from rate setpoint to control surface output * + * @unit %/rad/s * @min 0.0 * @max 10.0 * @group FW Attitude Control @@ -314,6 +328,7 @@ PARAM_DEFINE_FLOAT(FW_PR_FF, 0.5f); * * Direct feed forward from rate setpoint to control surface output * + * @unit %/rad/s * @min 0.0 * @max 10.0 * @group FW Attitude Control @@ -325,6 +340,7 @@ PARAM_DEFINE_FLOAT(FW_YR_FF, 0.3f); * * Direct feed forward from rate setpoint to control surface output * + * @unit %/rad/s * @min 0.0 * @max 10.0 * @group FW Attitude Control From 70a68def83db787caba14f49172d055c90d5ad3a Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 25 Mar 2016 20:25:17 -0400 Subject: [PATCH 4/8] params correct boolean tag --- src/drivers/gimbal/gimbal_params.c | 2 +- src/drivers/px4fmu/px4fmu_params.c | 12 ++++++------ src/drivers/px4io/px4io_params.c | 18 +++++++++--------- .../launchdetection/launchdetection_params.c | 2 +- src/lib/runway_takeoff/runway_takeoff_params.c | 2 +- .../attitude_estimator_q_params.c | 4 ++-- src/modules/commander/commander_params.c | 4 ++-- src/modules/ekf2/ekf2_params.c | 2 +- .../fw_pos_control_l1_params.c | 2 +- .../fw_pos_control_l1/mtecs/mTecs_params.c | 2 +- src/modules/local_position_estimator/params.c | 4 ++-- src/modules/mavlink/mavlink_params.c | 4 ++-- src/modules/navigator/datalinkloss_params.c | 2 +- src/modules/navigator/mission_params.c | 2 +- src/modules/navigator/navigator_params.c | 4 ++-- .../position_estimator_inav_params.cpp | 6 +++--- src/modules/sdlog2/params.c | 2 +- src/modules/sensors/sensor_params.c | 4 ++-- .../vtol_att_control/vtol_att_control_params.c | 10 +++++----- 19 files changed, 44 insertions(+), 44 deletions(-) diff --git a/src/drivers/gimbal/gimbal_params.c b/src/drivers/gimbal/gimbal_params.c index 7faa4fee82..05bcbf5a7c 100644 --- a/src/drivers/gimbal/gimbal_params.c +++ b/src/drivers/gimbal/gimbal_params.c @@ -48,7 +48,7 @@ * * If set to 1, mount mode will be enforced. * - * @unit boolean + * @boolean * @group Gimbal */ PARAM_DEFINE_INT32(GMB_USE_MNT, 0); diff --git a/src/drivers/px4fmu/px4fmu_params.c b/src/drivers/px4fmu/px4fmu_params.c index 06727080aa..56502bdaf5 100644 --- a/src/drivers/px4fmu/px4fmu_params.c +++ b/src/drivers/px4fmu/px4fmu_params.c @@ -48,7 +48,7 @@ * Set to 1 to invert the channel, 0 for default direction. * * @reboot_required true - * @unit boolean + * @boolean * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_AUX_REV1, 0); @@ -59,7 +59,7 @@ PARAM_DEFINE_INT32(PWM_AUX_REV1, 0); * Set to 1 to invert the channel, 0 for default direction. * * @reboot_required true - * @unit boolean + * @boolean * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_AUX_REV2, 0); @@ -70,7 +70,7 @@ PARAM_DEFINE_INT32(PWM_AUX_REV2, 0); * Set to 1 to invert the channel, 0 for default direction. * * @reboot_required true - * @unit boolean + * @boolean * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_AUX_REV3, 0); @@ -81,7 +81,7 @@ PARAM_DEFINE_INT32(PWM_AUX_REV3, 0); * Set to 1 to invert the channel, 0 for default direction. * * @reboot_required true - * @unit boolean + * @boolean * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_AUX_REV4, 0); @@ -92,7 +92,7 @@ PARAM_DEFINE_INT32(PWM_AUX_REV4, 0); * Set to 1 to invert the channel, 0 for default direction. * * @reboot_required true - * @unit boolean + * @boolean * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_AUX_REV5, 0); @@ -103,7 +103,7 @@ PARAM_DEFINE_INT32(PWM_AUX_REV5, 0); * Set to 1 to invert the channel, 0 for default direction. * * @reboot_required true - * @unit boolean + * @boolean * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_AUX_REV6, 0); diff --git a/src/drivers/px4io/px4io_params.c b/src/drivers/px4io/px4io_params.c index 2da0835318..bc1e349b85 100644 --- a/src/drivers/px4io/px4io_params.c +++ b/src/drivers/px4io/px4io_params.c @@ -48,7 +48,7 @@ * Set to 1 to invert the channel, 0 for default direction. * * @reboot_required true - * @unit boolean + * @boolean * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_MAIN_REV1, 0); @@ -59,7 +59,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV1, 0); * Set to 1 to invert the channel, 0 for default direction. * * @reboot_required true - * @unit boolean + * @boolean * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_MAIN_REV2, 0); @@ -70,7 +70,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV2, 0); * Set to 1 to invert the channel, 0 for default direction. * * @reboot_required true - * @unit boolean + * @boolean * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_MAIN_REV3, 0); @@ -81,7 +81,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV3, 0); * Set to 1 to invert the channel, 0 for default direction. * * @reboot_required true - * @unit boolean + * @boolean * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_MAIN_REV4, 0); @@ -92,7 +92,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV4, 0); * Set to 1 to invert the channel, 0 for default direction. * * @reboot_required true - * @unit boolean + * @boolean * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_MAIN_REV5, 0); @@ -103,7 +103,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV5, 0); * Set to 1 to invert the channel, 0 for default direction. * * @reboot_required true - * @unit boolean + * @boolean * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_MAIN_REV6, 0); @@ -114,7 +114,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV6, 0); * Set to 1 to invert the channel, 0 for default direction. * * @reboot_required true - * @unit boolean + * @boolean * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_MAIN_REV7, 0); @@ -125,7 +125,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV7, 0); * Set to 1 to invert the channel, 0 for default direction. * * @reboot_required true - * @unit boolean + * @boolean * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_MAIN_REV8, 0); @@ -135,7 +135,7 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV8, 0); * * Set to 1 to enable S.BUS version 1 output instead of RSSI. * - * @unit boolean + * @boolean * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_SBUS_MODE, 0); diff --git a/src/lib/launchdetection/launchdetection_params.c b/src/lib/launchdetection/launchdetection_params.c index 3a1607180d..9af90279d2 100644 --- a/src/lib/launchdetection/launchdetection_params.c +++ b/src/lib/launchdetection/launchdetection_params.c @@ -47,7 +47,7 @@ /** * Enable launch detection. * - * @unit boolean + * @boolean * @min 0 * @max 1 * @group Launch detection diff --git a/src/lib/runway_takeoff/runway_takeoff_params.c b/src/lib/runway_takeoff/runway_takeoff_params.c index 953773747b..ad5cecbb09 100644 --- a/src/lib/runway_takeoff/runway_takeoff_params.c +++ b/src/lib/runway_takeoff/runway_takeoff_params.c @@ -44,7 +44,7 @@ * * 0: disabled, 1: enabled * - * @unit boolean + * @boolean * @group Runway Takeoff */ PARAM_DEFINE_INT32(RWTO_TKOFF, 0); diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_params.c b/src/modules/attitude_estimator_q/attitude_estimator_q_params.c index 73513872d8..a7e16c56d7 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_params.c +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_params.c @@ -97,7 +97,7 @@ PARAM_DEFINE_FLOAT(ATT_MAG_DECL, 0.0f); * Enable automatic GPS based declination compensation * * @group Attitude Q estimator - * @unit boolean + * @boolean */ PARAM_DEFINE_INT32(ATT_MAG_DECL_A, 1); @@ -121,7 +121,7 @@ PARAM_DEFINE_INT32(ATT_EXT_HDG_M, 0); * velocity. * * @group Attitude Q estimator - * @unit boolean + * @boolean */ PARAM_DEFINE_INT32(ATT_ACC_COMP, 1); diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 04bf15ec07..dc0a8de0fd 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -178,7 +178,7 @@ PARAM_DEFINE_FLOAT(BAT_CAPACITY, -1.0f); * Set to 1 to enable actions triggered when the datalink is lost. * * @group Commander - * @unit boolean + * @boolean */ PARAM_DEFINE_INT32(COM_DL_LOSS_EN, 0); @@ -303,7 +303,7 @@ PARAM_DEFINE_FLOAT(COM_HOME_V_T, 10.0f); * being sticky. Developers can default it to off. * * @group Commander - * @unit boolean + * @boolean */ PARAM_DEFINE_INT32(COM_AUTOS_PAR, 1); diff --git a/src/modules/ekf2/ekf2_params.c b/src/modules/ekf2/ekf2_params.c index f777814588..2014b527db 100644 --- a/src/modules/ekf2/ekf2_params.c +++ b/src/modules/ekf2/ekf2_params.c @@ -387,7 +387,7 @@ PARAM_DEFINE_FLOAT(EKF2_GPS_V_GATE, 3.0f); * replay messages for logging. * * @group EKF2 - * @unit boolean + * @boolean */ PARAM_DEFINE_INT32(EKF2_REC_RPL, 0); diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c index d5fed52e7c..efccee1c12 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c @@ -461,7 +461,7 @@ PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f); * * 0: disabled, 1: enabled * - * @unit boolean + * @boolean * @group FW L1 Control */ PARAM_DEFINE_INT32(FW_LND_USETER, 0); diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c b/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c index 14543dfe45..dd457b664a 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c @@ -47,7 +47,7 @@ * * Set to 1 to enable mTECS * - * @unit boolean + * @boolean * @group mTECS */ PARAM_DEFINE_INT32(MT_ENABLED, 0); diff --git a/src/modules/local_position_estimator/params.c b/src/modules/local_position_estimator/params.c index 4b2ff0ebd6..be8008d8ad 100644 --- a/src/modules/local_position_estimator/params.c +++ b/src/modules/local_position_estimator/params.c @@ -6,7 +6,7 @@ /** * Enable local position estimator. * - * @unit boolean + * @boolean * @group Local Position Estimator */ PARAM_DEFINE_INT32(LPE_ENABLED, 1); @@ -14,7 +14,7 @@ PARAM_DEFINE_INT32(LPE_ENABLED, 1); /** * Enable accelerometer integration for prediction. * - * @unit boolean + * @boolean * @group Local Position Estimator */ PARAM_DEFINE_INT32(LPE_INTEGRATE, 1); diff --git a/src/modules/mavlink/mavlink_params.c b/src/modules/mavlink/mavlink_params.c index b0b0ff6a55..0dba4d870f 100644 --- a/src/modules/mavlink/mavlink_params.c +++ b/src/modules/mavlink/mavlink_params.c @@ -74,7 +74,7 @@ PARAM_DEFINE_INT32(MAV_TYPE, 1); * * If set to 1 incoming HIL GPS messages are parsed. * - * @unit boolean + * @boolean * @group MAVLink */ PARAM_DEFINE_INT32(MAV_USEHILGPS, 0); @@ -85,7 +85,7 @@ PARAM_DEFINE_INT32(MAV_USEHILGPS, 0); * If set to 1 incoming external setpoint messages will be directly forwarded * to the controllers if in offboard control mode * - * @unit boolean + * @boolean * @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 e86802cd20..8a5c59b87a 100644 --- a/src/modules/navigator/datalinkloss_params.c +++ b/src/modules/navigator/datalinkloss_params.c @@ -119,6 +119,6 @@ PARAM_DEFINE_INT32(NAV_DLL_N, 2); * airfield home * * @group Data Link Loss - * @unit boolean + * @boolean */ PARAM_DEFINE_INT32(NAV_DLL_CHSK, 0); diff --git a/src/modules/navigator/mission_params.c b/src/modules/navigator/mission_params.c index 1ee45bdbfe..17febd73f2 100644 --- a/src/modules/navigator/mission_params.c +++ b/src/modules/navigator/mission_params.c @@ -73,7 +73,7 @@ PARAM_DEFINE_FLOAT(MIS_LTRMIN_ALT, 1.2f); * When enabled, missions that have been uploaded by the GCS are stored * and reloaded after reboot persistently. * - * @unit boolean + * @boolean * @group Mission */ PARAM_DEFINE_INT32(MIS_ONBOARD_EN, 1); diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c index 746193135d..aeff97111a 100644 --- a/src/modules/navigator/navigator_params.c +++ b/src/modules/navigator/navigator_params.c @@ -69,7 +69,7 @@ PARAM_DEFINE_FLOAT(NAV_ACC_RAD, 10.0f); * * If set to 1 the behaviour on data link loss is set to a mode according to the Outback Challenge (OBC) rules * - * @unit boolean + * @boolean * @group Mission */ PARAM_DEFINE_INT32(NAV_DLL_OBC, 0); @@ -79,7 +79,7 @@ PARAM_DEFINE_INT32(NAV_DLL_OBC, 0); * * If set to 1 the behaviour on data link loss is set to a mode according to the Outback Challenge (OBC) rules * - * @unit boolean + * @boolean * @group Mission */ PARAM_DEFINE_INT32(NAV_RCL_OBC, 0); diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.cpp b/src/modules/position_estimator_inav/position_estimator_inav_params.cpp index 1fb1fc702b..a680f6b487 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_params.cpp +++ b/src/modules/position_estimator_inav/position_estimator_inav_params.cpp @@ -306,7 +306,7 @@ PARAM_DEFINE_FLOAT(INAV_FLOW_DIST_Y, 0.0f); * * Disable mocap * - * @unit boolean + * @boolean * @group Position Estimator INAV */ PARAM_DEFINE_FLOAT(INAV_DISAB_MOCAP, 0); @@ -316,7 +316,7 @@ PARAM_DEFINE_FLOAT(INAV_DISAB_MOCAP, 0); * * Enable LIDAR for altitude estimation * - * @unit boolean + * @boolean * @group Position Estimator INAV */ PARAM_DEFINE_FLOAT(INAV_LIDAR_EST, 0); @@ -352,7 +352,7 @@ PARAM_DEFINE_INT32(CBRK_NO_VISION, 0); * Else the system uses the combined attitude / position * filter framework. * - * @unit boolean + * @boolean * @group Position Estimator INAV */ PARAM_DEFINE_INT32(INAV_ENABLED, 1); diff --git a/src/modules/sdlog2/params.c b/src/modules/sdlog2/params.c index cf506f81e8..c4f1fa473a 100644 --- a/src/modules/sdlog2/params.c +++ b/src/modules/sdlog2/params.c @@ -73,7 +73,7 @@ PARAM_DEFINE_INT32(SDLOG_EXT, -1); * to only use the time stamp if a 3D GPS lock is * present. * - * @unit boolean + * @boolean * @group SD Logging */ PARAM_DEFINE_INT32(SDLOG_GPSTIME, 1); diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index 695229b13d..544fe0915d 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -1992,7 +1992,7 @@ PARAM_DEFINE_INT32(RC_CHAN_CNT, 0); * indicates that the threshold value where automatically set by the ground * station software. It is only meant for ground station use. * - * @unit boolean + * @boolean * @group Radio Calibration */ @@ -2888,7 +2888,7 @@ PARAM_DEFINE_INT32(RC_RSSI_PWM_MIN, 2000); * * @reboot_required true * - * @unit boolean + * @boolean * @group Sensor Enable */ PARAM_DEFINE_INT32(SENS_EN_LL40LS, 0); diff --git a/src/modules/vtol_att_control/vtol_att_control_params.c b/src/modules/vtol_att_control/vtol_att_control_params.c index 90478bb27b..e55af6bd22 100644 --- a/src/modules/vtol_att_control/vtol_att_control_params.c +++ b/src/modules/vtol_att_control/vtol_att_control_params.c @@ -110,7 +110,7 @@ PARAM_DEFINE_FLOAT(VT_MC_ARSPD_TRIM, 10.0f); * If set to one this parameter will cause permanent attitude stabilization in fw mode. * This parameter has been introduced for pure convenience sake. * - * @unit boolean + * @boolean * @group VTOL Attitude Control */ PARAM_DEFINE_INT32(VT_FW_PERM_STAB, 0); @@ -188,7 +188,7 @@ PARAM_DEFINE_INT32(VT_TYPE, 0); * * If set to 1 the elevons are locked in multicopter mode * - * @unit boolean + * @boolean * @group VTOL Attitude Control */ PARAM_DEFINE_INT32(VT_ELEV_MC_LOCK, 0); @@ -252,7 +252,7 @@ PARAM_DEFINE_FLOAT(VT_ARSP_TRANS, 10.0f); /** * Enable optimal recovery strategy for pitch-weak tailsitters * - * @unit boolean + * @boolean * @group VTOL Attitude Control */ PARAM_DEFINE_INT32(VT_OPT_RECOV_EN, 0); @@ -260,7 +260,7 @@ PARAM_DEFINE_INT32(VT_OPT_RECOV_EN, 0); /** * Enable weather-vane mode landings for missions * - * @unit boolean + * @boolean * @group VTOL Attitude Control */ PARAM_DEFINE_INT32(VT_WV_LND_EN, 0); @@ -282,7 +282,7 @@ PARAM_DEFINE_FLOAT(VT_WV_YAWR_SCL, 0.15f); /** * Enable weather-vane mode for loiter * - * @unit boolean + * @boolean * @group VTOL Attitude Control */ PARAM_DEFINE_INT32(VT_WV_LTR_EN, 0); From bee39d93d9d9bdcd14aa8e20c3db41d7625fad79 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 25 Mar 2016 20:27:48 -0400 Subject: [PATCH 5/8] battery param add units --- src/modules/commander/commander_params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index dc0a8de0fd..f153fc602e 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -137,7 +137,7 @@ PARAM_DEFINE_FLOAT(BAT_V_LOAD_DROP, 0.07f); * Defines the number of cells the attached battery consists of. * * @group Battery Calibration - * @unit enum + * @unit cells * @min 2 * @max 10 * @value 2 2S Battery From 68885450370382e36e2bd72c11e825afb871775e Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 25 Mar 2016 20:33:25 -0400 Subject: [PATCH 6/8] remove @unit enum --- .../camera_trigger/camera_trigger_params.c | 2 -- src/drivers/gimbal/gimbal_params.c | 1 - src/drivers/mkblctrl/mkblctrl_params.c | 1 - .../runway_takeoff/runway_takeoff_params.c | 1 - .../attitude_estimator_q_params.c | 1 - src/modules/commander/commander_params.c | 9 +----- src/modules/ekf2/ekf2_params.c | 1 - .../fw_att_control/fw_att_control_params.c | 1 - src/modules/navigator/geofence_params.c | 3 -- src/modules/navigator/mission_params.c | 2 -- src/modules/sdlog2/params.c | 1 - src/modules/sensors/sensor_params.c | 30 ------------------- src/modules/systemlib/system_params.c | 1 - src/modules/uavcan/uavcan_params.c | 1 - .../vtol_att_control_params.c | 1 - 15 files changed, 1 insertion(+), 55 deletions(-) diff --git a/src/drivers/camera_trigger/camera_trigger_params.c b/src/drivers/camera_trigger/camera_trigger_params.c index 54fa0133b9..9459841a36 100644 --- a/src/drivers/camera_trigger/camera_trigger_params.c +++ b/src/drivers/camera_trigger/camera_trigger_params.c @@ -58,7 +58,6 @@ PARAM_DEFINE_FLOAT(TRIG_INTERVAL, 40.0f); * * This parameter sets the polarity of the trigger (0 = ACTIVE_LOW, 1 = ACTIVE_HIGH ) * - * @unit enum * @value 0 ACTIVE_LOW * @value 1 ACTIVE_HIGH * @min 0 @@ -82,7 +81,6 @@ PARAM_DEFINE_FLOAT(TRIG_ACT_TIME, 0.5f); * * 0 disables the trigger, 1 sets it to enabled on command, 2 always on, 3 distance based, 4 distance based enabled on command * - * @unit enum * @value 0 disable * @value 1 cmd * @value 2 always diff --git a/src/drivers/gimbal/gimbal_params.c b/src/drivers/gimbal/gimbal_params.c index 05bcbf5a7c..872f6678ec 100644 --- a/src/drivers/gimbal/gimbal_params.c +++ b/src/drivers/gimbal/gimbal_params.c @@ -63,7 +63,6 @@ PARAM_DEFINE_INT32(GMB_USE_MNT, 0); * Switch on means the gimbal can move freely, and landing gear * will be retracted if applicable. * - * @unit enum * @value 0 disable * @value 1 aux1 * @value 2 aux2 diff --git a/src/drivers/mkblctrl/mkblctrl_params.c b/src/drivers/mkblctrl/mkblctrl_params.c index c4de4e7100..0264efeb90 100644 --- a/src/drivers/mkblctrl/mkblctrl_params.c +++ b/src/drivers/mkblctrl/mkblctrl_params.c @@ -46,7 +46,6 @@ /** * Enables testmode (Identify) of MKBLCTRL Driver * - * @unit enum * @value 0 Disabled * @value 1 Enabled * @min 0 diff --git a/src/lib/runway_takeoff/runway_takeoff_params.c b/src/lib/runway_takeoff/runway_takeoff_params.c index ad5cecbb09..004bdb2b8a 100644 --- a/src/lib/runway_takeoff/runway_takeoff_params.c +++ b/src/lib/runway_takeoff/runway_takeoff_params.c @@ -54,7 +54,6 @@ PARAM_DEFINE_INT32(RWTO_TKOFF, 0); * * 0: airframe heading, 1: heading towards takeoff waypoint * - * @unit enum * @value 0 airframe * @value 1 waypoint * @min 0 diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_params.c b/src/modules/attitude_estimator_q/attitude_estimator_q_params.c index a7e16c56d7..87e8ec76e9 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_params.c +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_params.c @@ -107,7 +107,6 @@ PARAM_DEFINE_INT32(ATT_MAG_DECL_A, 1); * Set to 2 to use heading from motion capture. * * @group Attitude Q estimator - * @unit enum * @value 0 none * @value 1 vision * @value 2 motion capture diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index f153fc602e..9ca7e5b32d 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -316,7 +316,6 @@ PARAM_DEFINE_INT32(COM_AUTOS_PAR, 1); * of directly forwarding the manual input data. * * @group Commander - * @unit enum * @min 0 * @max 2 * @value 0 RC Transmitter @@ -347,7 +346,6 @@ PARAM_DEFINE_INT32(COM_DISARM_LAND, 0); * If the main switch channel is in this range the * selected flight mode will be applied. * - * @unit enum * @value -1 Unassigned * @value 0 Manual * @value 1 Altitude @@ -370,7 +368,6 @@ PARAM_DEFINE_INT32(COM_FLTMODE1, -1); * If the main switch channel is in this range the * selected flight mode will be applied. * - * @unit enum * @value -1 Unassigned * @value 0 Manual * @value 1 Altitude @@ -393,7 +390,6 @@ PARAM_DEFINE_INT32(COM_FLTMODE2, -1); * If the main switch channel is in this range the * selected flight mode will be applied. * - * @unit enum * @value -1 Unassigned * @value 0 Manual * @value 1 Altitude @@ -416,7 +412,6 @@ PARAM_DEFINE_INT32(COM_FLTMODE3, -1); * If the main switch channel is in this range the * selected flight mode will be applied. * - * @unit enum * @value -1 Unassigned * @value 0 Manual * @value 1 Altitude @@ -439,7 +434,6 @@ PARAM_DEFINE_INT32(COM_FLTMODE4, -1); * If the main switch channel is in this range the * selected flight mode will be applied. * - * @unit enum * @value -1 Unassigned * @value 0 Manual * @value 1 Altitude @@ -457,12 +451,11 @@ PARAM_DEFINE_INT32(COM_FLTMODE4, -1); PARAM_DEFINE_INT32(COM_FLTMODE5, -1); /** - * Sixt flightmode slot (1800-2000) + * Sixth flightmode slot (1800-2000) * * If the main switch channel is in this range the * selected flight mode will be applied. * - * @unit enum * @value -1 Unassigned * @value 0 Manual * @value 1 Altitude diff --git a/src/modules/ekf2/ekf2_params.c b/src/modules/ekf2/ekf2_params.c index 2014b527db..1ad33f8282 100644 --- a/src/modules/ekf2/ekf2_params.c +++ b/src/modules/ekf2/ekf2_params.c @@ -345,7 +345,6 @@ PARAM_DEFINE_INT32(EKF2_DECL_TYPE, 7); * If set to automatic: heading fusion on-ground and 3-axis fusion in-flight * * @group EKF2 - * @unit enum * @value 0 Automatic * @value 1 Magnetic heading * @value 2 3-axis fusion diff --git a/src/modules/fw_att_control/fw_att_control_params.c b/src/modules/fw_att_control/fw_att_control_params.c index d592a6c796..3d5ed72058 100644 --- a/src/modules/fw_att_control/fw_att_control_params.c +++ b/src/modules/fw_att_control/fw_att_control_params.c @@ -365,7 +365,6 @@ PARAM_DEFINE_FLOAT(FW_YCO_VMIN, 1000.0f); * 0: open-loop zero lateral acceleration based on kinematic constraints * 1: closed-loop: try to reduce lateral acceleration to 0 by measuring the acceleration * - * @unit enum * @min 0 * @max 1 * @value 0 open-loop diff --git a/src/modules/navigator/geofence_params.c b/src/modules/navigator/geofence_params.c index cd5fef55a6..243255ca6d 100644 --- a/src/modules/navigator/geofence_params.c +++ b/src/modules/navigator/geofence_params.c @@ -48,7 +48,6 @@ * * 0 = none, 1 = warning (default), 2 = loiter, 3 = return to launch, 4 = fight termination * - * @unit enum * @min 0 * @max 4 * @value 0 none @@ -66,7 +65,6 @@ PARAM_DEFINE_INT32(GF_ACTION, 1); * Select which altitude reference should be used * 0 = WGS84, 1 = AMSL * - * @unit enum * @min 0 * @max 1 * @value 0 WGS84 @@ -82,7 +80,6 @@ PARAM_DEFINE_INT32(GF_ALTMODE, 0); * no dependence on the position estimator * 0 = global position, 1 = GPS * - * @unit enum * @min 0 * @max 1 * @value 0 GPOS diff --git a/src/modules/navigator/mission_params.c b/src/modules/navigator/mission_params.c index 17febd73f2..03a8329f8b 100644 --- a/src/modules/navigator/mission_params.c +++ b/src/modules/navigator/mission_params.c @@ -99,7 +99,6 @@ PARAM_DEFINE_FLOAT(MIS_DIST_1WP, 900); * 1: the system will follow a first order hold altitude setpoint * values follow the definition in enum mission_altitude_mode * - * @unit enum * @min 0 * @max 1 * @value 0 Zero Order Hold @@ -113,7 +112,6 @@ PARAM_DEFINE_INT32(MIS_ALTMODE, 1); * * The values are defined in the enum mission_altitude_mode * - * @unit enum * @min 0 * @max 3 * @value 0 Heading as set by waypoint diff --git a/src/modules/sdlog2/params.c b/src/modules/sdlog2/params.c index c4f1fa473a..62d9424d65 100644 --- a/src/modules/sdlog2/params.c +++ b/src/modules/sdlog2/params.c @@ -56,7 +56,6 @@ PARAM_DEFINE_INT32(SDLOG_RATE, -1); * parameter is only read out before logging starts * (which commonly is before arming). * - * @unit enum * @min -1 * @max 1 * @value -1 command line diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index 544fe0915d..820e239827 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -329,7 +329,6 @@ PARAM_DEFINE_INT32(CAL_MAG1_ID, 0); * should only attempt to configure the rotation if the value is * greater than or equal to zero. * - * @unit enum * @value -1 Internal mag * @value 0 No rotation * @value 1 Yaw 45° @@ -536,7 +535,6 @@ PARAM_DEFINE_INT32(CAL_MAG2_ID, 0); * should only attempt to configure the rotation if the value is * greater than or equal to zero. * - * @unit enum * @value -1 Internal mag * @value 0 No rotation * @value 1 Yaw 45° @@ -735,7 +733,6 @@ PARAM_DEFINE_FLOAT(SENS_BARO_QNH, 1013.25f); * * This parameter defines the rotation of the FMU board relative to the platform. * - * @unit enum * @value 0 No rotation * @value 1 Yaw 45° * @value 2 Yaw 90° @@ -773,7 +770,6 @@ PARAM_DEFINE_INT32(SENS_BOARD_ROT, 0); * This parameter defines the rotation of the PX4FLOW board relative to the platform. * Zero rotation is defined as Y on flow board pointing towards front of vehicle * - * @unit enum * @value 0 No rotation * @value 1 Yaw 45° * @value 2 Yaw 90° @@ -825,7 +821,6 @@ PARAM_DEFINE_FLOAT(SENS_BOARD_Z_OFF, 0.0f); /** * External magnetometer rotation * - * @unit enum * @value 0 No rotation * @value 1 Yaw 45° * @value 2 Yaw 90° @@ -860,7 +855,6 @@ PARAM_DEFINE_INT32(SENS_EXT_MAG_ROT, 0); /** * Select primary magnetometer * - * @unit enum * @min 0 * @max 2 * @value 0 Auto-select Mag @@ -1921,7 +1915,6 @@ PARAM_DEFINE_FLOAT(RC18_DZ, 0.0f); /** * Enable relay control of relay 1 mapped to the Spektrum receiver power supply * - * @unit enum * @min 0 * @max 1 * @value 0 Disabled @@ -1933,7 +1926,6 @@ PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */ /** * DSM binding trigger. * - * @unit enum * @value -1 Inactive * @value 0 Start DSM2 bind * @value 1 Start DSMX bind @@ -2005,7 +1997,6 @@ PARAM_DEFINE_INT32(RC_TH_USER, 1); * which channel should be used for reading roll inputs from. * A value of zero indicates the switch is not assigned. * - * @unit enum * @min 0 * @max 18 * @value 0 Unassigned @@ -2038,7 +2029,6 @@ PARAM_DEFINE_INT32(RC_MAP_ROLL, 0); * which channel should be used for reading pitch inputs from. * A value of zero indicates the switch is not assigned. * - * @unit enum * @min 0 * @max 18 * @value 0 Unassigned @@ -2071,7 +2061,6 @@ PARAM_DEFINE_INT32(RC_MAP_PITCH, 0); * If 0, whichever channel is mapped to throttle is used * otherwise the value indicates the specific rc channel to use * - * @unit enum * @min 0 * @max 18 * @value 0 Unassigned @@ -2103,7 +2092,6 @@ PARAM_DEFINE_INT32(RC_MAP_FAILSAFE, 0); //Default to throttle function * which channel should be used for reading throttle inputs from. * A value of zero indicates the switch is not assigned. * - * @unit enum * @min 0 * @max 18 * @value 0 Unassigned @@ -2136,7 +2124,6 @@ PARAM_DEFINE_INT32(RC_MAP_THROTTLE, 0); * which channel should be used for reading yaw inputs from. * A value of zero indicates the switch is not assigned. * - * @unit enum * @min 0 * @max 18 * @value 0 Unassigned @@ -2168,7 +2155,6 @@ PARAM_DEFINE_INT32(RC_MAP_YAW, 0); * If this parameter is non-zero, flight modes are only selected * by this channel and are assigned to six slots. * - * @unit enum * @min 0 * @max 18 * @group Radio Switches @@ -2202,7 +2188,6 @@ PARAM_DEFINE_INT32(RC_MAP_FLTMODE, 0); * which channel should be used for deciding about the main mode. * A value of zero indicates the switch is not assigned. * - * @unit enum * @min 0 * @max 18 * @group Radio Switches @@ -2231,7 +2216,6 @@ PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0); /** * Return switch channel * - * @unit enum * @min 0 * @max 18 * @group Radio Switches @@ -2260,7 +2244,6 @@ PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0); /** * Rattitude switch channel * - * @unit enum * @min 0 * @max 18 * @group Radio Switches @@ -2289,7 +2272,6 @@ PARAM_DEFINE_INT32(RC_MAP_RATT_SW, 0); /** * Position Control switch channel * - * @unit enum * @min 0 * @max 18 * @group Radio Switches @@ -2318,7 +2300,6 @@ PARAM_DEFINE_INT32(RC_MAP_POSCTL_SW, 0); /** * Loiter switch channel * - * @unit enum * @min 0 * @max 18 * @group Radio Switches @@ -2347,7 +2328,6 @@ PARAM_DEFINE_INT32(RC_MAP_LOITER_SW, 0); /** * Acro switch channel * - * @unit enum * @min 0 * @max 18 * @group Radio Switches @@ -2376,7 +2356,6 @@ PARAM_DEFINE_INT32(RC_MAP_ACRO_SW, 0); /** * Offboard switch channel * - * @unit enum * @min 0 * @max 18 * @group Radio Switches @@ -2405,7 +2384,6 @@ PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0); /** * Kill switch channel * - * @unit enum * @min 0 * @max 18 * @group Radio Switches @@ -2434,7 +2412,6 @@ PARAM_DEFINE_INT32(RC_MAP_KILL_SW, 0); /** * Flaps channel * - * @unit enum * @min 0 * @max 18 * @group Radio Switches @@ -2465,7 +2442,6 @@ PARAM_DEFINE_INT32(RC_MAP_FLAPS, 0); * * Default function: Camera pitch * - * @unit enum * @min 0 * @max 18 * @group Radio Calibration @@ -2496,7 +2472,6 @@ PARAM_DEFINE_INT32(RC_MAP_AUX1, 0); * * Default function: Camera roll * - * @unit enum * @min 0 * @max 18 * @group Radio Calibration @@ -2527,7 +2502,6 @@ PARAM_DEFINE_INT32(RC_MAP_AUX2, 0); * * Default function: Camera azimuth / yaw * - * @unit enum * @min 0 * @max 18 * @group Radio Calibration @@ -2559,7 +2533,6 @@ PARAM_DEFINE_INT32(RC_MAP_AUX3, 0); * Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel. * Set to 0 to deactivate * * - * @unit enum * @min 0 * @max 18 * @group Radio Calibration @@ -2591,7 +2564,6 @@ PARAM_DEFINE_INT32(RC_MAP_PARAM1, 0); * Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel. * Set to 0 to deactivate * * - * @unit enum * @min 0 * @max 18 * @group Radio Calibration @@ -2623,7 +2595,6 @@ PARAM_DEFINE_INT32(RC_MAP_PARAM2, 0); * Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel. * Set to 0 to deactivate * * - * @unit enum * @min 0 * @max 18 * @group Radio Calibration @@ -2832,7 +2803,6 @@ PARAM_DEFINE_FLOAT(RC_KILLSWITCH_TH, 0.25f); * * Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters. * - * @unit enum * @min 0 * @max 18 * @value 0 Unassigned diff --git a/src/modules/systemlib/system_params.c b/src/modules/systemlib/system_params.c index d6c2ada653..a77feff43f 100644 --- a/src/modules/systemlib/system_params.c +++ b/src/modules/systemlib/system_params.c @@ -90,7 +90,6 @@ PARAM_DEFINE_INT32(SYS_RESTART_TYPE, 2); * 921600: enables onboard mode at 921600 baud, 8N1. 57600: enables onboard mode at 57600 baud, 8N1. * 157600: enables OSD mode at 57600 baud, 8N1. * - * @unit enum * @value 921600 Companion Link (921600 baud, 8N1) * @value 57600 Companion Link (57600 baud, 8N1) * @value 157600 OSD (57600 baud, 8N1) diff --git a/src/modules/uavcan/uavcan_params.c b/src/modules/uavcan/uavcan_params.c index f58a5f0d87..f91dbd762e 100644 --- a/src/modules/uavcan/uavcan_params.c +++ b/src/modules/uavcan/uavcan_params.c @@ -47,7 +47,6 @@ * 2 - Enabled support for dynamic node ID allocation and firmware update. * 3 - Sets the motor control outputs to UAVCAN and enables support for dynamic node ID allocation and firmware update. * - * @unit enum * @min 0 * @max 3 * @value 0 disabled diff --git a/src/modules/vtol_att_control/vtol_att_control_params.c b/src/modules/vtol_att_control/vtol_att_control_params.c index e55af6bd22..3f8022ba58 100644 --- a/src/modules/vtol_att_control/vtol_att_control_params.c +++ b/src/modules/vtol_att_control/vtol_att_control_params.c @@ -172,7 +172,6 @@ PARAM_DEFINE_FLOAT(VT_ARSP_LP_GAIN, 0.3f); /** * VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2) * - * @unit enum * @value 0 Tailsitter * @value 1 Tiltrotor * @value 2 Standard From 26bb2fd22f9f8ee52b7dcaefb8892c229a889f58 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 25 Mar 2016 20:38:08 -0400 Subject: [PATCH 7/8] capitalize param values --- src/drivers/camera_trigger/camera_trigger_params.c | 8 ++++---- src/drivers/gimbal/gimbal_params.c | 8 ++++---- src/lib/runway_takeoff/runway_takeoff_params.c | 4 ++-- .../attitude_estimator_q/attitude_estimator_q_params.c | 6 +++--- src/modules/commander/commander_params.c | 2 +- src/modules/navigator/geofence_params.c | 10 +++++----- src/modules/sdlog2/params.c | 6 +++--- src/modules/uavcan/uavcan_params.c | 8 ++++---- 8 files changed, 26 insertions(+), 26 deletions(-) diff --git a/src/drivers/camera_trigger/camera_trigger_params.c b/src/drivers/camera_trigger/camera_trigger_params.c index 9459841a36..a68303e494 100644 --- a/src/drivers/camera_trigger/camera_trigger_params.c +++ b/src/drivers/camera_trigger/camera_trigger_params.c @@ -81,10 +81,10 @@ PARAM_DEFINE_FLOAT(TRIG_ACT_TIME, 0.5f); * * 0 disables the trigger, 1 sets it to enabled on command, 2 always on, 3 distance based, 4 distance based enabled on command * - * @value 0 disable - * @value 1 cmd - * @value 2 always - * @value 3 distance + * @value 0 Disable + * @value 1 CMD + * @value 2 Always + * @value 3 Distance * @min 0 * @max 4 * @group Camera trigger diff --git a/src/drivers/gimbal/gimbal_params.c b/src/drivers/gimbal/gimbal_params.c index 872f6678ec..6b19814f61 100644 --- a/src/drivers/gimbal/gimbal_params.c +++ b/src/drivers/gimbal/gimbal_params.c @@ -63,10 +63,10 @@ PARAM_DEFINE_INT32(GMB_USE_MNT, 0); * Switch on means the gimbal can move freely, and landing gear * will be retracted if applicable. * - * @value 0 disable - * @value 1 aux1 - * @value 2 aux2 - * @value 3 aux3 + * @value 0 Disable + * @value 1 AUX1 + * @value 2 AUX2 + * @value 3 AUX3 * @min 0 * @max 3 * @group Gimbal diff --git a/src/lib/runway_takeoff/runway_takeoff_params.c b/src/lib/runway_takeoff/runway_takeoff_params.c index 004bdb2b8a..aed95e99eb 100644 --- a/src/lib/runway_takeoff/runway_takeoff_params.c +++ b/src/lib/runway_takeoff/runway_takeoff_params.c @@ -54,8 +54,8 @@ PARAM_DEFINE_INT32(RWTO_TKOFF, 0); * * 0: airframe heading, 1: heading towards takeoff waypoint * - * @value 0 airframe - * @value 1 waypoint + * @value 0 Airframe + * @value 1 Waypoint * @min 0 * @max 1 * @group Runway Takeoff diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_params.c b/src/modules/attitude_estimator_q/attitude_estimator_q_params.c index 87e8ec76e9..e2babfee43 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_params.c +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_params.c @@ -107,9 +107,9 @@ PARAM_DEFINE_INT32(ATT_MAG_DECL_A, 1); * Set to 2 to use heading from motion capture. * * @group Attitude Q estimator - * @value 0 none - * @value 1 vision - * @value 2 motion capture + * @value 0 None + * @value 1 Vision + * @value 2 Motion Capture * @min 0 * @max 2 */ diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 9ca7e5b32d..6a4d409103 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -137,7 +137,7 @@ PARAM_DEFINE_FLOAT(BAT_V_LOAD_DROP, 0.07f); * Defines the number of cells the attached battery consists of. * * @group Battery Calibration - * @unit cells + * @unit S * @min 2 * @max 10 * @value 2 2S Battery diff --git a/src/modules/navigator/geofence_params.c b/src/modules/navigator/geofence_params.c index 243255ca6d..7dbe4329a4 100644 --- a/src/modules/navigator/geofence_params.c +++ b/src/modules/navigator/geofence_params.c @@ -50,11 +50,11 @@ * * @min 0 * @max 4 - * @value 0 none - * @value 1 warning - * @value 2 loiter - * @value 3 return - * @value 4 terminate + * @value 0 None + * @value 1 Warning + * @value 2 Loiter + * @value 3 Return + * @value 4 Terminate * @group Geofence */ PARAM_DEFINE_INT32(GF_ACTION, 1); diff --git a/src/modules/sdlog2/params.c b/src/modules/sdlog2/params.c index 62d9424d65..db96d564ac 100644 --- a/src/modules/sdlog2/params.c +++ b/src/modules/sdlog2/params.c @@ -58,9 +58,9 @@ PARAM_DEFINE_INT32(SDLOG_RATE, -1); * * @min -1 * @max 1 - * @value -1 command line - * @value 0 disable - * @value 1 enable + * @value -1 Command Line + * @value 0 Disable + * @value 1 Enable * @group SD Logging */ PARAM_DEFINE_INT32(SDLOG_EXT, -1); diff --git a/src/modules/uavcan/uavcan_params.c b/src/modules/uavcan/uavcan_params.c index f91dbd762e..e269202d99 100644 --- a/src/modules/uavcan/uavcan_params.c +++ b/src/modules/uavcan/uavcan_params.c @@ -49,10 +49,10 @@ * * @min 0 * @max 3 - * @value 0 disabled - * @value 1 enabled - * @value 2 update - * @value 3 motors/update + * @value 0 Disabled + * @value 1 Enabled + * @value 2 Dynamic ID/Update + * @value 3 Motors/Update * @group UAVCAN */ PARAM_DEFINE_INT32(UAVCAN_ENABLE, 0); From ff75b8bb8f0511feddfd8a921940421ec7630af5 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 25 Mar 2016 20:47:56 -0400 Subject: [PATCH 8/8] allow boolean tag --- Tools/px4params/srcparser.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/px4params/srcparser.py b/Tools/px4params/srcparser.py index 9889357004..438bc9eb2d 100644 --- a/Tools/px4params/srcparser.py +++ b/Tools/px4params/srcparser.py @@ -133,7 +133,7 @@ class SourceParser(object): re_remove_dots = re.compile(r'\.+$') re_remove_carriage_return = re.compile('\n+') - valid_tags = set(["group", "board", "min", "max", "unit", "decimal", "increment", "reboot_required", "value"]) + valid_tags = set(["group", "board", "min", "max", "unit", "decimal", "increment", "reboot_required", "value", "boolean"]) # Order of parameter groups priority = {