mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-10 06:39:25 +08:00
params: ensure short description is only a single line
So a UI can display it properly
This commit is contained in:
@@ -33,7 +33,8 @@
|
||||
|
||||
/**
|
||||
* PCF8583 rotorfreq (i2c) pool interval
|
||||
* How often the sensor is readout.
|
||||
*
|
||||
* Determines how often the sensor is read out.
|
||||
*
|
||||
* @reboot_required true
|
||||
* @group Sensors
|
||||
|
||||
@@ -20,7 +20,8 @@ PARAM_DEFINE_INT32(ISBD_READ_INT, 0);
|
||||
PARAM_DEFINE_INT32(ISBD_SBD_TIMEOUT, 60);
|
||||
|
||||
/**
|
||||
* Time [ms] the Iridium driver will wait for additional mavlink messages to combine them into one SBD message
|
||||
* Time the Iridium driver will wait for additional mavlink messages to combine them into one SBD message
|
||||
*
|
||||
* Value 0 turns the functionality off
|
||||
*
|
||||
* @unit ms
|
||||
|
||||
@@ -305,6 +305,8 @@ class SourceParser(object):
|
||||
group = "Miscellaneous"
|
||||
if state == "comment-processed":
|
||||
if short_desc is not None:
|
||||
if '\n' in short_desc:
|
||||
raise Exception('short description must be a single line (parameter: {:})'.format(name))
|
||||
param.SetField("short_desc", self.re_remove_dots.sub('', short_desc))
|
||||
if long_desc is not None:
|
||||
long_desc = self.re_remove_carriage_return.sub(' ', long_desc)
|
||||
|
||||
@@ -103,6 +103,7 @@ PARAM_DEFINE_INT32(ATT_MAG_DECL_A, 1);
|
||||
|
||||
/**
|
||||
* External heading usage mode (from Motion capture/Vision)
|
||||
*
|
||||
* Set to 1 to use heading estimate from vision.
|
||||
* Set to 2 to use heading from motion capture.
|
||||
*
|
||||
@@ -116,8 +117,7 @@ PARAM_DEFINE_INT32(ATT_MAG_DECL_A, 1);
|
||||
PARAM_DEFINE_INT32(ATT_EXT_HDG_M, 0);
|
||||
|
||||
/**
|
||||
* Acceleration compensation based on GPS
|
||||
* velocity.
|
||||
* Acceleration compensation based on GPS velocity.
|
||||
*
|
||||
* @group Attitude Q estimator
|
||||
* @boolean
|
||||
|
||||
@@ -341,6 +341,7 @@ PARAM_DEFINE_INT32(COM_LOW_BAT_ACT, 0);
|
||||
|
||||
/**
|
||||
* Time-out to wait when offboard connection is lost before triggering offboard lost action.
|
||||
*
|
||||
* See COM_OBL_ACT and COM_OBL_RC_ACT to configure action.
|
||||
*
|
||||
* @group Commander
|
||||
@@ -595,6 +596,7 @@ PARAM_DEFINE_FLOAT(COM_ARM_IMU_GYR, 0.25f);
|
||||
|
||||
/**
|
||||
* Maximum magnetic field inconsistency between units that will allow arming
|
||||
*
|
||||
* Set -1 to disable the check.
|
||||
*
|
||||
* @group Commander
|
||||
|
||||
@@ -107,9 +107,9 @@ PARAM_DEFINE_FLOAT(FD_FAIL_R_TTRI, 0.3);
|
||||
PARAM_DEFINE_FLOAT(FD_FAIL_P_TTRI, 0.3);
|
||||
|
||||
/**
|
||||
* Enable PWM input on AUX5 or MAIN5 (depending on board) for engaging failsafe from an external
|
||||
* automatic trigger system (ATS).
|
||||
* Enable PWM input on for engaging failsafe from an external automatic trigger system (ATS).
|
||||
*
|
||||
* Enabled on either AUX5 or MAIN5 depending on board.
|
||||
* External ATS is required by ASTM F3322-18.
|
||||
*
|
||||
* @boolean
|
||||
@@ -132,6 +132,7 @@ PARAM_DEFINE_INT32(FD_EXT_ATS_TRIG, 1900);
|
||||
|
||||
/**
|
||||
* Enable checks on ESCs that report their arming state.
|
||||
*
|
||||
* If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state.
|
||||
* Timeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle.
|
||||
*
|
||||
|
||||
@@ -41,6 +41,7 @@
|
||||
|
||||
/**
|
||||
* Minimum time of arrival delta between non-IMU observations before data is downsampled.
|
||||
*
|
||||
* Baro and Magnetometer data will be averaged before downsampling, other data will be point sampled resulting in loss of information.
|
||||
*
|
||||
* @group EKF2
|
||||
@@ -89,6 +90,7 @@ PARAM_DEFINE_FLOAT(EKF2_GPS_DELAY, 110);
|
||||
|
||||
/**
|
||||
* Optical flow measurement delay relative to IMU measurements
|
||||
*
|
||||
* Assumes measurement is timestamped at trailing edge of integration period
|
||||
*
|
||||
* @group EKF2
|
||||
@@ -493,6 +495,7 @@ PARAM_DEFINE_INT32(EKF2_MAG_TYPE, 0);
|
||||
|
||||
/**
|
||||
* Horizontal acceleration threshold used by automatic selection of magnetometer fusion method.
|
||||
*
|
||||
* This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered horizontal acceleration is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion.
|
||||
*
|
||||
* @group EKF2
|
||||
@@ -505,6 +508,7 @@ PARAM_DEFINE_FLOAT(EKF2_MAG_ACCLIM, 0.5f);
|
||||
|
||||
/**
|
||||
* Yaw rate threshold used by automatic selection of magnetometer fusion method.
|
||||
*
|
||||
* This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered yaw rate is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion.
|
||||
*
|
||||
* @group EKF2
|
||||
@@ -945,7 +949,9 @@ PARAM_DEFINE_FLOAT(EKF2_EV_POS_Y, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(EKF2_EV_POS_Z, 0.0f);
|
||||
|
||||
/**
|
||||
* Airspeed fusion threshold. A value of zero will deactivate airspeed fusion. Any other positive
|
||||
* Airspeed fusion threshold.
|
||||
*
|
||||
* A value of zero will deactivate airspeed fusion. Any other positive
|
||||
* value will determine the minimum airspeed which will still be fused. Set to about 90% of the vehicles stall speed.
|
||||
* Both airspeed fusion and sideslip fusion must be active for the EKF to continue navigating after loss of GPS.
|
||||
* Use EKF2_FUSE_BETA to activate sideslip fusion.
|
||||
@@ -1122,6 +1128,7 @@ PARAM_DEFINE_FLOAT(EKF2_EVV_GATE, 3.0f);
|
||||
|
||||
/**
|
||||
* Gate size for vision position fusion
|
||||
*
|
||||
* Sets the number of standard deviations used by the innovation consistency test.
|
||||
* @group EKF2
|
||||
* @min 1.0
|
||||
@@ -1132,7 +1139,8 @@ PARAM_DEFINE_FLOAT(EKF2_EVP_GATE, 5.0f);
|
||||
|
||||
/**
|
||||
* Specific drag force observation noise variance used by the multi-rotor specific drag force model.
|
||||
* Increasing it makes the multi-rotor wind estimates adjust more slowly.
|
||||
*
|
||||
* Increasing this makes the multi-rotor wind estimates adjust more slowly.
|
||||
*
|
||||
* @group EKF2
|
||||
* @min 0.5
|
||||
@@ -1144,6 +1152,7 @@ PARAM_DEFINE_FLOAT(EKF2_DRAG_NOISE, 2.5f);
|
||||
|
||||
/**
|
||||
* X-axis ballistic coefficient used by the multi-rotor specific drag force model.
|
||||
*
|
||||
* This should be adjusted to minimise variance of the X-axis drag specific force innovation sequence.
|
||||
*
|
||||
* @group EKF2
|
||||
@@ -1156,6 +1165,7 @@ PARAM_DEFINE_FLOAT(EKF2_BCOEF_X, 25.0f);
|
||||
|
||||
/**
|
||||
* Y-axis ballistic coefficient used by the multi-rotor specific drag force model.
|
||||
*
|
||||
* This should be adjusted to minimise variance of the Y-axis drag specific force innovation sequence.
|
||||
*
|
||||
* @group EKF2
|
||||
@@ -1179,6 +1189,7 @@ PARAM_DEFINE_FLOAT(EKF2_ASPD_MAX, 20.0f);
|
||||
|
||||
/**
|
||||
* Static pressure position error coefficient for the positive X axis
|
||||
*
|
||||
* This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis.
|
||||
* If the baro height estimate rises during forward flight, then this will be a negative number.
|
||||
*
|
||||
@@ -1191,6 +1202,7 @@ PARAM_DEFINE_FLOAT(EKF2_PCOEF_XP, 0.0f);
|
||||
|
||||
/**
|
||||
* Static pressure position error coefficient for the negative X axis.
|
||||
*
|
||||
* This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis.
|
||||
* If the baro height estimate rises during backwards flight, then this will be a negative number.
|
||||
*
|
||||
@@ -1203,6 +1215,7 @@ PARAM_DEFINE_FLOAT(EKF2_PCOEF_XN, 0.0f);
|
||||
|
||||
/**
|
||||
* Pressure position error coefficient for the positive Y axis.
|
||||
*
|
||||
* This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the positive Y (RH) body axis.
|
||||
* If the baro height estimate rises during sideways flight to the right, then this will be a negative number.
|
||||
*
|
||||
@@ -1215,6 +1228,7 @@ PARAM_DEFINE_FLOAT(EKF2_PCOEF_YP, 0.0f);
|
||||
|
||||
/**
|
||||
* Pressure position error coefficient for the negative Y axis.
|
||||
*
|
||||
* This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the negative Y (LH) body axis.
|
||||
* If the baro height estimate rises during sideways flight to the left, then this will be a negative number.
|
||||
*
|
||||
@@ -1227,6 +1241,7 @@ PARAM_DEFINE_FLOAT(EKF2_PCOEF_YN, 0.0f);
|
||||
|
||||
/**
|
||||
* Static pressure position error coefficient for the Z axis.
|
||||
*
|
||||
* This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis.
|
||||
*
|
||||
* @group EKF2
|
||||
@@ -1237,7 +1252,9 @@ PARAM_DEFINE_FLOAT(EKF2_PCOEF_YN, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(EKF2_PCOEF_Z, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer bias learning limit. The ekf delta velocity bias states will be limited to within a range equivalent to +- of this value.
|
||||
* Accelerometer bias learning limit.
|
||||
*
|
||||
* The ekf delta velocity bias states will be limited to within a range equivalent to +- of this value.
|
||||
*
|
||||
* @group EKF2
|
||||
* @min 0.0
|
||||
@@ -1249,6 +1266,7 @@ PARAM_DEFINE_FLOAT(EKF2_ABL_LIM, 0.4f);
|
||||
|
||||
/**
|
||||
* Maximum IMU accel magnitude that allows IMU bias learning.
|
||||
*
|
||||
* If the magnitude of the IMU accelerometer vector exceeds this value, the EKF delta velocity state estimation will be inhibited.
|
||||
* This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the delta velocity bias estimates.
|
||||
*
|
||||
@@ -1262,6 +1280,7 @@ PARAM_DEFINE_FLOAT(EKF2_ABL_ACCLIM, 25.0f);
|
||||
|
||||
/**
|
||||
* Maximum IMU gyro angular rate magnitude that allows IMU bias learning.
|
||||
*
|
||||
* If the magnitude of the IMU angular rate vector exceeds this value, the EKF delta velocity state estimation will be inhibited.
|
||||
* This reduces the adverse effect of rapid rotation rates and associated errors on the delta velocity bias estimates.
|
||||
*
|
||||
@@ -1275,6 +1294,7 @@ PARAM_DEFINE_FLOAT(EKF2_ABL_GYRLIM, 3.0f);
|
||||
|
||||
/**
|
||||
* Time constant used by acceleration and angular rate magnitude checks used to inhibit delta velocity bias learning.
|
||||
*
|
||||
* The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay.
|
||||
* This parameter controls the time constant of the decay.
|
||||
*
|
||||
@@ -1342,6 +1362,7 @@ PARAM_DEFINE_INT32(EKF2_SYNT_MAG_Z, 0);
|
||||
|
||||
/**
|
||||
* Default value of true airspeed used in EKF-GSF AHRS calculation.
|
||||
*
|
||||
* If no airspeed measurements are avalable, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes.
|
||||
*
|
||||
* @group EKF2
|
||||
|
||||
@@ -321,6 +321,7 @@ PARAM_DEFINE_FLOAT(FW_LND_TLALT, -1.0f);
|
||||
|
||||
/**
|
||||
* Landing heading hold horizontal distance.
|
||||
*
|
||||
* Set to 0 to disable heading hold.
|
||||
*
|
||||
* @unit m
|
||||
|
||||
@@ -62,6 +62,7 @@ PARAM_DEFINE_INT32(RWTO_HDG, 0);
|
||||
|
||||
/**
|
||||
* Altitude AGL at which we have enough ground clearance to allow some roll.
|
||||
*
|
||||
* Until RWTO_NAV_ALT is reached the plane is held level and only
|
||||
* rudder is used to keep the heading (see RWTO_HDG). This should be below
|
||||
* FW_CLMBOUT_DIFF if FW_CLMBOUT_DIFF > 0.
|
||||
@@ -77,7 +78,8 @@ PARAM_DEFINE_FLOAT(RWTO_NAV_ALT, 5.0);
|
||||
|
||||
/**
|
||||
* Max throttle during runway takeoff.
|
||||
* (Can be used to test taxi on runway)
|
||||
*
|
||||
* Can be used to test taxi on runway
|
||||
*
|
||||
* @unit norm
|
||||
* @min 0.0
|
||||
@@ -90,6 +92,7 @@ PARAM_DEFINE_FLOAT(RWTO_MAX_THR, 1.0);
|
||||
|
||||
/**
|
||||
* Pitch setpoint during taxi / before takeoff airspeed is reached.
|
||||
*
|
||||
* A taildragger with steerable wheel might need to pitch up
|
||||
* a little to keep its wheel on the ground before airspeed
|
||||
* to takeoff is reached.
|
||||
@@ -105,6 +108,7 @@ PARAM_DEFINE_FLOAT(RWTO_PSP, 0.0);
|
||||
|
||||
/**
|
||||
* Max pitch during takeoff.
|
||||
*
|
||||
* Fixed-wing settings are used if set to 0. Note that there is also a minimum
|
||||
* pitch of 10 degrees during takeoff, so this must be larger if set.
|
||||
*
|
||||
@@ -119,6 +123,7 @@ PARAM_DEFINE_FLOAT(RWTO_MAX_PITCH, 20.0);
|
||||
|
||||
/**
|
||||
* Max roll during climbout.
|
||||
*
|
||||
* Roll is limited during climbout to ensure enough lift and prevents aggressive
|
||||
* navigation before we're on a safe height.
|
||||
*
|
||||
@@ -132,7 +137,8 @@ PARAM_DEFINE_FLOAT(RWTO_MAX_PITCH, 20.0);
|
||||
PARAM_DEFINE_FLOAT(RWTO_MAX_ROLL, 25.0);
|
||||
|
||||
/**
|
||||
* Min. airspeed scaling factor for takeoff.
|
||||
* Min airspeed scaling factor for takeoff.
|
||||
*
|
||||
* Pitch up will be commanded when the following airspeed is reached:
|
||||
* FW_AIRSPD_MIN * RWTO_AIRSPD_SCL
|
||||
*
|
||||
|
||||
@@ -175,6 +175,7 @@ PARAM_DEFINE_FLOAT(LPE_GPS_Z, 3.0f);
|
||||
|
||||
/**
|
||||
* GPS xy velocity standard deviation.
|
||||
*
|
||||
* EPV used if greater than this value.
|
||||
*
|
||||
* @group Local Position Estimator
|
||||
@@ -316,6 +317,7 @@ PARAM_DEFINE_FLOAT(LPE_PN_T, 0.001f);
|
||||
|
||||
/**
|
||||
* Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg)
|
||||
*
|
||||
* Used to calculate increased terrain random walk nosie due to movement.
|
||||
*
|
||||
* @group Local Position Estimator
|
||||
@@ -339,7 +341,8 @@ PARAM_DEFINE_FLOAT(LPE_FGYRO_HP, 0.001f);
|
||||
|
||||
/**
|
||||
* Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow)
|
||||
* by initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable
|
||||
*
|
||||
* By initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable
|
||||
*
|
||||
* @group Local Position Estimator
|
||||
* @min 0
|
||||
|
||||
@@ -148,6 +148,7 @@ PARAM_DEFINE_FLOAT(MC_YAWRATE_MAX, 200.0f);
|
||||
|
||||
/**
|
||||
* Manual tilt input filter time constant
|
||||
*
|
||||
* Setting this parameter to 0 disables the filter
|
||||
*
|
||||
* @unit s
|
||||
|
||||
@@ -299,6 +299,7 @@ PARAM_DEFINE_FLOAT(MPC_XY_ERR_MAX, 2.0f);
|
||||
|
||||
/**
|
||||
* Maximum horizontal velocity setpoint for manual controlled mode
|
||||
*
|
||||
* If velocity setpoint larger than MPC_XY_VEL_MAX is set, then
|
||||
* the setpoint will be capped to MPC_XY_VEL_MAX
|
||||
*
|
||||
@@ -364,6 +365,7 @@ PARAM_DEFINE_FLOAT(MPC_LAND_SPEED, 0.7f);
|
||||
|
||||
/**
|
||||
* Maximum horizontal position mode velocity when close to ground/home altitude
|
||||
*
|
||||
* Set the value higher than the otherwise expected maximum to disable any slowdown.
|
||||
*
|
||||
* @unit m/s
|
||||
@@ -423,6 +425,7 @@ PARAM_DEFINE_FLOAT(MPC_MAN_Y_MAX, 150.0f);
|
||||
|
||||
/**
|
||||
* Manual yaw rate input filter time constant
|
||||
*
|
||||
* Setting this parameter to 0 disables the filter
|
||||
*
|
||||
* @unit s
|
||||
|
||||
@@ -283,6 +283,7 @@ PARAM_DEFINE_FLOAT(MC_YAWRATE_K, 1.0f);
|
||||
|
||||
/**
|
||||
* Max acro roll rate
|
||||
*
|
||||
* default: 2 turns per second
|
||||
*
|
||||
* @unit deg/s
|
||||
@@ -296,6 +297,7 @@ PARAM_DEFINE_FLOAT(MC_ACRO_R_MAX, 720.0f);
|
||||
|
||||
/**
|
||||
* Max acro pitch rate
|
||||
*
|
||||
* default: 2 turns per second
|
||||
*
|
||||
* @unit deg/s
|
||||
@@ -309,6 +311,7 @@ PARAM_DEFINE_FLOAT(MC_ACRO_P_MAX, 720.0f);
|
||||
|
||||
/**
|
||||
* Max acro yaw rate
|
||||
*
|
||||
* default 1.5 turns per second
|
||||
*
|
||||
* @unit deg/s
|
||||
|
||||
@@ -78,6 +78,7 @@ PARAM_DEFINE_INT32(NAV_FT_FS, 1);
|
||||
|
||||
/**
|
||||
* Dynamic filtering algorithm responsiveness to target movement
|
||||
*
|
||||
* lower numbers increase the responsiveness to changing long lat
|
||||
* but also ignore less noise
|
||||
*
|
||||
|
||||
@@ -262,6 +262,7 @@ PARAM_DEFINE_FLOAT(GND_SPEED_MAX, 10.0f);
|
||||
|
||||
/**
|
||||
* Maximum turn angle for Ackerman steering.
|
||||
*
|
||||
* At a control output of 0, the steering wheels are at 0 radians.
|
||||
* At a control output of 1, the steering wheels are at GND_MAX_ANG radians.
|
||||
*
|
||||
|
||||
@@ -87,6 +87,7 @@ PARAM_DEFINE_FLOAT(SENS_FLOW_MAXHGT, 3.0f);
|
||||
|
||||
/**
|
||||
* Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor.
|
||||
*
|
||||
* Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and
|
||||
* control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground
|
||||
* is less than 50% of this value.
|
||||
|
||||
@@ -195,9 +195,11 @@ PARAM_DEFINE_FLOAT(CAL_MAG0_YODIAG, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_ZODIAG, 0.0f);
|
||||
|
||||
/**
|
||||
* X Axis throttle compensation for Mag 0
|
||||
*
|
||||
* Coefficient describing linear relationship between
|
||||
* X component of magnetometer in body frame axis
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP.
|
||||
* Unit for throttle-based compensation is [G] and
|
||||
* for current-based compensation [G/kA]
|
||||
*
|
||||
@@ -207,9 +209,11 @@ PARAM_DEFINE_FLOAT(CAL_MAG0_ZODIAG, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_XCOMP, 0.0f);
|
||||
|
||||
/**
|
||||
* Y Axis throttle compensation for Mag 0
|
||||
*
|
||||
* Coefficient describing linear relationship between
|
||||
* Y component of magnetometer in body frame axis
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP.
|
||||
* Unit for throttle-based compensation is [G] and
|
||||
* for current-based compensation [G/kA]
|
||||
*
|
||||
@@ -219,9 +223,11 @@ PARAM_DEFINE_FLOAT(CAL_MAG0_XCOMP, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_YCOMP, 0.0f);
|
||||
|
||||
/**
|
||||
* Z Axis throttle compensation for Mag 0
|
||||
*
|
||||
* Coefficient describing linear relationship between
|
||||
* Z component of magnetometer in body frame axis
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP.
|
||||
* Unit for throttle-based compensation is [G] and
|
||||
* for current-based compensation [G/kA]
|
||||
*
|
||||
|
||||
@@ -195,9 +195,11 @@ PARAM_DEFINE_FLOAT(CAL_MAG1_YODIAG, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG1_ZODIAG, 0.0f);
|
||||
|
||||
/**
|
||||
* X Axis throttle compensation for Mag 1
|
||||
*
|
||||
* Coefficient describing linear relationship between
|
||||
* X component of magnetometer in body frame axis
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP.
|
||||
* Unit for throttle-based compensation is [G] and
|
||||
* for current-based compensation [G/kA]
|
||||
*
|
||||
@@ -207,9 +209,11 @@ PARAM_DEFINE_FLOAT(CAL_MAG1_ZODIAG, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG1_XCOMP, 0.0f);
|
||||
|
||||
/**
|
||||
* Y Axis throttle compensation for Mag 1
|
||||
*
|
||||
* Coefficient describing linear relationship between
|
||||
* Y component of magnetometer in body frame axis
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP.
|
||||
* Unit for throttle-based compensation is [G] and
|
||||
* for current-based compensation [G/kA]
|
||||
*
|
||||
@@ -219,9 +223,11 @@ PARAM_DEFINE_FLOAT(CAL_MAG1_XCOMP, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG1_YCOMP, 0.0f);
|
||||
|
||||
/**
|
||||
* Z Axis throttle compensation for Mag 1
|
||||
*
|
||||
* Coefficient describing linear relationship between
|
||||
* Z component of magnetometer in body frame axis
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP.
|
||||
* Unit for throttle-based compensation is [G] and
|
||||
* for current-based compensation [G/kA]
|
||||
*
|
||||
|
||||
@@ -195,9 +195,11 @@ PARAM_DEFINE_FLOAT(CAL_MAG2_YODIAG, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG2_ZODIAG, 0.0f);
|
||||
|
||||
/**
|
||||
* X Axis throttle compensation for Mag 2
|
||||
*
|
||||
* Coefficient describing linear relationship between
|
||||
* X component of magnetometer in body frame axis
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP.
|
||||
* Unit for throttle-based compensation is [G] and
|
||||
* for current-based compensation [G/kA]
|
||||
*
|
||||
@@ -207,9 +209,11 @@ PARAM_DEFINE_FLOAT(CAL_MAG2_ZODIAG, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG2_XCOMP, 0.0f);
|
||||
|
||||
/**
|
||||
* Y Axis throttle compensation for Mag 2
|
||||
*
|
||||
* Coefficient describing linear relationship between
|
||||
* Y component of magnetometer in body frame axis
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP.
|
||||
* Unit for throttle-based compensation is [G] and
|
||||
* for current-based compensation [G/kA]
|
||||
*
|
||||
@@ -219,9 +223,11 @@ PARAM_DEFINE_FLOAT(CAL_MAG2_XCOMP, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG2_YCOMP, 0.0f);
|
||||
|
||||
/**
|
||||
* Z Axis throttle compensation for Mag 2
|
||||
*
|
||||
* Coefficient describing linear relationship between
|
||||
* Z component of magnetometer in body frame axis
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP.
|
||||
* Unit for throttle-based compensation is [G] and
|
||||
* for current-based compensation [G/kA]
|
||||
*
|
||||
|
||||
@@ -195,9 +195,11 @@ PARAM_DEFINE_FLOAT(CAL_MAG3_YODIAG, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG3_ZODIAG, 0.0f);
|
||||
|
||||
/**
|
||||
* X Axis throttle compensation for Mag 3
|
||||
*
|
||||
* Coefficient describing linear relationship between
|
||||
* X component of magnetometer in body frame axis
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP.
|
||||
* Unit for throttle-based compensation is [G] and
|
||||
* for current-based compensation [G/kA]
|
||||
*
|
||||
@@ -207,9 +209,11 @@ PARAM_DEFINE_FLOAT(CAL_MAG3_ZODIAG, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG3_XCOMP, 0.0f);
|
||||
|
||||
/**
|
||||
* Y Axis throttle compensation for Mag 3
|
||||
*
|
||||
* Coefficient describing linear relationship between
|
||||
* Y component of magnetometer in body frame axis
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP.
|
||||
* Unit for throttle-based compensation is [G] and
|
||||
* for current-based compensation [G/kA]
|
||||
*
|
||||
@@ -219,9 +223,11 @@ PARAM_DEFINE_FLOAT(CAL_MAG3_XCOMP, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG3_YCOMP, 0.0f);
|
||||
|
||||
/**
|
||||
* Z Axis throttle compensation for Mag 3
|
||||
*
|
||||
* Coefficient describing linear relationship between
|
||||
* Z component of magnetometer in body frame axis
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP
|
||||
* and either current or throttle depending on value of CAL_MAG_COMP_TYP.
|
||||
* Unit for throttle-based compensation is [G] and
|
||||
* for current-based compensation [G/kA]
|
||||
*
|
||||
|
||||
@@ -418,6 +418,7 @@ PARAM_DEFINE_FLOAT(SIH_DISTSNSR_MAX, 100.0f);
|
||||
|
||||
/**
|
||||
* if >= 0 the distance sensor measures will be overrided by this value
|
||||
*
|
||||
* Absolute value superior to 10000 will disable distance sensor
|
||||
*
|
||||
* @unit m
|
||||
|
||||
@@ -44,8 +44,9 @@
|
||||
PARAM_DEFINE_FLOAT(SIM_BAT_DRAIN, 60);
|
||||
|
||||
/**
|
||||
* Simulator Battery minimal percentage. Can be used to alter
|
||||
* the battery level during SITL- or HITL-simulation on the fly.
|
||||
* Simulator Battery minimal percentage.
|
||||
*
|
||||
* Can be used to alter the battery level during SITL- or HITL-simulation on the fly.
|
||||
* Particularly useful for testing different low-battery behaviour.
|
||||
*
|
||||
* @min 0
|
||||
|
||||
@@ -94,6 +94,7 @@ PARAM_DEFINE_INT32(MNT_MAV_COMPID, 154);
|
||||
|
||||
/**
|
||||
* Mixer value for selecting normal mode
|
||||
*
|
||||
* if required by the gimbal (only in AUX output mode)
|
||||
*
|
||||
* @min -1.0
|
||||
@@ -105,6 +106,7 @@ PARAM_DEFINE_FLOAT(MNT_OB_NORM_MODE, -1.0f);
|
||||
|
||||
/**
|
||||
* Mixer value for selecting a locking mode
|
||||
*
|
||||
* if required for the gimbal (only in AUX output mode)
|
||||
*
|
||||
* @min -1.0
|
||||
@@ -163,9 +165,11 @@ PARAM_DEFINE_INT32(MNT_MAN_PITCH, 0);
|
||||
PARAM_DEFINE_INT32(MNT_MAN_YAW, 0);
|
||||
|
||||
/**
|
||||
* Stabilize the mount (set to true for servo gimbal, false for passthrough).
|
||||
* (This is required for a gimbal which is not capable of stabilizing itself
|
||||
* and relies on the IMU's attitude estimation.)
|
||||
* Stabilize the mount
|
||||
*
|
||||
* Set to true for servo gimbal, false for passthrough.
|
||||
* This is required for a gimbal which is not capable of stabilizing itself
|
||||
* and relies on the IMU's attitude estimation.
|
||||
*
|
||||
* @value 0 Disable
|
||||
* @value 1 Stabilize all axis
|
||||
@@ -238,6 +242,7 @@ PARAM_DEFINE_FLOAT(MNT_OFF_YAW, 0.0f);
|
||||
|
||||
/**
|
||||
* Angular pitch rate for manual input in degrees/second.
|
||||
*
|
||||
* Full stick input [-1..1] translats to [-pitch rate..pitch rate].
|
||||
*
|
||||
* @min 1.0
|
||||
@@ -248,6 +253,7 @@ PARAM_DEFINE_FLOAT(MNT_RATE_PITCH, 30.0f);
|
||||
|
||||
/**
|
||||
* Angular yaw rate for manual input in degrees/second.
|
||||
*
|
||||
* Full stick input [-1..1] translats to [-yaw rate..yaw rate].
|
||||
*
|
||||
* @min 1.0
|
||||
|
||||
@@ -42,6 +42,7 @@
|
||||
|
||||
/**
|
||||
* Enable/disable usage of fixed-wing actuators in hover to generate forward force (instead of pitching down).
|
||||
*
|
||||
* This technique can be used to avoid the plane having to pitch down in order to move forward.
|
||||
* This prevents large, negative lift values being created when facing strong winds.
|
||||
* Fixed-wing forward actuators refers to puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL).
|
||||
@@ -62,7 +63,8 @@ PARAM_DEFINE_INT32(VT_FWD_THRUST_EN, 0);
|
||||
|
||||
/**
|
||||
* Maximum allowed angle the vehicle is allowed to pitch down to generate forward force
|
||||
* when fixed-wing forward actuation is active (seeVT_FW_TRHUST_EN).
|
||||
*
|
||||
* When fixed-wing forward actuation is active (see VT_FW_TRHUST_EN).
|
||||
* If demanded down pitch exceeds this limmit, the fixed-wing forward actuators are used instead.
|
||||
*
|
||||
* @min 0.0
|
||||
@@ -98,6 +100,7 @@ PARAM_DEFINE_FLOAT(VT_B_TRANS_RAMP, 3.0f);
|
||||
|
||||
/**
|
||||
* Output on airbrakes channel during back transition
|
||||
*
|
||||
* Used for airbrakes or with ESCs that have reverse thrust enabled on a seperate channel
|
||||
* Airbrakes need to be enables for your selected model/mixer
|
||||
*
|
||||
@@ -112,6 +115,7 @@ PARAM_DEFINE_FLOAT(VT_B_REV_OUT, 0.0f);
|
||||
|
||||
/**
|
||||
* Delay in seconds before applying back transition throttle
|
||||
*
|
||||
* Set this to a value greater than 0 to give the motor time to spin down.
|
||||
*
|
||||
* unit s
|
||||
@@ -124,6 +128,8 @@ PARAM_DEFINE_FLOAT(VT_B_REV_OUT, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(VT_B_REV_DEL, 0.0f);
|
||||
|
||||
/**
|
||||
* Pusher throttle ramp up window
|
||||
*
|
||||
* Defines the time window during which the pusher throttle will be ramped up linearly to VT_F_TRANS_THR during a transition
|
||||
* to fixed wing mode. Zero or negative values will produce an instant throttle rise to VT_F_TRANS_THR.
|
||||
*
|
||||
|
||||
@@ -116,7 +116,9 @@ PARAM_DEFINE_FLOAT(VT_B_TRANS_DUR, 4.0f);
|
||||
|
||||
/**
|
||||
* Target throttle value for the transition to fixed wing flight.
|
||||
*
|
||||
* standard vtol: pusher
|
||||
*
|
||||
* tailsitter, tiltrotor: main throttle
|
||||
*
|
||||
* @min 0.0
|
||||
@@ -129,7 +131,9 @@ PARAM_DEFINE_FLOAT(VT_F_TRANS_THR, 1.0f);
|
||||
|
||||
/**
|
||||
* Target throttle value for the transition to hover flight.
|
||||
*
|
||||
* standard vtol: pusher
|
||||
*
|
||||
* tailsitter, tiltrotor: main throttle
|
||||
*
|
||||
* Note for standard vtol:
|
||||
|
||||
Reference in New Issue
Block a user