Browse Source

params correct boolean tag

sbg
Daniel Agar 9 years ago
parent
commit
70a68def83
  1. 2
      src/drivers/gimbal/gimbal_params.c
  2. 12
      src/drivers/px4fmu/px4fmu_params.c
  3. 18
      src/drivers/px4io/px4io_params.c
  4. 2
      src/lib/launchdetection/launchdetection_params.c
  5. 2
      src/lib/runway_takeoff/runway_takeoff_params.c
  6. 4
      src/modules/attitude_estimator_q/attitude_estimator_q_params.c
  7. 4
      src/modules/commander/commander_params.c
  8. 2
      src/modules/ekf2/ekf2_params.c
  9. 2
      src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
  10. 2
      src/modules/fw_pos_control_l1/mtecs/mTecs_params.c
  11. 4
      src/modules/local_position_estimator/params.c
  12. 4
      src/modules/mavlink/mavlink_params.c
  13. 2
      src/modules/navigator/datalinkloss_params.c
  14. 2
      src/modules/navigator/mission_params.c
  15. 4
      src/modules/navigator/navigator_params.c
  16. 6
      src/modules/position_estimator_inav/position_estimator_inav_params.cpp
  17. 2
      src/modules/sdlog2/params.c
  18. 4
      src/modules/sensors/sensor_params.c
  19. 10
      src/modules/vtol_att_control/vtol_att_control_params.c

2
src/drivers/gimbal/gimbal_params.c

@ -48,7 +48,7 @@
* *
* If set to 1, mount mode will be enforced. * If set to 1, mount mode will be enforced.
* *
* @unit boolean * @boolean
* @group Gimbal * @group Gimbal
*/ */
PARAM_DEFINE_INT32(GMB_USE_MNT, 0); PARAM_DEFINE_INT32(GMB_USE_MNT, 0);

12
src/drivers/px4fmu/px4fmu_params.c

@ -48,7 +48,7 @@
* Set to 1 to invert the channel, 0 for default direction. * Set to 1 to invert the channel, 0 for default direction.
* *
* @reboot_required true * @reboot_required true
* @unit boolean * @boolean
* @group PWM Outputs * @group PWM Outputs
*/ */
PARAM_DEFINE_INT32(PWM_AUX_REV1, 0); 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. * Set to 1 to invert the channel, 0 for default direction.
* *
* @reboot_required true * @reboot_required true
* @unit boolean * @boolean
* @group PWM Outputs * @group PWM Outputs
*/ */
PARAM_DEFINE_INT32(PWM_AUX_REV2, 0); 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. * Set to 1 to invert the channel, 0 for default direction.
* *
* @reboot_required true * @reboot_required true
* @unit boolean * @boolean
* @group PWM Outputs * @group PWM Outputs
*/ */
PARAM_DEFINE_INT32(PWM_AUX_REV3, 0); 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. * Set to 1 to invert the channel, 0 for default direction.
* *
* @reboot_required true * @reboot_required true
* @unit boolean * @boolean
* @group PWM Outputs * @group PWM Outputs
*/ */
PARAM_DEFINE_INT32(PWM_AUX_REV4, 0); 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. * Set to 1 to invert the channel, 0 for default direction.
* *
* @reboot_required true * @reboot_required true
* @unit boolean * @boolean
* @group PWM Outputs * @group PWM Outputs
*/ */
PARAM_DEFINE_INT32(PWM_AUX_REV5, 0); 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. * Set to 1 to invert the channel, 0 for default direction.
* *
* @reboot_required true * @reboot_required true
* @unit boolean * @boolean
* @group PWM Outputs * @group PWM Outputs
*/ */
PARAM_DEFINE_INT32(PWM_AUX_REV6, 0); PARAM_DEFINE_INT32(PWM_AUX_REV6, 0);

18
src/drivers/px4io/px4io_params.c

