params correct boolean tag

This commit is contained in:
Daniel Agar 2016-03-25 20:25:17 -04:00
parent ff9b8118ab
commit 70a68def83
19 changed files with 44 additions and 44 deletions

View File

@ -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);

View File

@ -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);

View File

@ -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);

View File

@ -47,7 +47,7 @@
/**
* Enable launch detection.
*
* @unit boolean
* @boolean
* @min 0
* @max 1
* @group Launch detection

View File

@ -44,7 +44,7 @@
*
* 0: disabled, 1: enabled
*
* @unit boolean
* @boolean
* @group Runway Takeoff
*/
PARAM_DEFINE_INT32(RWTO_TKOFF, 0);

View File

@ -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);

View File

@ -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);

View File

@ -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);

View File

@ -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);

View File

@ -47,7 +47,7 @@
*
* Set to 1 to enable mTECS
*
* @unit boolean
* @boolean
* @group mTECS
*/
PARAM_DEFINE_INT32(MT_ENABLED, 0);

View File

@ -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);

View File

@ -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);

View File

@ -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);

View File

@ -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);

View File

@ -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);

View File

@ -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);

View File

@ -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);

View File

@ -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);

View File

@ -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);