@ -48,7 +48,7 @@
* Set to 1 to invert the channel, 0 for default direction. * Set to 1 to invert the channel, 0 for default direction.
* *
* @reboot_required true * @reboot_required true
* @unit boolean * @boolean
* @group PWM Outputs * @group PWM Outputs
*/ */
PARAM_DEFINE_INT32(PWM_MAIN_REV1, 0); 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. * Set to 1 to invert the channel, 0 for default direction.
* *
* @reboot_required true * @reboot_required true
* @unit boolean * @boolean
* @group PWM Outputs * @group PWM Outputs
*/ */
PARAM_DEFINE_INT32(PWM_MAIN_REV2, 0); 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. * Set to 1 to invert the channel, 0 for default direction.
* *
* @reboot_required true * @reboot_required true
* @unit boolean * @boolean
* @group PWM Outputs * @group PWM Outputs
*/ */
PARAM_DEFINE_INT32(PWM_MAIN_REV3, 0); 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. * Set to 1 to invert the channel, 0 for default direction.
* *
* @reboot_required true * @reboot_required true
* @unit boolean * @boolean
* @group PWM Outputs * @group PWM Outputs
*/ */
PARAM_DEFINE_INT32(PWM_MAIN_REV4, 0); 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. * Set to 1 to invert the channel, 0 for default direction.
* *
* @reboot_required true * @reboot_required true
* @unit boolean * @boolean
* @group PWM Outputs * @group PWM Outputs
*/ */
PARAM_DEFINE_INT32(PWM_MAIN_REV5, 0); 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. * Set to 1 to invert the channel, 0 for default direction.
* *
* @reboot_required true * @reboot_required true
* @unit boolean * @boolean
* @group PWM Outputs * @group PWM Outputs
*/ */
PARAM_DEFINE_INT32(PWM_MAIN_REV6, 0); 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. * Set to 1 to invert the channel, 0 for default direction.
* *
* @reboot_required true * @reboot_required true
* @unit boolean * @boolean
* @group PWM Outputs * @group PWM Outputs
*/ */
PARAM_DEFINE_INT32(PWM_MAIN_REV7, 0); 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. * Set to 1 to invert the channel, 0 for default direction.
* *
* @reboot_required true * @reboot_required true
* @unit boolean * @boolean
* @group PWM Outputs * @group PWM Outputs
*/ */
PARAM_DEFINE_INT32(PWM_MAIN_REV8, 0); 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. * Set to 1 to enable S.BUS version 1 output instead of RSSI.
* *
* @unit boolean * @boolean
* @group PWM Outputs * @group PWM Outputs
*/ */
PARAM_DEFINE_INT32(PWM_SBUS_MODE, 0); PARAM_DEFINE_INT32(PWM_SBUS_MODE, 0);

2
src/lib/launchdetection/launchdetection_params.c

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

2
src/lib/runway_takeoff/runway_takeoff_params.c

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

4
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 * Enable automatic GPS based declination compensation
* *
* @group Attitude Q estimator * @group Attitude Q estimator
* @unit boolean * @boolean
*/ */
PARAM_DEFINE_INT32(ATT_MAG_DECL_A, 1); PARAM_DEFINE_INT32(ATT_MAG_DECL_A, 1);
@ -121,7 +121,7 @@ PARAM_DEFINE_INT32(ATT_EXT_HDG_M, 0);
* velocity. * velocity.
* *
* @group Attitude Q estimator * @group Attitude Q estimator
* @unit boolean * @boolean
*/ */
PARAM_DEFINE_INT32(ATT_ACC_COMP, 1); PARAM_DEFINE_INT32(ATT_ACC_COMP, 1);

4
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. * Set to 1 to enable actions triggered when the datalink is lost.
* *
* @group Commander * @group Commander
* @unit boolean * @boolean
*/ */
PARAM_DEFINE_INT32(COM_DL_LOSS_EN, 0); 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. * being sticky. Developers can default it to off.
* *
* @group Commander * @group Commander
* @unit boolean * @boolean
*/ */
PARAM_DEFINE_INT32(COM_AUTOS_PAR, 1); PARAM_DEFINE_INT32(COM_AUTOS_PAR, 1);

2
src/modules/ekf2/ekf2_params.c

@ -387,7 +387,7 @@ PARAM_DEFINE_FLOAT(EKF2_GPS_V_GATE, 3.0f);
* replay messages for logging. * replay messages for logging.
* *
* @group EKF2 * @group EKF2
* @unit boolean * @boolean
*/ */
PARAM_DEFINE_INT32(EKF2_REC_RPL, 0); PARAM_DEFINE_INT32(EKF2_REC_RPL, 0);

2
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 * 0: disabled, 1: enabled
* *
* @unit boolean * @boolean
* @group FW L1 Control * @group FW L1 Control
*/ */
PARAM_DEFINE_INT32(FW_LND_USETER, 0); PARAM_DEFINE_INT32(FW_LND_USETER, 0);

2
src/modules/fw_pos_control_l1/mtecs/mTecs_params.c

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

4
src/modules/local_position_estimator/params.c

@ -6,7 +6,7 @@
/** /**
* Enable local position estimator. * Enable local position estimator.
* *
* @unit boolean * @boolean
* @group Local Position Estimator * @group Local Position Estimator
*/ */
PARAM_DEFINE_INT32(LPE_ENABLED, 1); PARAM_DEFINE_INT32(LPE_ENABLED, 1);
@ -14,7 +14,7 @@ PARAM_DEFINE_INT32(LPE_ENABLED, 1);
/** /**
* Enable accelerometer integration for prediction. * Enable accelerometer integration for prediction.
* *
* @unit boolean * @boolean
* @group Local Position Estimator * @group Local Position Estimator
*/ */
PARAM_DEFINE_INT32(LPE_INTEGRATE, 1); PARAM_DEFINE_INT32(LPE_INTEGRATE, 1);

4
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. * If set to 1 incoming HIL GPS messages are parsed.
* *
* @unit boolean * @boolean
* @group MAVLink * @group MAVLink
*/ */
PARAM_DEFINE_INT32(MAV_USEHILGPS, 0); 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 * If set to 1 incoming external setpoint messages will be directly forwarded
* to the controllers if in offboard control mode * to the controllers if in offboard control mode
* *
* @unit boolean * @boolean
* @group MAVLink * @group MAVLink
*/ */
PARAM_DEFINE_INT32(MAV_FWDEXTSP, 1); PARAM_DEFINE_INT32(MAV_FWDEXTSP, 1);

2
src/modules/navigator/datalinkloss_params.c

@ -119,6 +119,6 @@ PARAM_DEFINE_INT32(NAV_DLL_N, 2);
* airfield home * airfield home
* *
* @group Data Link Loss * @group Data Link Loss
* @unit boolean * @boolean
*/ */
PARAM_DEFINE_INT32(NAV_DLL_CHSK, 0); PARAM_DEFINE_INT32(NAV_DLL_CHSK, 0);

2
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 * When enabled, missions that have been uploaded by the GCS are stored
* and reloaded after reboot persistently. * and reloaded after reboot persistently.
* *
* @unit boolean * @boolean
* @group Mission * @group Mission
*/ */
PARAM_DEFINE_INT32(MIS_ONBOARD_EN, 1); PARAM_DEFINE_INT32(MIS_ONBOARD_EN, 1);

4
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 * 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 * @group Mission
*/ */
PARAM_DEFINE_INT32(NAV_DLL_OBC, 0); 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 * 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 * @group Mission
*/ */
PARAM_DEFINE_INT32(NAV_RCL_OBC, 0); PARAM_DEFINE_INT32(NAV_RCL_OBC, 0);

6
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 * Disable mocap
* *
* @unit boolean * @boolean
* @group Position Estimator INAV * @group Position Estimator INAV
*/ */
PARAM_DEFINE_FLOAT(INAV_DISAB_MOCAP, 0); PARAM_DEFINE_FLOAT(INAV_DISAB_MOCAP, 0);
@ -316,7 +316,7 @@ PARAM_DEFINE_FLOAT(INAV_DISAB_MOCAP, 0);
* *
* Enable LIDAR for altitude estimation * Enable LIDAR for altitude estimation
* *
* @unit boolean * @boolean
* @group Position Estimator INAV * @group Position Estimator INAV
*/ */
PARAM_DEFINE_FLOAT(INAV_LIDAR_EST, 0); 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 * Else the system uses the combined attitude / position
* filter framework. * filter framework.
* *
* @unit boolean * @boolean
* @group Position Estimator INAV * @group Position Estimator INAV
*/ */
PARAM_DEFINE_INT32(INAV_ENABLED, 1); PARAM_DEFINE_INT32(INAV_ENABLED, 1);

2
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 * to only use the time stamp if a 3D GPS lock is
* present. * present.
* *
* @unit boolean * @boolean
* @group SD Logging * @group SD Logging
*/ */
PARAM_DEFINE_INT32(SDLOG_GPSTIME, 1); PARAM_DEFINE_INT32(SDLOG_GPSTIME, 1);

4
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 * indicates that the threshold value where automatically set by the ground
* station software. It is only meant for ground station use. * station software. It is only meant for ground station use.
* *
* @unit boolean * @boolean
* @group Radio Calibration * @group Radio Calibration
*/ */
@ -2888,7 +2888,7 @@ PARAM_DEFINE_INT32(RC_RSSI_PWM_MIN, 2000);
* *
* @reboot_required true * @reboot_required true
* *
* @unit boolean * @boolean
* @group Sensor Enable * @group Sensor Enable
*/ */
PARAM_DEFINE_INT32(SENS_EN_LL40LS, 0); PARAM_DEFINE_INT32(SENS_EN_LL40LS, 0);

10
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. * If set to one this parameter will cause permanent attitude stabilization in fw mode.
* This parameter has been introduced for pure convenience sake. * This parameter has been introduced for pure convenience sake.
* *
* @unit boolean * @boolean
* @group VTOL Attitude Control * @group VTOL Attitude Control
*/ */
PARAM_DEFINE_INT32(VT_FW_PERM_STAB, 0); 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 * If set to 1 the elevons are locked in multicopter mode
* *
* @unit boolean * @boolean
* @group VTOL Attitude Control * @group VTOL Attitude Control
*/ */
PARAM_DEFINE_INT32(VT_ELEV_MC_LOCK, 0); 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 * Enable optimal recovery strategy for pitch-weak tailsitters
* *
* @unit boolean * @boolean
* @group VTOL Attitude Control * @group VTOL Attitude Control
*/ */
PARAM_DEFINE_INT32(VT_OPT_RECOV_EN, 0); 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 * Enable weather-vane mode landings for missions
* *
* @unit boolean * @boolean
* @group VTOL Attitude Control * @group VTOL Attitude Control
*/ */
PARAM_DEFINE_INT32(VT_WV_LND_EN, 0); 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 * Enable weather-vane mode for loiter
* *
* @unit boolean * @boolean
* @group VTOL Attitude Control * @group VTOL Attitude Control
*/ */
PARAM_DEFINE_INT32(VT_WV_LTR_EN, 0); PARAM_DEFINE_INT32(VT_WV_LTR_EN, 0);

Loading…
Cancel
Save