- 参数参照表
- Airspeed Validator
- Attitude Q estimator
- Battery Calibration
- Camera Capture
- Camera Control
- Camera trigger
- Circuit Breaker
- Commander
- Data Link Loss
- EKF2
- Events
- FW Attitude Control
- FW L1 Control
- FW Launch detection
- FW TECS
- Failure Detector
- Follow target
- GPS
- GPS Failure Navigation
- Geofence
- Iridium SBD
- Land Detector
- Landing target Estimator
- Local Position Estimator
- MAVLink
- MKBLCTRL Testmode
- MPU9x50 Configuration
- Mission
- Mount
- Multicopter Attitude Control
- Multicopter Position Control
- OSD
- PWM Outputs
- Payload drop
- Precision Land
- RC Receiver Configuration
- RTPS
- Radio Calibration
- Radio Switches
- Return Mode
- Roboclaw
- Roboclaw driver
- Rover Position Control
- Runway Takeoff
- SD Logging
- SITL
- Sensor Calibration
- Sensors
- Serial
- Simulation In Hardware
- Snapdragon UART ESC
- System
- Telemetry
- Testing
- Thermal Compensation
- UAVCAN
- VTOL Attitude Control
- Miscellaneous
参数参照表
注意:**这个清单是从源代码中自动生成的** (使用
make parameters_metadata
) 并且包含了最新的参数文档.
Airspeed Validator
名称 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
ARSP_ARSP_SCALE (FLOAT) | Airspeed scale (scale from IAS to CAS/EAS) Comment: Scale can either be entered manually, or estimated in-flight by setting ARSP_SCALE_EST to 1. | 0.5 > 1.5 | 1.0 | |
ARSP_BETA_GATE (INT32) | Airspeed Selector: Gate size for true sideslip fusion Comment: Sets the number of standard deviations used by the innovation consistency test. | 1 > 5 | 1 | SD |
ARSP_BETA_NOISE (FLOAT) | Airspeed Selector: Wind estimator sideslip measurement noise Comment: Sideslip measurement noise of the internal wind estimator(s) of the airspeed selector. | 0 > 1 | 0.3 | rad |
ARSP_SCALE_EST (INT32) | Automatic airspeed scale estimation on Comment: Turns the automatic airspeed scale (scale from IAS to CAS/EAS) on or off. It is recommended level (keeping altitude) while performing the estimation. Set to 1 to start estimation (best when already flying). Set to 0 to end scale estimation. The estimated scale is then saved in the ARSP_ARSP_SCALE parameter. | 0 | ||
ARSP_SC_P_NOISE (FLOAT) | Airspeed Selector: Wind estimator true airspeed scale process noise Comment: Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector. | 0 > 0.1 | 0.0001 | 1/s |
ARSP_TAS_GATE (INT32) | Airspeed Selector: Gate size for true airspeed fusion Comment: Sets the number of standard deviations used by the innovation consistency test. | 1 > 5 | 3 | SD |
ARSP_TAS_NOISE (FLOAT) | Airspeed Selector: Wind estimator true airspeed measurement noise Comment: True airspeed measurement noise of the internal wind estimator(s) of the airspeed selector. | 0 > 4 | 1.4 | m/s |
ARSP_W_P_NOISE (FLOAT) | Airspeed Selector: Wind estimator wind process noise Comment: Wind process noise of the internal wind estimator(s) of the airspeed selector. | 0 > 1 | 0.1 | m/s/s |
Attitude Q estimator
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
ATT_ACC_COMP (INT32) | Acceleration compensation based on GPS velocity | 1 | ||
ATT_BIAS_MAX (FLOAT) | Gyro bias limit | 0 > 2 | 0.05 | rad/s |
ATT_EXT_HDG_M (INT32) | 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 Values:
| 0 > 2 | 0 | |
ATT_MAG_DECL (FLOAT) | Magnetic declination, in degrees Comment: This parameter is not used in normal operation, as the declination is looked up based on the GPS coordinates of the vehicle. | 0.0 | deg | |
ATT_MAG_DECL_A (INT32) | Automatic GPS based declination compensation | 1 | ||
ATT_W_ACC (FLOAT) | Complimentary filter accelerometer weight | 0 > 1 | 0.2 | |
ATT_W_EXT_HDG (FLOAT) | Complimentary filter external heading weight | 0 > 1 | 0.1 | |
ATT_W_GYRO_BIAS (FLOAT) | Complimentary filter gyroscope bias weight | 0 > 1 | 0.1 | |
ATT_W_MAG (FLOAT) | Complimentary filter magnetometer weight Comment: Set to 0 to avoid using the magnetometer. | 0 > 1 | 0.1 |
Battery Calibration
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
BAT_ADC_CHANNEL (INT32) | Battery ADC Channel Comment: This parameter specifies the ADC channel used to monitor voltage of main power battery. A value of -1 means to use the board default. | -1 | ||
BAT_A_PER_V (FLOAT) | Battery current per volt (A/V) Comment: The voltage seen by the 3.3V ADC multiplied by this factor will determine the battery current. A value of -1 means to use the board default. | -1.0 | ||
BAT_CAPACITY (FLOAT) | Battery capacity Comment: Defines the capacity of the attached battery. Reboot required: true | -1.0 > 100000 (50) | -1.0 | mAh |
BAT_CNT_V_CURR (FLOAT) | Scaling from ADC counts to volt on the ADC input (battery current) Comment: This is not the battery current, but the intermediate ADC voltage. A value of -1 signifies that the board defaults are used, which is highly recommended. | -1.0 | ||
BAT_CNT_V_VOLT (FLOAT) | Scaling from ADC counts to volt on the ADC input (battery voltage) Comment: This is not the battery voltage, but the intermediate ADC voltage. A value of -1 signifies that the board defaults are used, which is highly recommended. | -1.0 | ||
BAT_CRIT_THR (FLOAT) | Critical threshold Comment: Sets the threshold when the battery will be reported as critically low. This has to be lower than the low threshold. This threshold commonly will trigger RTL. Reboot required: true | 0.05 > 0.1 (0.01) | 0.07 | norm |
BAT_EMERGEN_THR (FLOAT) | Emergency threshold Comment: Sets the threshold when the battery will be reported as dangerously low. This has to be lower than the critical threshold. This threshold commonly will trigger landing. Reboot required: true | 0.03 > 0.07 (0.01) | 0.05 | norm |
BAT_LOW_THR (FLOAT) | Low threshold Comment: Sets the threshold when the battery will be reported as low. This has to be higher than the critical threshold. Reboot required: true | 0.12 > 0.4 (0.01) | 0.15 | norm |
BAT_N_CELLS (INT32) | Number of cells Comment: Defines the number of cells the attached battery consists of. Values:
Reboot required: true | 0 | S | |
BAT_R_INTERNAL (FLOAT) | Explicitly defines the per cell internal resistance Comment: If non-negative, then this will be used in place of BAT_V_LOAD_DROP for all calculations. Reboot required: true | -1.0 > 0.2 | -1.0 | Ohms |
BAT_SOURCE (INT32) | Battery monitoring source Comment: This parameter controls the source of battery data. The value ‘Power Module’ means that measurements are expected to come from a power module. If the value is set to ‘External’ then the system expects to receive mavlink battery status messages. Values:
| 0 > 1 | 0 | |
BAT_V_CHARGED (FLOAT) | Full cell voltage (5C load) Comment: Defines the voltage where a single cell of the battery is considered full under a mild load. This will never be the nominal voltage of 4.2V Reboot required: true | (0.01) | 4.05 | V |
BAT_V_DIV (FLOAT) | Battery voltage divider (V divider) Comment: This is the divider from battery voltage to 3.3V ADC voltage. If using e.g. Mauch power modules the value from the datasheet can be applied straight here. A value of -1 means to use the board default. | -1.0 | ||
BAT_V_EMPTY (FLOAT) | Empty cell voltage (5C load) Comment: Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen before the steep dropoff to 2.8V. A typical lithium battery can only be discharged down to 10% before it drops off to a voltage level damaging the cells. Reboot required: true | (0.01) | 3.5 | V |
BAT_V_LOAD_DROP (FLOAT) | Voltage drop per cell on full throttle Comment: This implicitely defines the internal resistance to maximum current ratio and assumes linearity. A good value to use is the difference between the 5C and 20-25C load. Not used if BAT_R_INTERNAL is set. Reboot required: true | 0.07 > 0.5 (0.01) | 0.3 | V |
BAT_V_OFFS_CURR (FLOAT) | Offset in volt as seen by the ADC input of the current sensor Comment: This offset will be subtracted before calculating the battery current based on the voltage. | 0.0 |
Camera Capture
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
CAM_CAP_DELAY (FLOAT) | Camera strobe delay Comment: This parameter sets the delay between image integration start and strobe firing | 0.0 > 100.0 | 0.0 | ms |
Camera Control
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
CAM_CAP_EDGE (INT32) | Camera capture edge Values:
Reboot required: true | 0 | ||
CAM_CAP_FBACK (INT32) | Camera capture feedback Comment: Enables camera capture feedback Reboot required: true | 0 | ||
CAM_CAP_MODE (INT32) | Camera capture timestamping mode Comment: Change time measurement Values:
要求重启:是 | 0 |
Camera trigger
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
TRIG_ACT_TIME (FLOAT) | Camera trigger activation time Comment: This parameter sets the time the trigger needs to pulled high or low. | 0.1 > 3000 | 40.0 | ms |
TRIG_DISTANCE (FLOAT) | Camera trigger distance Comment: Sets the distance at which to trigger the camera. | 0 > ? (1) | 25.0 | m |
TRIG_INTERFACE (INT32) | Camera trigger Interface Comment: Selects the trigger interface Values:
Reboot required: true | 4 | ||
TRIG_INTERVAL (FLOAT) | Camera trigger interval Comment: This parameter sets the time between two consecutive trigger events | 4.0 > 10000.0 | 40.0 | ms |
TRIG_MODE (INT32) | Camera trigger mode Values:
Reboot required: true | 0 > 4 | 0 | |
TRIG_PINS (INT32) | Camera trigger pin Comment: Selects which pin is used, ranges from 1 to 6 (AUX1-AUX6 on px4_fmu-v2 and the rail pins on px4_fmu-v4). The PWM interface takes two pins per camera, while relay triggers on every pin individually. Example: Value 56 would trigger on pins 5 and 6. For GPIO mode Pin 6 will be triggered followed by 5. With a value of 65 pin 5 will be triggered followed by 6. Pins may be non contiguous. I.E. 16 or 61. In GPIO mode the delay pin to pin is < .2 uS. Reboot required: true | 1 > 123456 | 56 | |
TRIG_POLARITY (INT32) | Camera trigger polarity Comment: This parameter sets the polarity of the trigger (0 = active low, 1 = active high ) Values:
| 0 > 1 | 0 | |
TRIG_PWM_NEUTRAL (INT32) | PWM neutral output on trigger pin Reboot required: true | 1000 > 2000 | 1500 | us |
TRIG_PWM_SHOOT (INT32) | PWM output to trigger shot Reboot required: true | 1000 > 2000 | 1900 | us |
Circuit Breaker
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
CBRK_AIRSPD_CHK (INT32) | Circuit breaker for airspeed sensor Comment: Setting this parameter to 162128 will disable the check for an airspeed sensor. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK Reboot required: true | 0 > 162128 | 0 | |
CBRK_BUZZER (INT32) | Circuit breaker for disabling buzzer Comment: Setting this parameter to 782097 will disable the buzzer audio notification. Setting this parameter to 782090 will disable the startup tune, while keeping all others enabled. Reboot required: true | 0 > 782097 | 0 | |
CBRK_ENGINEFAIL (INT32) | Circuit breaker for engine failure detection Comment: Setting this parameter to 284953 will disable the engine failure detection. If the aircraft is in engine failure mode the engine failure flag will be set to healthy WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK Reboot required: true | 0 > 284953 | 284953 | |
CBRK_FLIGHTTERM (INT32) | Circuit breaker for flight termination Comment: Setting this parameter to 121212 will disable the flight termination action if triggered by the FailureDetector logic or if FMU is lost. This circuit breaker does not affect the RC loss, data link loss and geofence safety logic. Reboot required: true | 0 > 121212 | 121212 | |
CBRK_GPSFAIL (INT32) | Circuit breaker for GPS failure detection Comment: Setting this parameter to 240024 will disable the GPS failure detection. If this check is enabled, then the sensor check will fail if the GPS module is missing. It will also check for excessive signal noise on the GPS receiver and warn the user if detected. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK Reboot required: true | 0 > 240024 | 0 | |
CBRK_IO_SAFETY (INT32) | Circuit breaker for IO safety Comment: Setting this parameter to 22027 will disable IO safety. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK Reboot required: true | 0 > 22027 | 0 | |
CBRK_RATE_CTRL (INT32) | Circuit breaker for rate controller output Comment: Setting this parameter to 140253 will disable the rate controller uORB publication. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK Reboot required: true | 0 > 140253 | 0 | |
CBRK_SUPPLY_CHK (INT32) | Circuit breaker for power supply check Comment: Setting this parameter to 894281 will disable the power valid checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK Reboot required: true | 0 > 894281 | 0 | |
CBRK_USB_CHK (INT32) | Circuit breaker for USB link check Comment: Setting this parameter to 197848 will disable the USB connected checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK Reboot required: true | 0 > 197848 | 0 | |
CBRK_VELPOSERR (INT32) | Circuit breaker for position error check Comment: Setting this parameter to 201607 will disable the position and velocity accuracy checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK Reboot required: true | 0 > 201607 | 0 |
Commander
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
COM_ARM_AUTH (INT32) | Arm authorization parameters, this uint32_t will be split between starting from the LSB: - 8bits to authorizer system id - 16bits to authentication method parameter, this will be used to store a timeout for the first 2 methods but can be used to another parameter for other new authentication methods. - 7bits to authentication method - one arm = 0 - two step arm = 1 the MSB bit is not used to avoid problems in the conversion between int and uint Comment: Default value: (10 << 0 | 1000 << 8 | 0 << 24) = 256010 - authorizer system id = 10 - authentication method parameter = 10000msec of timeout - authentication method = during arm | 256010 | ||
COM_ARM_CHK_ESCS (INT32) | Require all the ESCs to be detected to arm Comment: This param is specific for ESCs reporting status. Normal ESCs configurations are not affected by the change of this param. | 1 | ||
COM_ARM_EKF_AB (FLOAT) | Maximum value of EKF accelerometer delta velocity bias estimate that will allow arming. Note: ekf2 will limit the delta velocity bias estimate magnitude to be less than EKF2_ABL_LIM FILTER_UPDATE_PERIOD_MS * 0.001 so this parameter must be less than that to be useful | 0.001 > 0.01 (0.0001) | 1.73e-3 | m/s |
COM_ARM_EKF_GB (FLOAT) | Maximum value of EKF gyro delta angle bias estimate that will allow arming | 0.0001 > 0.0017 (0.0001) | 8.7e-4 | rad |
COM_ARM_EKF_HGT (FLOAT) | Maximum EKF height innovation test ratio that will allow arming | 0.1 > 1.0 (0.05) | 1.0 | m |
COM_ARM_EKF_POS (FLOAT) | Maximum EKF position innovation test ratio that will allow arming | 0.1 > 1.0 (0.05) | 0.5 | m |
COM_ARM_EKF_VEL (FLOAT) | Maximum EKF velocity innovation test ratio that will allow arming | 0.1 > 1.0 (0.05) | 0.5 | m/s |
COM_ARM_EKF_YAW (FLOAT) | Maximum EKF yaw innovation test ratio that will allow arming | 0.1 > 1.0 (0.05) | 0.5 | rad |
COM_ARM_IMU_ACC (FLOAT) | Maximum accelerometer inconsistency between IMU units that will allow arming | 0.1 > 1.0 (0.05) | 0.7 | m/s/s |
COM_ARM_IMU_GYR (FLOAT) | Maximum rate gyro inconsistency between IMU units that will allow arming | 0.02 > 0.3 (0.01) | 0.25 | rad/s |
COM_ARM_MAG_ANG (INT32) | Maximum magnetic field inconsistency between units that will allow arming Set -1 to disable the check | 3 > 180 | 30 | deg |
COM_ARM_MIS_REQ (INT32) | Require valid mission to arm Comment: The default allows to arm the vehicle without a valid mission. | 0 | ||
COM_ARM_SWISBTN (INT32) | Arm switch is only a button Comment: The default uses the arm switch as real switch. If parameter set button gets handled like stick arming. Values:
| 0 > 1 | 0 | |
COM_ARM_WO_GPS (INT32) | Allow arming without GPS Comment: The default allows to arm the vehicle without GPS signal. | 1 | ||
COM_ASPD_FS_ACT (INT32) | Airspeed fault detection (Experimental) Comment: Failsafe action when bad airspeed measurements are detected. Ensure the COM_ASPD_STALL parameter is set correctly before use. Values:
| 0 | ||
COM_ASPD_FS_DLY (INT32) | Airspeed fault detection delay before RTL (Experimental) Comment: RTL delay after bad airspeed measurements are detected if COM_ASPD_FS_ACT is set to 4. Ensure the COM_ASPD_STALL parameter is set correctly before use. The failsafe start and stop delays are controlled by the COM_TAS_FS_T1 and COM_TAS_FS_T2 parameters. Additional protection against persistent airspeed sensor errors can be enabled using the COM_TAS_FS_INNOV parameter, but these addtional checks are more prone to false positives in windy conditions. | 0 > 300 | 0 | s |
COM_ASPD_STALL (FLOAT) | Airspeed fault detection stall airspeed. (Experimental) Comment: This is the minimum indicated airspeed at which the wing can produce 1g of lift. It is used by the airspeed sensor fault detection and failsafe calculation to detect a significant airspeed low measurement error condition and should be set based on flight test for reliable operation. The failsafe response is controlled by the COM_ASPD_FS_ACT parameter. | 10.0 | m/s | |
COM_DISARM_LAND (FLOAT) | Time-out for auto disarm after landing Comment: A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be automatically disarmed in case a landing situation has been detected during this period. The vehicle will also auto-disarm right after arming if it has not even flown, however the time will always be 10 seconds such that the pilot has enough time to take off. A negative value means that automatic disarming triggered by landing detection is disabled. | -1 > 20 | 2.0 | s |
COM_DL_LOSS_T (INT32) | Datalink loss time threshold Comment: After this amount of seconds without datalink the data link lost mode triggers | 5 > 300 (0.5) | 10 | s |
COM_EF_C2T (FLOAT) | Engine Failure Current/Throttle Threshold Comment: Engine failure triggers only below this current value | 0.0 > 50.0 (1) | 5.0 | A/% |
COM_EF_THROT (FLOAT) | Engine Failure Throttle Threshold Comment: Engine failure triggers only above this throttle value | 0.0 > 1.0 (0.01) | 0.5 | norm |
COM_EF_TIME (FLOAT) | Engine Failure Time Threshold Comment: Engine failure triggers only if the throttle threshold and the current to throttle threshold are violated for this time | 0.0 > 60.0 (1) | 10.0 | s |
COM_FLIGHT_UUID (INT32) | Next flight UUID Comment: This number is incremented automatically after every flight on disarming in order to remember the next flight UUID. The first flight is 0. | 0 > ? | 0 | |
COM_FLTMODE1 (INT32) | First flightmode slot (1000-1160) Comment: If the main switch channel is in this range the selected flight mode will be applied. Values:
| -1 | ||
COM_FLTMODE2 (INT32) | Second flightmode slot (1160-1320) Comment: If the main switch channel is in this range the selected flight mode will be applied. Values:
| -1 | ||
COM_FLTMODE3 (INT32) | Third flightmode slot (1320-1480) Comment: If the main switch channel is in this range the selected flight mode will be applied. Values:
| -1 | ||
COM_FLTMODE4 (INT32) | Fourth flightmode slot (1480-1640) Comment: If the main switch channel is in this range the selected flight mode will be applied. Values:
| -1 | ||
COM_FLTMODE5 (INT32) | Fifth flightmode slot (1640-1800) Comment: If the main switch channel is in this range the selected flight mode will be applied. Values:
| -1 | ||
COM_FLTMODE6 (INT32) | Sixth flightmode slot (1800-2000) Comment: If the main switch channel is in this range the selected flight mode will be applied. Values:
| -1 | ||
COM_FLT_PROFILE (INT32) | User Flight Profile Comment: Describes the intended use of the vehicle. Can be used by ground control software or log post processing. This param does not influence the behavior within the firmware. This means for example the control logic is independent of the setting of this param (but depends on other params). Values:
| 0 | ||
COM_HLDL_LOSS_T (INT32) | High Latency Datalink loss time threshold Comment: After this amount of seconds without datalink the data link lost mode triggers | 60 > 3600 | 120 | s |
COM_HLDL_REG_T (INT32) | High Latency Datalink regain time threshold Comment: After a data link loss: after this this amount of seconds with a healthy datalink the ‘datalink loss’ flag is set back to false | 0 > 60 | 0 | s |
COM_HOME_H_T (FLOAT) | Home set horizontal threshold Comment: The home position will be set if the estimated positioning accuracy is below the threshold. | 2 > 15 (0.5) | 5.0 | m |
COM_HOME_V_T (FLOAT) | Home set vertical threshold Comment: The home position will be set if the estimated positioning accuracy is below the threshold. | 5 > 25 (0.5) | 10.0 | m |
COM_LOW_BAT_ACT (INT32) | Battery failsafe mode Comment: Action the system takes on low battery. Defaults to off Values:
| (1) | 0 | |
COM_OA_BOOT_T (INT32) | Set avoidance system bootup timeout Comment: The avoidance system running on the companion computer is expected to boot within this time and start providing trajectory points. If no avoidance system is detected a MAVLink warning message is sent. | 0 > 200 | 100 | s |
COM_OBL_ACT (INT32) | Set offboard loss failsafe mode Comment: The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds. Values:
| 0 | ||
COM_OBL_RC_ACT (INT32) | Set offboard loss failsafe mode when RC is available Comment: The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds. Values:
| 0 | ||
COM_OF_LOSS_T (FLOAT) | 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 | 0 > 60 (1) | 0.0 | s |
COM_POSCTL_NAVL (INT32) | Position control navigation loss response Comment: This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control. Navigation accuracy checks can be disabled using the CBRK_VELPOSERR parameter, but doing so will remove protection for all flight modes. Values:
| 0 | ||
COM_POS_FS_DELAY (INT32) | Loss of position failsafe activation delay Comment: This sets number of seconds that the position checks need to be failed before the failsafe will activate. The default value has been optimised for rotary wing applications. For fixed wing applications, a larger value between 5 and 10 should be used. Reboot required: true | 1 > 100 | 1 | sec |
COM_POS_FS_EPH (FLOAT) | Horizontal position error threshold Comment: This is the horizontal position error (EPH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. | 5 | m | |
COM_POS_FS_EPV (FLOAT) | Vertical position error threshold Comment: This is the vertical position error (EPV) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. | 10 | m | |
COM_POS_FS_GAIN (INT32) | Loss of position probation gain factor Comment: This sets the rate that the loss of position probation time grows when position checks are failing. The default value has been optimised for rotary wing applications. For fixed wing applications a value of 0 should be used. Reboot required: true | 10 | ||
COM_POS_FS_PROB (INT32) | Loss of position probation delay at takeoff Comment: The probation delay is the number of seconds that the EKF innovation checks need to pass for the position to be declared good after it has been declared bad. The probation delay will be reset to this parameter value when takeoff is detected. After takeoff, if position checks are passing, the probation delay will reduce by one second for every lapsed second of valid position down to a minimum of 1 second. If position checks are failing, the probation delay will increase by COM_POS_FS_GAIN seconds for every lapsed second up to a maximum of 100 seconds. The default value has been optimised for rotary wing applications. For fixed wing applications, a value of 1 should be used. Reboot required: true | 1 > 100 | 30 | sec |
COM_RC_ARM_HYST (INT32) | RC input arm/disarm command duration Comment: The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second. | 100 > 1500 | 1000 | |
COM_RC_IN_MODE (INT32) | RC control input mode Comment: The default value of 0 requires a valid RC transmitter setup. Setting this to 1 allows joystick control and disables RC input handling and the associated checks. A value of 2 will generate RC control data from manual input received via MAVLink instead of directly forwarding the manual input data. Values:
| 0 > 2 | 0 | |
COM_RC_LOSS_T (FLOAT) | RC loss time threshold Comment: After this amount of seconds without RC connection the rc lost flag is set to true | 0 > 35 (0.1) | 0.5 | s |
COM_RC_OVERRIDE (INT32) | Enable RC stick override of auto modes Comment: When an auto mode is active (except a critical battery reaction) moving the RC sticks gives control back to the pilot in manual position mode immediately. Only has an effect on multicopters and VTOLS in multicopter mode. | 1 | ||
COM_RC_STICK_OV (FLOAT) | RC stick override threshold Comment: If an RC stick is moved more than by this amount the system will interpret this as override request by the pilot. | 5 > 40 (0.05) | 12.0 | % |
COM_TAS_FS_INNOV (FLOAT) | Airspeed failsafe consistency threshold (Experimental) Comment: This specifies the minimum airspeed test ratio as logged in estimator_status.tas_test_ratio required to trigger a failsafe. Larger values make the check less sensitive, smaller values make it more sensitive. Start with a value of 1.0 when tuning. When estimator_status.tas_test_ratio is > 1.0 it indicates the inconsistency between predicted and measured airspeed is large enough to cause the navigation EKF to reject airspeed measurements. The time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the COM_TAS_FS_INTEG parameter. The subsequent failsafe response is controlled by the COM_ASPD_FS_ACT parameter. | 0.5 > 3.0 | 1.0 | |
COM_TAS_FS_INTEG (FLOAT) | Airspeed failsafe consistency delay (Experimental) Comment: This sets the time integral of airspeed test ratio exceedance above COM_TAS_FS_INNOV required to trigger a failsafe. For example if COM_TAS_FS_INNOV is 100 and estimator_status.tas_test_ratio is 2.0, then the exceedance is 1.0 and the integral will rise at a rate of 1.0/second. A negative value disables the check. Larger positive values make the check less sensitive, smaller positive values make it more sensitive. The failsafe response is controlled by the COM_ASPD_FS_ACT parameter. | ? > 30.0 | -1.0 | s |
COM_TAS_FS_T1 (INT32) | Airspeed failsafe stop delay (Experimental) Comment: Delay before stopping use of airspeed sensor if checks indicate sensor is bad. The failsafe response is controlled by the COM_ASPD_FS_ACT parameter. | 1 > 10 | 3 | s |
COM_TAS_FS_T2 (INT32) | Airspeed failsafe start delay (Experimental) Comment: Delay before switching back to using airspeed sensor if checks indicate sensor is good. The failsafe response is controlled by the COM_ASPD_FS_ACT parameter. | 10 > 1000 | 100 | s |
COM_VEL_FS_EVH (FLOAT) | Horizontal velocity error threshold Comment: This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. | 1 | m/s |
Data Link Loss
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
NAV_AH_ALT (FLOAT) | Airfield home alt Comment: Altitude of airfield home waypoint | -50 > ? (0.5) | 600.0 | m |
NAV_AH_LAT (INT32) | Airfield home Lat Comment: Latitude of airfield home waypoint | -900000000 > 900000000 | -265847810 | deg 1e7 |
NAV_AH_LON (INT32) | Airfield home Lon Comment: Longitude of airfield home waypoint | -1800000000 > 1800000000 | 1518423250 | deg 1e7 |
NAV_DLL_AH_T (FLOAT) | Airfield home wait time Comment: The amount of time in seconds the system should wait at the airfield home waypoint | 0.0 > 3600.0 (1) | 120.0 | s |
NAV_DLL_CHSK (INT32) | Skip comms hold wp Comment: If set to 1 the system will skip the comms hold wp on data link loss and will directly fly to airfield home | 0 | ||
NAV_DLL_CH_ALT (FLOAT) | Comms hold alt Comment: Altitude of comms hold waypoint | -50 > 30000 (0.5) | 600.0 | m |
NAV_DLL_CH_LAT (INT32) | Comms hold Lat Comment: Latitude of comms hold waypoint | -900000000 > 900000000 | -266072120 | deg 1e7 |
NAV_DLL_CH_LON (INT32) | Comms hold Lon Comment: Longitude of comms hold waypoint | -1800000000 > 1800000000 | 1518453890 | deg 1e7 |
NAV_DLL_CH_T (FLOAT) | Comms hold wait time Comment: The amount of time in seconds the system should wait at the comms hold waypoint | 0.0 > 3600.0 (1) | 120.0 | s |
NAV_DLL_N (INT32) | Number of allowed Datalink timeouts Comment: After more than this number of data link timeouts the aircraft returns home directly | 0 > 1000 | 2 |
EKF2
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
EKF2_ABIAS_INIT (FLOAT) | 1-sigma IMU accelerometer switch-on bias Reboot required: true | 0.0 > 0.5 | 0.2 | m/s/s |
EKF2_ABL_ACCLIM (FLOAT) | 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 | 20.0 > 200.0 | 25.0 | m/s/s |
EKF2_ABL_GYRLIM (FLOAT) | 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 | 2.0 > 20.0 | 3.0 | rad/s |
EKF2_ABL_LIM (FLOAT) | Accelerometer bias learning limit. The ekf delta velocity bias states will be limited to within a range equivalent to +- of this value | 0.0 > 0.8 | 0.4 | m/s/s |
EKF2_ABL_TAU (FLOAT) | 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 | 0.1 > 1.0 | 0.5 | s |
EKF2_ACC_B_NOISE (FLOAT) | Process noise for IMU accelerometer bias prediction | 0.0 > 0.01 | 3.0e-3 | m/s3 |
EKF2_ACC_NOISE (FLOAT) | Accelerometer noise for covariance prediction | 0.01 > 1.0 | 3.5e-1 | m/s/s |
EKF2_AID_MASK (INT32) | Integer bitmask controlling data fusion and aiding methods Comment: Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available 2 : Set to true to inhibit IMU delta velocity bias estimation 3 : Set to true to enable vision position fusion 4 : Set to true to enable vision yaw fusion. Cannot be used if bit position 7 is true. 5 : Set to true to enable multi-rotor drag specific force fusion 6 : set to true if the EV observations are in a non NED reference frame and need to be rotated before being used 7 : Set to true to enable GPS yaw fusion. Cannot be used if bit position 4 is true. Bitmask:
Reboot required: true | 0 > 255 | 1 | |
EKF2_ANGERR_INIT (FLOAT) | 1-sigma tilt angle uncertainty after gravity vector alignment Reboot required: true | 0.0 > 0.5 | 0.1 | rad |
EKF2_ARSP_THR (FLOAT) | 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 | 0.0 > ? | 0.0 | m/s |
EKF2_ASPD_MAX (FLOAT) | Upper limit on airspeed along individual axes used to correct baro for position error effects | 5.0 > 50.0 | 20.0 | m/s |
EKF2_ASP_DELAY (FLOAT) | Airspeed measurement delay relative to IMU measurements Reboot required: true | 0 > 300 | 100 | ms |
EKF2_AVEL_DELAY (FLOAT) | Auxillary Velocity Estimate (e.g from a landing target) delay relative to IMU measurements Reboot required: true | 0 > 300 | 5 | ms |
EKF2_BARO_DELAY (FLOAT) | Barometer measurement delay relative to IMU measurements Reboot required: true | 0 > 300 | 0 | ms |
EKF2_BARO_GATE (FLOAT) | Gate size for barometric and GPS height fusion Comment: Sets the number of standard deviations used by the innovation consistency test. | 1.0 > ? | 5.0 | SD |
EKF2_BARO_NOISE (FLOAT) | Measurement noise for barometric altitude | 0.01 > 15.0 | 2.0 | m |
EKF2_BCOEF_X (FLOAT) | 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 | 1.0 > 100.0 | 25.0 | kg/m2 |
EKF2_BCOEF_Y (FLOAT) | 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 | 1.0 > 100.0 | 25.0 | kg/m2 |
EKF2_BETA_GATE (FLOAT) | Gate size for synthetic sideslip fusion Comment: Sets the number of standard deviations used by the innovation consistency test. | 1.0 > ? | 5.0 | SD |
EKF2_BETA_NOISE (FLOAT) | Noise for synthetic sideslip fusion | 0.1 > 1.0 | 0.3 | m/s |
EKF2_DECL_TYPE (INT32) | Integer bitmask controlling handling of magnetic declination Comment: Set bits in the following positions to enable functions. 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms. 2 : Set to true to always use the declination as an observation when 3-axis magnetometer fusion is being used. Bitmask:
Reboot required: true | 0 > 7 | 7 | |
EKF2_DRAG_NOISE (FLOAT) | 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 | 0.5 > 10.0 | 2.5 | (m/sec2)2 |
EKF2_EAS_NOISE (FLOAT) | Measurement noise for airspeed fusion | 0.5 > 5.0 | 1.4 | m/s |
EKF2_EVA_NOISE (FLOAT) | Measurement noise for vision angle observations used when the vision system does not supply error estimates | 0.01 > ? | 0.05 | rad |
EKF2_EVP_NOISE (FLOAT) | Measurement noise for vision position observations used when the vision system does not supply error estimates | 0.01 > ? | 0.05 | m |
EKF2_EV_DELAY (FLOAT) | Vision Position Estimator delay relative to IMU measurements Reboot required: true | 0 > 300 | 175 | ms |
EKF2_EV_GATE (FLOAT) | Gate size for vision estimate fusion Comment: Sets the number of standard deviations used by the innovation consistency test. | 1.0 > ? | 5.0 | SD |
EKF2_EV_POS_X (FLOAT) | X position of VI sensor focal point in body frame | 0.0 | m | |
EKF2_EV_POS_Y (FLOAT) | Y position of VI sensor focal point in body frame | 0.0 | m | |
EKF2_EV_POS_Z (FLOAT) | Z position of VI sensor focal point in body frame | 0.0 | m | |
EKF2_FUSE_BETA (INT32) | Boolean determining if synthetic sideslip measurements should fused Comment: A value of 1 indicates that fusion is active Both sideslip fusion and airspeed fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_ARSP_THR to activate airspeed fusion. | 0 | ||
EKF2_GBIAS_INIT (FLOAT) | 1-sigma IMU gyro switch-on bias Reboot required: true | 0.0 > 0.2 | 0.1 | rad/sec |
EKF2_GND_EFF_DZ (FLOAT) | Baro deadzone range for height fusion Comment: Sets the value of deadzone applied to negative baro innovations. Deadzone is enabled when EKF2_GND_EFF_DZ > 0. | 0.0 > 10.0 | 0.0 | M |
EKF2_GND_MAX_HGT (FLOAT) | Height above ground level for ground effect zone Comment: Sets the maximum distance to the ground level where negative baro innovations are expected. | 0.0 > 5.0 | 0.5 | M |
EKF2_GPS_CHECK (INT32) | Integer bitmask controlling GPS checks Comment: Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Minimum required sat count set by EKF2_REQ_NSATS 1 : Minimum required GDoP set by EKF2_REQ_GDOP 2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH 3 : Maximum allowed vertical position error set by EKF2_REQ_EPV 4 : Maximum allowed speed error set by EKF2_REQ_SACC 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT Bitmask:
| 0 > 511 | 245 | |
EKF2_GPS_DELAY (FLOAT) | GPS measurement delay relative to IMU measurements Reboot required: true | 0 > 300 | 110 | ms |
EKF2_GPS_MASK (INT32) | Multi GPS Blending Control Mask Comment: Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance. 0 : Set to true to use speed accuracy 1 : Set to true to use horizontal position accuracy 2 : Set to true to use vertical position accuracy Bitmask:
| 0 > 7 | 0 | |
EKF2_GPS_POS_X (FLOAT) | X position of GPS antenna in body frame | 0.0 | m | |
EKF2_GPS_POS_Y (FLOAT) | Y position of GPS antenna in body frame | 0.0 | m | |
EKF2_GPS_POS_Z (FLOAT) | Z position of GPS antenna in body frame | 0.0 | m | |
EKF2_GPS_P_GATE (FLOAT) | Gate size for GPS horizontal position fusion Comment: Sets the number of standard deviations used by the innovation consistency test. | 1.0 > ? | 5.0 | SD |
EKF2_GPS_P_NOISE (FLOAT) | Measurement noise for gps position | 0.01 > 10.0 | 0.5 | m |
EKF2_GPS_TAU (FLOAT) | Multi GPS Blending Time Constant Comment: Sets the longest time constant that will be applied to the calculation of GPS position and height offsets used to correct data from multiple GPS data for steady state position differences. | 1.0 > 100.0 | 10.0 | s |
EKF2_GPS_V_GATE (FLOAT) | Gate size for GPS velocity fusion Comment: Sets the number of standard deviations used by the innovation consistency test. | 1.0 > ? | 5.0 | SD |
EKF2_GPS_V_NOISE (FLOAT) | Measurement noise for gps horizontal velocity | 0.01 > 5.0 | 0.5 | m/s |
EKF2_GYR_B_NOISE (FLOAT) | Process noise for IMU rate gyro bias prediction | 0.0 > 0.01 | 1.0e-3 | rad/s2 |
EKF2_GYR_NOISE (FLOAT) | Rate gyro noise for covariance prediction | 0.0001 > 0.1 | 1.5e-2 | rad/s |
EKF2_HDG_GATE (FLOAT) | Gate size for magnetic heading fusion Comment: Sets the number of standard deviations used by the innovation consistency test. | 1.0 > ? | 2.6 | SD |
EKF2_HEAD_NOISE (FLOAT) | Measurement noise for magnetic heading fusion | 0.01 > 1.0 | 0.3 | rad |
EKF2_HGT_MODE (INT32) | Determines the primary source of height data used by the EKF Comment: The range sensor option should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. Values:
Reboot required: true | 0 | ||
EKF2_IMU_POS_X (FLOAT) | X position of IMU in body frame | 0.0 | m | |
EKF2_IMU_POS_Y (FLOAT) | Y position of IMU in body frame | 0.0 | m | |
EKF2_IMU_POS_Z (FLOAT) | Z position of IMU in body frame | 0.0 | m | |
EKF2_MAGBIAS_ID (INT32) | ID of Magnetometer the learned bias is for Reboot required: true | 0 | ||
EKF2_MAGBIAS_X (FLOAT) | Learned value of magnetometer X axis bias. This is the amount of X-axis magnetometer bias learned by the EKF and saved from the last flight. It must be set to zero if the ground based magnetometer calibration is repeated Reboot required: true | -0.5 > 0.5 | 0.0 | mGauss |
EKF2_MAGBIAS_Y (FLOAT) | Learned value of magnetometer Y axis bias. This is the amount of Y-axis magnetometer bias learned by the EKF and saved from the last flight. It must be set to zero if the ground based magnetometer calibration is repeated Reboot required: true | -0.5 > 0.5 | 0.0 | mGauss |
EKF2_MAGBIAS_Z (FLOAT) | Learned value of magnetometer Z axis bias. This is the amount of Z-axis magnetometer bias learned by the EKF and saved from the last flight. It must be set to zero if the ground based magnetometer calibration is repeated Reboot required: true | -0.5 > 0.5 | 0.0 | mGauss |
EKF2_MAGB_K (FLOAT) | Maximum fraction of learned mag bias saved at each disarm. Smaller values make the saved mag bias learn slower from flight to flight. Larger values make it learn faster. Must be > 0.0 and <= 1.0 | 0.0 > 1.0 | 0.2 | |
EKF2_MAGB_VREF (FLOAT) | State variance assumed for magnetometer bias storage. This is a reference variance used to calculate the fraction of learned magnetometer bias that will be used to update the stored value. Smaller values will make the stored bias data adjust more slowly from flight to flight. Larger values will make it adjust faster Reboot required: true | 2.5E-7 | mGauss2 | |
EKF2_MAG_ACCLIM (FLOAT) | 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 | 0.0 > 5.0 | 0.5 | m/s2 |
EKF2_MAG_B_NOISE (FLOAT) | Process noise for body magnetic field prediction | 0.0 > 0.1 | 1.0e-4 | Gauss/s |
EKF2_MAG_DECL (FLOAT) | Magnetic declination | 0 | deg | |
EKF2_MAG_DELAY (FLOAT) | Magnetometer measurement delay relative to IMU measurements Reboot required: true | 0 > 300 | 0 | ms |
EKF2_MAG_E_NOISE (FLOAT) | Process noise for earth magnetic field prediction | 0.0 > 0.1 | 1.0e-3 | Gauss/s |
EKF2_MAG_GATE (FLOAT) | Gate size for magnetometer XYZ component fusion Comment: Sets the number of standard deviations used by the innovation consistency test. | 1.0 > ? | 3.0 | SD |
EKF2_MAG_NOISE (FLOAT) | Measurement noise for magnetometer 3-axis fusion | 0.001 > 1.0 | 5.0e-2 | Gauss |
EKF2_MAG_TYPE (INT32) | Type of magnetometer fusion Comment: Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fuson of magnetomer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to ‘Automatic’ magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight with fallback to magnetic heading fusion if there is insufficient motion to make yaw or magnetic field states observable. If set to ‘Magnetic heading’ magnetic heading fusion is used at all times If set to ‘3-axis’ 3-axis field fusion is used at all times. If set to ‘VTOL custom’ the behaviour is the same as ‘Automatic’, but if fusing airspeed, magnetometer fusion is only allowed to modify the magnetic field states. This can be used by VTOL platforms with large magnetic field disturbances to prevent incorrect bias states being learned during forward flight operation which can adversely affect estimation accuracy after transition to hovering flight. If set to ‘MC custom’ the behaviour is the same as ‘Automatic, but if there are no earth frame position or velocity observations being used, the magnetometer will not be used. This enables vehicles to operate with no GPS in environments where the magnetic field cannot be used to provide a heading reference. Prior to flight, the yaw angle is assumed to be constant if movement tests controlled by the EKF2_MOVE_TEST parameter indicate that the vehicle is static. This allows the vehicle to be placed on the ground to learn the yaw gyro bias prior to flight. If set to ‘None’ the magnetometer will not be used under any circumstance. Other sources of yaw may be used if selected via the EKF2_AID_MASK parameter. Values:
Reboot required: true | 0 | ||
EKF2_MAG_YAWLIM (FLOAT) | 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 | 0.0 > 1.0 | 0.25 | rad/s |
EKF2_MIN_OBS_DT (INT32) | 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 Reboot required: true | 10 > 50 | 20 | ms |
EKF2_MIN_RNG (FLOAT) | Minimum valid range for the range finder | 0.01 > ? | 0.1 | m |
EKF2_MOVE_TEST (FLOAT) | Vehicle movement test threshold Comment: Scales the threshold tests applied to IMU data used to determine if the vehicle is static or moving. See parameter descriptions for EKF2_GPS_CHECK and EKF2_MAG_TYPE for further information on the functionality affected by this parameter. | 0.1 > 10.0 | 1.0 | |
EKF2_NOAID_NOISE (FLOAT) | Measurement noise for non-aiding position hold | 0.5 > 50.0 | 10.0 | m |
EKF2_NOAID_TOUT (INT32) | Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid | 500000 > 10000000 | 5000000 | uSec |
EKF2_OF_DELAY (FLOAT) | Optical flow measurement delay relative to IMU measurements Assumes measurement is timestamped at trailing edge of integration period Reboot required: true | 0 > 300 | 5 | ms |
EKF2_OF_GATE (FLOAT) | Gate size for optical flow fusion Comment: Sets the number of standard deviations used by the innovation consistency test. | 1.0 > ? | 3.0 | SD |
EKF2_OF_N_MAX (FLOAT) | Measurement noise for the optical flow sensor Comment: (when it’s reported quality metric is at the minimum set by EKF2_OF_QMIN). The following condition must be met: EKF2_OF_N_MAXN >= EKF2_OF_N_MIN | 0.05 > ? | 0.5 | rad/s |
EKF2_OF_N_MIN (FLOAT) | Measurement noise for the optical flow sensor when it’s reported quality metric is at the maximum | 0.05 > ? | 0.15 | rad/s |
EKF2_OF_POS_X (FLOAT) | X position of optical flow focal point in body frame | 0.0 | m | |
EKF2_OF_POS_Y (FLOAT) | Y position of optical flow focal point in body frame | 0.0 | m | |
EKF2_OF_POS_Z (FLOAT) | Z position of optical flow focal point in body frame | 0.0 | m | |
EKF2_OF_QMIN (INT32) | Optical Flow data will only be used if the sensor reports a quality metric >= EKF2_OF_QMIN | 0 > 255 | 1 | |
EKF2_PCOEF_XN (FLOAT) | 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 | -0.5 > 0.5 | 0.0 | |
EKF2_PCOEF_XP (FLOAT) | 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 | -0.5 > 0.5 | 0.0 | |
EKF2_PCOEF_YN (FLOAT) | 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 | -0.5 > 0.5 | 0.0 | |
EKF2_PCOEF_YP (FLOAT) | 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 | -0.5 > 0.5 | 0.0 | |
EKF2_PCOEF_Z (FLOAT) | 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 | -0.5 > 0.5 | 0.0 | |
EKF2_REQ_EPH (FLOAT) | Required EPH to use GPS | 2 > 100 | 3.0 | m |
EKF2_REQ_EPV (FLOAT) | Required EPV to use GPS | 2 > 100 | 5.0 | m |
EKF2_REQ_GDOP (FLOAT) | Required GDoP to use GPS | 1.5 > 5.0 | 2.5 | |
EKF2_REQ_GPS_H (FLOAT) | Required GPS health time on startup Comment: Minimum continuous period without GPS failure required to mark a healthy GPS status. It can be reduced to speed up initialization, but it’s recommended to keep this unchanged for a vehicle. Reboot required: true | 0.1 > ? | 10.0 | s |
EKF2_REQ_HDRIFT (FLOAT) | Maximum horizontal drift speed to use GPS | 0.1 > 1.0 | 0.1 | m/s |
EKF2_REQ_NSATS (INT32) | Required satellite count to use GPS | 4 > 12 | 6 | |
EKF2_REQ_SACC (FLOAT) | Required speed accuracy to use GPS | 0.5 > 5.0 | 0.5 | m/s |
EKF2_REQ_VDRIFT (FLOAT) | Maximum vertical drift speed to use GPS | 0.1 > 1.5 | 0.2 | m/s |
EKF2_RNG_AID (INT32) | Range sensor aid Comment: If this parameter is enabled then the estimator will make use of the range finder measurements to estimate it’s height even if range sensor is not the primary height source. It will only do so if conditions for range measurement fusion are met. This enables the range finder to be used during low speed and low altitude operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX. If vehicle motion causes repeated switching between the primary height sensor and range finder, an offset in the local position origin can accumulate. Also range finder measurements are less reliable and can experience unexpected errors. For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors are severe enough to cause problems with landing and takeoff. Values:
| 0 | ||
EKF2_RNG_A_HMAX (FLOAT) | Maximum absolute altitude (height above ground level) allowed for range aid mode Comment: If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate it’s height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled). | 1.0 > 10.0 | 5.0 | m |
EKF2_RNG_A_IGATE (FLOAT) | Gate size used for innovation consistency checks for range aid fusion Comment: A lower value means HAGL needs to be more stable in order to use range finder for height estimation in range aid mode | 0.1 > 5.0 | 1.0 | SD |
EKF2_RNG_A_VMAX (FLOAT) | Maximum horizontal velocity allowed for range aid mode Comment: If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate it’s height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled). | 0.1 > 2 | 1.0 | m/s |
EKF2_RNG_DELAY (FLOAT) | Range finder measurement delay relative to IMU measurements Reboot required: true | 0 > 300 | 5 | ms |
EKF2_RNG_GATE (FLOAT) | Gate size for range finder fusion Comment: Sets the number of standard deviations used by the innovation consistency test. | 1.0 > ? | 5.0 | SD |
EKF2_RNG_NOISE (FLOAT) | Measurement noise for range finder fusion | 0.01 > ? | 0.1 | m |
EKF2_RNG_PITCH (FLOAT) | Range sensor pitch offset | -0.75 > 0.75 | 0.0 | rad |
EKF2_RNG_POS_X (FLOAT) | X position of range finder origin in body frame | 0.0 | m | |
EKF2_RNG_POS_Y (FLOAT) | Y position of range finder origin in body frame | 0.0 | m | |
EKF2_RNG_POS_Z (FLOAT) | Z position of range finder origin in body frame | 0.0 | m | |
EKF2_RNG_SFE (FLOAT) | Range finder range dependant noise scaler Comment: Specifies the increase in range finder noise with range. | 0.0 > 0.2 | 0.05 | m/m |
EKF2_TAS_GATE (FLOAT) | Gate size for TAS fusion Comment: Sets the number of standard deviations used by the innovation consistency test. | 1.0 > ? | 3.0 | SD |
EKF2_TAU_POS (FLOAT) | Time constant of the position output prediction and smoothing filter. Controls how tightly the output track the EKF states | 0.1 > 1.0 | 0.25 | s |
EKF2_TAU_VEL (FLOAT) | Time constant of the velocity output prediction and smoothing filter | ? > 1.0 | 0.25 | s |
EKF2_TERR_GRAD (FLOAT) | Magnitude of terrain gradient | 0.0 > ? | 0.5 | m/m |
EKF2_TERR_NOISE (FLOAT) | Terrain altitude process noise - accounts for instability in vehicle height estimate | 0.5 > ? | 5.0 | m/s |
EKF2_WIND_NOISE (FLOAT) | Process noise for wind velocity prediction | 0.0 > 1.0 | 1.0e-1 | m/s/s |
Events
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
EV_TSK_RC_LOSS (INT32) | RC Loss Alarm Comment: Enable/disable event task for RC Loss. When enabled, an alarm tune will be played via buzzer or ESCs, if supported. The alarm will sound after a disarm, if the vehicle was previously armed and only if the vehicle had RC signal at some point. Particularly useful for locating crashed drones without a GPS sensor. Reboot required: true | 0 | ||
EV_TSK_STAT_DIS (INT32) | Status Display Comment: Enable/disable event task for displaying the vehicle status using arm-mounted LEDs. When enabled and if the vehicle supports it, LEDs will flash indicating various vehicle status changes. Currently PX4 has not implemented any specific status events. - Reboot required: true | 0 |
FW Attitude Control
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
FW_ACRO_X_MAX (FLOAT) | Acro body x max rate Comment: This is the rate the controller is trying to achieve if the user applies full roll stick input in acro mode. | 45 > 720 | 90 | degrees |
FW_ACRO_Y_MAX (FLOAT) | Acro body y max rate Comment: This is the body y rate the controller is trying to achieve if the user applies full pitch stick input in acro mode. | 45 > 720 | 90 | degrees |
FW_ACRO_Z_MAX (FLOAT) | Acro body z max rate Comment: This is the body z rate the controller is trying to achieve if the user applies full yaw stick input in acro mode. | 10 > 180 | 45 | degrees |
FW_ARSP_MODE (INT32) | Airspeed mode Comment: For small wings or VTOL without airspeed sensor this parameter can be used to enable flying without an airspeed reading Values:
| 0 | ||
FW_BAT_SCALE_EN (INT32) | Whether to scale throttle by battery power level Comment: This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The fixed wing should constantly behave as if it was fully charged with reduced max thrust at lower battery percentages. i.e. if cruise speed is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery. | 0 | ||
FW_DTRIM_P_FLPS (FLOAT) | Pitch trim increment for flaps configuration Comment: This increment is added to the pitch trim whenever flaps are fully deployed. | -0.25 > 0.25 (0.01) | 0.0 | |
FW_DTRIM_P_VMAX (FLOAT) | Pitch trim increment at maximum airspeed Comment: This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX. | -0.25 > 0.25 (0.01) | 0.0 | |
FW_DTRIM_P_VMIN (FLOAT) | Pitch trim increment at minimum airspeed Comment: This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN. | -0.25 > 0.25 (0.01) | 0.0 | |
FW_DTRIM_R_FLPS (FLOAT) | Roll trim increment for flaps configuration Comment: This increment is added to TRIM_ROLL whenever flaps are fully deployed. | -0.25 > 0.25 (0.01) | 0.0 | |
FW_DTRIM_R_VMAX (FLOAT) | Roll trim increment at maximum airspeed Comment: This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX. | -0.25 > 0.25 (0.01) | 0.0 | |
FW_DTRIM_R_VMIN (FLOAT) | Roll trim increment at minimum airspeed Comment: This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN. | -0.25 > 0.25 (0.01) | 0.0 | |
FW_DTRIM_Y_VMAX (FLOAT) | Yaw trim increment at maximum airspeed Comment: This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX. | -0.25 > 0.25 (0.01) | 0.0 | |
FW_DTRIM_Y_VMIN (FLOAT) | Yaw trim increment at minimum airspeed Comment: This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN. | -0.25 > 0.25 (0.01) | 0.0 | |
FW_FLAPERON_SCL (FLOAT) | Scale factor for flaperons | 0.0 > 1.0 (0.01) | 0.0 | norm |
FW_FLAPS_LND_SCL (FLOAT) | Flaps setting during landing Comment: Sets a fraction of full flaps (FW_FLAPS_SCL) during landing | 0.0 > 1.0 (0.01) | 1.0 | norm |
FW_FLAPS_SCL (FLOAT) | Scale factor for flaps | 0.0 > 1.0 (0.01) | 1.0 | norm |
FW_FLAPS_TO_SCL (FLOAT) | Flaps setting during take-off Comment: Sets a fraction of full flaps (FW_FLAPS_SCL) during take-off | 0.0 > 1.0 (0.01) | 0.0 | norm |
FW_MAN_P_MAX (FLOAT) | Max manual pitch Comment: Max pitch for manual control in attitude stabilized mode | 0.0 > 90.0 (0.5) | 45.0 | deg |
FW_MAN_P_SC (FLOAT) | Manual pitch scale Comment: Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. | 0.0 > ? (0.01) | 1.0 | norm |
FW_MAN_R_MAX (FLOAT) | Max manual roll Comment: Max roll for manual control in attitude stabilized mode | 0.0 > 90.0 (0.5) | 45.0 | deg |
FW_MAN_R_SC (FLOAT) | Manual roll scale Comment: Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. | 0.0 > 1.0 (0.01) | 1.0 | norm |
FW_MAN_Y_SC (FLOAT) | Manual yaw scale Comment: Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. | 0.0 > ? (0.01) | 1.0 | norm |
FW_PR_FF (FLOAT) | Pitch rate feed forward Comment: Direct feed forward from rate setpoint to control surface output | 0.0 > 10.0 (0.05) | 0.5 | %/rad/s |
FW_PR_I (FLOAT) | Pitch rate integrator gain Comment: This gain defines how much control response will result out of a steady state error. It trims any constant error. | 0.005 > 0.5 (0.005) | 0.1 | %/rad |
FW_PR_IMAX (FLOAT) | Pitch rate integrator limit Comment: The portion of the integrator part in the control surface deflection is limited to this value | 0.0 > 1.0 (0.05) | 0.4 | |
FW_PR_P (FLOAT) | Pitch rate proportional gain Comment: This defines how much the elevator input will be commanded depending on the current body angular rate error. | 0.005 > 1.0 (0.005) | 0.08 | %/rad/s |
FW_PSP_OFF (FLOAT) | Pitch setpoint offset Comment: An airframe specific offset of the pitch setpoint in degrees, the value is added to the pitch setpoint and should correspond to the typical cruise speed of the airframe. | -90.0 > 90.0 (0.5) | 0.0 | deg |
FW_P_RMAX_NEG (FLOAT) | Maximum negative / down pitch rate Comment: This limits the maximum pitch down up angular rate the controller will output (in degrees per second). | 0.0 > 90.0 (0.5) | 60.0 | deg/s |
FW_P_RMAX_POS (FLOAT) | Maximum positive / up pitch rate Comment: This limits the maximum pitch up angular rate the controller will output (in degrees per second). | 0.0 > 90.0 (0.5) | 60.0 | deg/s |
FW_P_TC (FLOAT) | Attitude pitch time constant Comment: This defines the latency between a pitch step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed. | 0.2 > 1.0 (0.05) | 0.4 | s |
FW_RATT_TH (FLOAT) | Threshold for Rattitude mode Comment: Manual input needed in order to override attitude control rate setpoints and instead pass manual stick inputs as rate setpoints | 0.0 > 1.0 (0.01) | 0.8 | |
FW_RLL_TO_YAW_FF (FLOAT) | Roll control to yaw control feedforward gain Comment: This gain can be used to counteract the “adverse yaw” effect for fixed wings. When the plane enters a roll it will tend to yaw the nose out of the turn. This gain enables the use of a yaw actuator (rudder, airbrakes, …) to counteract this effect. | 0.0 > ? (0.01) | 0.0 | |
FW_RR_FF (FLOAT) | Roll rate feed forward Comment: Direct feed forward from rate setpoint to control surface output. Use this to obtain a tigher response of the controller without introducing noise amplification. | 0.0 > 10.0 (0.05) | 0.5 | %/rad/s |
FW_RR_I (FLOAT) | Roll rate integrator Gain Comment: This gain defines how much control response will result out of a steady state error. It trims any constant error. | 0.005 > 0.2 (0.005) | 0.1 | %/rad |
FW_RR_IMAX (FLOAT) | Roll integrator anti-windup Comment: The portion of the integrator part in the control surface deflection is limited to this value. | 0.0 > 1.0 (0.05) | 0.2 | |
FW_RR_P (FLOAT) | Roll rate proportional Gain Comment: This defines how much the aileron input will be commanded depending on the current body angular rate error. | 0.005 > 1.0 (0.005) | 0.05 | %/rad/s |
FW_RSP_OFF (FLOAT) | Roll setpoint offset Comment: An airframe specific offset of the roll setpoint in degrees, the value is added to the roll setpoint and should correspond to the typical cruise speed of the airframe. | -90.0 > 90.0 (0.5) | 0.0 | deg |
FW_R_RMAX (FLOAT) | Maximum roll rate Comment: This limits the maximum roll rate the controller will output (in degrees per second). | 0.0 > 90.0 (0.5) | 70.0 | deg/s |
FW_R_TC (FLOAT) | Attitude Roll Time Constant Comment: This defines the latency between a roll step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed. | 0.4 > 1.0 (0.05) | 0.4 | s |
FW_WR_FF (FLOAT) | Wheel steering rate feed forward Comment: Direct feed forward from rate setpoint to control surface output | 0.0 > 10.0 (0.05) | 0.2 | %/rad/s |
FW_WR_I (FLOAT) | Wheel steering rate integrator gain Comment: This gain defines how much control response will result out of a steady state error. It trims any constant error. | 0.005 > 0.5 (0.005) | 0.1 | %/rad |
FW_WR_IMAX (FLOAT) | Wheel steering rate integrator limit Comment: The portion of the integrator part in the control surface deflection is limited to this value | 0.0 > 1.0 (0.05) | 1.0 | |
FW_WR_P (FLOAT) | Wheel steering rate proportional gain Comment: This defines how much the wheel steering input will be commanded depending on the current body angular rate error. | 0.005 > 1.0 (0.005) | 0.5 | %/rad/s |
FW_W_EN (INT32) | Enable wheel steering controller | 0 | ||
FW_W_RMAX (FLOAT) | Maximum wheel steering rate Comment: This limits the maximum wheel steering rate the controller will output (in degrees per second). | 0.0 > 90.0 (0.5) | 30.0 | deg/s |
FW_YR_FF (FLOAT) | Yaw rate feed forward Comment: Direct feed forward from rate setpoint to control surface output | 0.0 > 10.0 (0.05) | 0.3 | %/rad/s |
FW_YR_I (FLOAT) | Yaw rate integrator gain Comment: This gain defines how much control response will result out of a steady state error. It trims any constant error. | 0.0 > 50.0 (0.5) | 0.1 | %/rad |
FW_YR_IMAX (FLOAT) | Yaw rate integrator limit Comment: The portion of the integrator part in the control surface deflection is limited to this value | 0.0 > 1.0 (0.05) | 0.2 | |
FW_YR_P (FLOAT) | Yaw rate proportional gain Comment: This defines how much the rudder input will be commanded depending on the current body angular rate error. | 0.005 > 1.0 (0.005) | 0.05 | %/rad/s |
FW_Y_RMAX (FLOAT) | Maximum yaw rate Comment: This limits the maximum yaw rate the controller will output (in degrees per second). | 0.0 > 90.0 (0.5) | 50.0 | deg/s |
FW L1 Control
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
FW_CLMBOUT_DIFF (FLOAT) | Climbout Altitude difference Comment: If the altitude error exceeds this parameter, the system will climb out with maximum throttle and minimum airspeed until it is closer than this distance to the desired altitude. Mostly used for takeoff waypoints / modes. Set to 0 to disable climbout mode (not recommended). | 0.0 > 150.0 (0.5) | 10.0 | m |
FW_L1_DAMPING (FLOAT) | L1 damping Comment: Damping factor for L1 control. | 0.6 > 0.9 (0.05) | 0.75 | |
FW_L1_PERIOD (FLOAT) | L1 period Comment: This is the L1 distance and defines the tracking point ahead of the aircraft its following. A value of 18-25 meters works for most aircraft. Shorten slowly during tuning until response is sharp without oscillation. | 12.0 > 50.0 (0.5) | 20.0 | m |
FW_L1_R_SLEW_MAX (FLOAT) | L1 controller roll slew rate limit Comment: The maxium change in roll angle setpoint per second. | 0 > ? (1) | 90.0 | deg/s |
FW_LND_AIRSPD_SC (FLOAT) | Min. airspeed scaling factor for landing Comment: Multiplying this factor with the minimum airspeed of the plane gives the target airspeed the landing approach. FW_AIRSPD_MIN * FW_LND_AIRSPD_SC | 1.0 > 1.5 (0.01) | 1.3 | norm |
FW_LND_ANG (FLOAT) | Landing slope angle | 1.0 > 15.0 (0.5) | 5.0 | deg |
FW_LND_EARLYCFG (INT32) | Early landing configuration deployment Comment: When disabled, the landing configuration (flaps, landing airspeed, etc.) is only activated on the final approach to landing. When enabled, it is already activated when entering the final loiter-down (loiter-to-alt) waypoint before the landing approach. This shifts the (often large) altitude and airspeed errors caused by the configuration change away from the ground such that these are not so critical. It also gives the controller enough time to adapt to the new configuration such that the landing approach starts with a cleaner initial state. | 0 | ||
FW_LND_FLALT (FLOAT) | Landing flare altitude (relative to landing altitude) | 0.0 > 25.0 (0.5) | 3.0 | m |
FW_LND_FL_PMAX (FLOAT) | Flare, maximum pitch Comment: Maximum pitch during flare, a positive sign means nose up Applied once FW_LND_FLALT is reached | 0 > 45.0 (0.5) | 15.0 | deg |
FW_LND_FL_PMIN (FLOAT) | Flare, minimum pitch Comment: Minimum pitch during flare, a positive sign means nose up Applied once FW_LND_FLALT is reached | 0 > 15.0 (0.5) | 2.5 | deg |
FW_LND_HHDIST (FLOAT) | Landing heading hold horizontal distance. Set to 0 to disable heading hold | 0 > 30.0 (0.5) | 15.0 | m |
FW_LND_HVIRT (FLOAT) |
| 1.0 > 15.0 (0.5) | 10.0 | m |
FW_LND_THRTC_SC (FLOAT) | Throttle time constant factor for landing Comment: Set this parameter to less than 1.0 to make the TECS throttle loop react faster during landing than during normal flight (i.e. giving efficiency and low motor wear at high altitudes but control accuracy during landing). During landing, the TECS throttle time constant (FW_T_THRO_CONST) is multiplied by this value. | 0.2 > 1.0 (0.1) | 1.0 | |
FW_LND_TLALT (FLOAT) | Landing throttle limit altitude (relative landing altitude) Comment: Default of -1.0 lets the system default to applying throttle limiting at 2/3 of the flare altitude. | -1.0 > 30.0 (0.5) | -1.0 | m |
FW_LND_USETER (INT32) | Use terrain estimate during landing Comment: This is turned off by default and a waypoint or return altitude is normally used (or sea level for an arbitrary land position). | 0 | ||
FW_P_LIM_MAX (FLOAT) | Positive pitch limit Comment: The maximum positive pitch the controller will output. | 0.0 > 60.0 (0.5) | 45.0 | deg |
FW_P_LIM_MIN (FLOAT) | Negative pitch limit Comment: The minimum negative pitch the controller will output. | -60.0 > 0.0 (0.5) | -45.0 | deg |
FW_R_LIM (FLOAT) | Controller roll limit Comment: The maximum roll the controller will output. | 35.0 > 65.0 (0.5) | 50.0 | deg |
FW_THR_ALT_SCL (FLOAT) | Scale throttle by pressure change Comment: Automatically adjust throttle to account for decreased air density at higher altitudes. Start with a scale factor of 1.0 and adjust for different propulsion systems. When flying without airspeed sensor this will help to keep a constant performance over large altitude ranges. The default value of 0 will disable scaling. | 0.0 > 10.0 (0.1) | 0.0 | |
FW_THR_CRUISE (FLOAT) | Cruise throttle Comment: This is the throttle setting required to achieve the desired cruise speed. Most airframes have a value of 0.5-0.7. | 0.0 > 1.0 (0.01) | 0.6 | norm |
FW_THR_IDLE (FLOAT) | Idle throttle Comment: This is the minimum throttle while on the ground For aircraft with internal combustion engine this parameter should be set above desired idle rpm. | 0.0 > 0.4 (0.01) | 0.15 | norm |
FW_THR_LND_MAX (FLOAT) | Throttle limit during landing below throttle limit altitude Comment: During the flare of the autonomous landing process, this value will be set as throttle limit when the aircraft altitude is below FW_LND_TLALT. | 0.0 > 1.0 (0.01) | 1.0 | norm |
FW_THR_MAX (FLOAT) | Throttle limit max Comment: This is the maximum throttle % that can be used by the controller. For overpowered aircraft, this should be reduced to a value that provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX. | 0.0 > 1.0 (0.01) | 1.0 | norm |
FW_THR_MIN (FLOAT) | Throttle limit min Comment: This is the minimum throttle % that can be used by the controller. For electric aircraft this will normally be set to zero, but can be set to a small non-zero value if a folding prop is fitted to prevent the prop from folding and unfolding repeatedly in-flight or to provide some aerodynamic drag from a turning prop to improve the descent rate. For aircraft with internal combustion engine this parameter should be set for desired idle rpm. | 0.0 > 1.0 (0.01) | 0.0 | norm |
FW_THR_SLEW_MAX (FLOAT) | Throttle max slew rate Comment: Maximum slew rate for the commanded throttle | 0.0 > 1.0 | 0.0 |
FW Launch detection
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
LAUN_ALL_ON (INT32) | Launch detection | 0 | ||
LAUN_CAT_A (FLOAT) | Catapult accelerometer threshold Comment: LAUN_CAT_A for LAUN_CAT_T serves as threshold to trigger launch detection. | 0 > ? (0.5) | 30.0 | m/s/s |
LAUN_CAT_MDEL (FLOAT) | Motor delay Comment: Delay between starting attitude control and powering up the throttle (giving throttle control to the controller) Before this timespan is up the throttle will be set to FW_THR_IDLE, set to 0 to deactivate | 0.0 > 10.0 (0.5) | 0.0 | s |
LAUN_CAT_PMAX (FLOAT) | Maximum pitch before the throttle is powered up (during motor delay phase) Comment: This is an extra limit for the maximum pitch which is imposed in the phase before the throttle turns on. This allows to limit the maximum pitch angle during a bungee launch (make the launch less steep). | 0.0 > 45.0 (0.5) | 30.0 | deg |
LAUN_CAT_T (FLOAT) | Catapult time threshold Comment: LAUN_CAT_A for LAUN_CAT_T serves as threshold to trigger launch detection. | 0.0 > 5.0 (0.05) | 0.05 | s |
FW TECS
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
FW_AIRSPD_MAX (FLOAT) | Maximum Airspeed Comment: If the airspeed is above this value, the TECS controller will try to decrease airspeed more aggressively. | 0.0 > 40 (0.5) | 20.0 | m/s |
FW_AIRSPD_MIN (FLOAT) | Minimum Airspeed Comment: If the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. | 0.0 > 40 (0.5) | 10.0 | m/s |
FW_AIRSPD_TRIM (FLOAT) | Cruise Airspeed Comment: The fixed wing controller tries to fly at this airspeed. | 0.0 > 40 (0.5) | 15.0 | m/s |
FW_GND_SPD_MIN (FLOAT) | Minimum groundspeed Comment: The controller will increase the commanded airspeed to maintain this minimum groundspeed to the next waypoint. | 0.0 > 40 (0.5) | 5.0 | m/s |
FW_T_CLMB_MAX (FLOAT) | Maximum climb rate Comment: This is the best climb rate that the aircraft can achieve with the throttle set to THR_MAX and the airspeed set to the default value. For electric aircraft make sure this number can be achieved towards the end of flight when the battery voltage has reduced. The setting of this parameter can be checked by commanding a positive altitude change of 100m in loiter, RTL or guided mode. If the throttle required to climb is close to THR_MAX and the aircraft is maintaining airspeed, then this parameter is set correctly. If the airspeed starts to reduce, then the parameter is set to high, and if the throttle demand required to climb and maintain speed is noticeably less than FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or FW_THR_MAX reduced. | 1.0 > 15.0 (0.5) | 5.0 | m/s |
FW_T_HGT_OMEGA (FLOAT) | Complementary filter “omega” parameter for height Comment: This is the cross-over frequency (in radians/second) of the complementary filter used to fuse vertical acceleration and barometric height to obtain an estimate of height rate and height. Increasing this frequency weights the solution more towards use of the barometer, whilst reducing it weights the solution more towards use of the accelerometer data. | 1.0 > 10.0 (0.5) | 3.0 | rad/s |
FW_T_HRATE_FF (FLOAT) | Height rate feed forward | 0.0 > 1.0 (0.05) | 0.8 | |
FW_T_HRATE_P (FLOAT) | Height rate proportional factor | 0.0 > 1.0 (0.05) | 0.05 | |
FW_T_INTEG_GAIN (FLOAT) | Integrator gain Comment: This is the integrator gain on the control loop. Increasing this gain increases the speed at which speed and height offsets are trimmed out, but reduces damping and increases overshoot. Set this value to zero to completely disable all integrator action. | 0.0 > 2.0 (0.05) | 0.1 | |
FW_T_PTCH_DAMP (FLOAT) | Pitch damping factor Comment: This is the damping gain for the pitch demand loop. Increase to add damping to correct for oscillations in height. The default value of 0.0 will work well provided the pitch to servo controller has been tuned properly. | 0.0 > 2.0 (0.1) | 0.0 | |
FW_T_RLL2THR (FLOAT) | Roll -> Throttle feedforward Comment: Increasing this gain turn increases the amount of throttle that will be used to compensate for the additional drag created by turning. Ideally this should be set to approximately 10 x the extra sink rate in m/s created by a 45 degree bank turn. Increase this gain if the aircraft initially loses energy in turns and reduce if the aircraft initially gains energy in turns. Efficient high aspect-ratio aircraft (eg powered sailplanes) can use a lower value, whereas inefficient low aspect-ratio models (eg delta wings) can use a higher value. | 0.0 > 20.0 (0.5) | 15.0 | |
FW_T_SINK_MAX (FLOAT) | Maximum descent rate Comment: This sets the maximum descent rate that the controller will use. If this value is too large, the aircraft can over-speed on descent. This should be set to a value that can be achieved without exceeding the lower pitch angle limit and without over-speeding the aircraft. | 1.0 > 15.0 (0.5) | 5.0 | m/s |
FW_T_SINK_MIN (FLOAT) | Minimum descent rate Comment: This is the sink rate of the aircraft with the throttle set to THR_MIN and flown at the same airspeed as used to measure FW_T_CLMB_MAX. | 1.0 > 5.0 (0.5) | 2.0 | m/s |
FW_T_SPDWEIGHT (FLOAT) | Speed <—> Altitude priority Comment: This parameter adjusts the amount of weighting that the pitch control applies to speed vs height errors. Setting it to 0.0 will cause the pitch control to control height and ignore speed errors. This will normally improve height accuracy but give larger airspeed errors. Setting it to 2.0 will cause the pitch control loop to control speed and ignore height errors. This will normally reduce airspeed errors, but give larger height errors. The default value of 1.0 allows the pitch control to simultaneously control height and speed. Note to Glider Pilots - set this parameter to 2.0 (The glider will adjust its pitch angle to maintain airspeed, ignoring changes in height). | 0.0 > 2.0 (1.0) | 1.0 | |
FW_T_SPD_OMEGA (FLOAT) | Complementary filter “omega” parameter for speed Comment: This is the cross-over frequency (in radians/second) of the complementary filter used to fuse longitudinal acceleration and airspeed to obtain an improved airspeed estimate. Increasing this frequency weights the solution more towards use of the airspeed sensor, whilst reducing it weights the solution more towards use of the accelerometer data. | 1.0 > 10.0 (0.5) | 2.0 | rad/s |
FW_T_SRATE_P (FLOAT) | Speed rate P factor | 0.0 > 2.0 (0.01) | 0.02 | |
FW_T_THRO_CONST (FLOAT) | TECS Throttle time constant Comment: This is the time constant of the TECS throttle control algorithm (in seconds). Smaller values make it faster to respond, larger values make it slower to respond. | 1.0 > 10.0 (0.5) | 8.0 | s |
FW_T_THR_DAMP (FLOAT) | Throttle damping factor Comment: This is the damping gain for the throttle demand loop. Increase to add damping to correct for oscillations in speed and height. | 0.0 > 2.0 (0.1) | 0.5 | |
FW_T_TIME_CONST (FLOAT) | TECS time constant Comment: This is the time constant of the TECS control algorithm (in seconds). Smaller values make it faster to respond, larger values make it slower to respond. | 1.0 > 10.0 (0.5) | 5.0 | s |
FW_T_VERT_ACC (FLOAT) | Maximum vertical acceleration Comment: This is the maximum vertical acceleration (in m/s/s) either up or down that the controller will use to correct speed or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g) allows for reasonably aggressive pitch changes if required to recover from under-speed conditions. | 1.0 > 10.0 (0.5) | 7.0 | m/s/s |
Failure Detector
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
FD_FAIL_P (INT32) | FailureDetector Max Pitch Comment: Maximum pitch angle before FailureDetector triggers the attitude_failure flag If flight termination is enabled (@CBRK_FLIGHTTERM set to 0), the autopilot will terminate the flight and set all the outputs to their failsafe value as soon as the attitude_failure flag is set. Setting this parameter to 0 disables the check | 60 > 180 | 60 | degrees |
FD_FAIL_P_TTRI (FLOAT) | Pitch failure trigger time Comment: Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure. | 0.02 > 5 | 0.3 | s |
FD_FAIL_R (INT32) | FailureDetector Max Roll Comment: Maximum roll angle before FailureDetector triggers the attitude_failure flag If flight termination is enabled (@CBRK_FLIGHTTERM set to 0), the autopilot will terminate the flight and set all the outputs to their failsafe value as soon as the attitude_failure flag is set. Setting this parameter to 0 disables the check | 60 > 180 | 60 | degrees |
FD_FAIL_R_TTRI (FLOAT) | Roll failure trigger time Comment: Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure. | 0.02 > 5 | 0.3 | s |
Follow target
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
NAV_FT_DST (FLOAT) | Distance to follow target from Comment: The distance in meters to follow the target at | 1.0 > ? | 8.0 | meters |
NAV_FT_FS (INT32) | Side to follow target from Comment: The side to follow the target from (front right = 0, behind = 1, front = 2, front left = 3) | 0 > 3 | 1 | n/a |
NAV_FT_RS (FLOAT) | Dynamic filtering algorithm responsiveness to target movement lower numbers increase the responsiveness to changing long lat but also ignore less noise | 0.0 > 1.0 | 0.5 | n/a |
NAV_MIN_FT_HT (FLOAT) | Minimum follow target altitude Comment: The minimum height in meters relative to home for following a target | 8.0 > ? | 8.0 | meters |
GPS
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
GPS_1_CONFIG (INT32) | Serial Configuration for Main GPS Comment: Configure on which serial port to run Main GPS. Values:
Reboot required: true | 201 | ||
GPS_2_CONFIG (INT32) | Serial Configuration for Secondary GPS Comment: Configure on which serial port to run Secondary GPS. Values:
Reboot required: true | 0 | ||
GPS_DUMP_COMM (INT32) | Dump GPS communication to a file Comment: If this is set to 1, all GPS communication data will be published via uORB, and written to the log file as gps_dump message. Values:
| 0 > 1 | 0 | |
GPS_UBX_DYNMODEL (INT32) | u-blox GPS dynamic platform model Comment: u-blox receivers support different dynamic platform models to adjust the navigation engine to the expected application environment. Values:
Reboot required: true | 0 > 9 | 7 | |
GPS_YAW_OFFSET (FLOAT) | Heading/Yaw offset for dual antenna GPS Comment: Heading offset angle for dual antenna GPS setups that support heading estimation. (currently only for the Trimble MB-Two). Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the first antenna is in front. The offset angle increases counterclockwise. Set this to 90 if the first antenna is placed on the right side and the second on the left side of the vehicle. Reboot required: true | 0 > 360 | 0. | deg |
GPS Failure Navigation
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
NAV_GPSF_LT (FLOAT) | Loiter time Comment: The time in seconds the system should do open loop loiter and wait for GPS recovery before it goes into flight termination. Set to 0 to disable. | 0.0 > 3600.0 (1) | 0.0 | s |
NAV_GPSF_P (FLOAT) | Fixed pitch angle Comment: Pitch in degrees during the open loop loiter | -30.0 > 30.0 (0.5) | 0.0 | deg |
NAV_GPSF_R (FLOAT) | Fixed bank angle Comment: Roll in degrees during the loiter | 0.0 > 30.0 (0.5) | 15.0 | deg |
NAV_GPSF_TR (FLOAT) | Thrust Comment: Thrust value which is set during the open loop loiter | 0.0 > 1.0 (0.05) | 0.0 | norm |
Geofence
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
GF_ACTION (INT32) | Geofence violation action Comment: Note: Setting this value to 4 enables flight termination, which will kill the vehicle on violation of the fence. Due to the inherent danger of this, this function is disabled using a software circuit breaker, which needs to be reset to 0 to really shut down the system. Values:
| 0 > 4 | 1 | |
GF_ALTMODE (INT32) | Geofence altitude mode Comment: Select which altitude reference should be used 0 = WGS84, 1 = AMSL Values:
| 0 > 1 | 0 | |
GF_COUNT (INT32) | Geofence counter limit Comment: Set how many subsequent position measurements outside of the fence are needed before geofence violation is triggered | -1 > 10 (1) | -1 | |
GF_MAX_HOR_DIST (FLOAT) | Max horizontal distance in meters Comment: Maximum horizontal distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. | 0 > 10000 (1) | 0 | m |
GF_MAX_VER_DIST (FLOAT) | Max vertical distance in meters Comment: Maximum vertical distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. | 0 > 10000 (1) | 0 | m |
GF_SOURCE (INT32) | Geofence source Comment: Select which position source should be used. Selecting GPS instead of global position makes sure that there is no dependence on the position estimator 0 = global position, 1 = GPS Values:
| 0 > 1 | 0 |
Iridium SBD
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
ISBD_CONFIG (INT32) | Serial Configuration for Iridium (with MAVLink) Comment: Configure on which serial port to run Iridium (with MAVLink). Values:
Reboot required: true | 0 | ||
ISBD_READ_INT (INT32) | Satellite radio read interval. Only required to be nonzero if data is not sent using a ring call | 0 > 5000 | 0 | s |
ISBD_SBD_TIMEOUT (INT32) | Iridium SBD session timeout | 0 > 300 | 60 | s |
ISBD_STACK_TIME (INT32) | Time [ms] the Iridium driver will wait for additional mavlink messages to combine them into one SBD message Value 0 turns the functionality off | 0 > 500 | 0 | ms |
Land Detector
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
LNDFW_AIRSPD_MAX (FLOAT) | Airspeed max Comment: Maximum airspeed allowed in the landed state (m/s) | 4 > 20 | 8.00 | m/s |
LNDFW_VEL_XY_MAX (FLOAT) | Fixedwing max horizontal velocity Comment: Maximum horizontal velocity allowed in the landed state (m/s) | 0.5 > 10 | 5.0 | m/s |
LNDFW_VEL_Z_MAX (FLOAT) | Fixedwing max climb rate Comment: Maximum vertical velocity allowed in the landed state (m/s up and down) | 0.1 > 20 | 3.0 | m/s |
LNDFW_XYACC_MAX (FLOAT) | Fixedwing max horizontal acceleration Comment: Maximum horizontal (x,y body axes) acceleration allowed in the landed state (m/s^2) | 2 > 15 | 8.0 | m/s^2 |
LNDMC_ALT_MAX (FLOAT) | Maximum altitude for multicopters Comment: The system will obey this limit as a hard altitude limit. This setting will be consolidated with the GF_MAX_VER_DIST parameter. A negative value indicates no altitude limitation. | -1 > 10000 | -1.0 | m |
LNDMC_FFALL_THR (FLOAT) | Multicopter specific force threshold Comment: Multicopter threshold on the specific force measured by accelerometers in m/s^2 for free-fall detection | 0.1 > 10 | 2.0 | m/s^2 |
LNDMC_FFALL_TTRI (FLOAT) | Multicopter free-fall trigger time Comment: Seconds (decimal) that freefall conditions have to met before triggering a freefall. Minimal value is limited by LAND_DETECTOR_UPDATE_RATE=50Hz in landDetector.h | 0.02 > 5 | 0.3 | s |
LNDMC_LOW_T_THR (FLOAT) | Low throttle detection threshold Comment: Defines the commanded throttle value below which the land detector considers the vehicle to have “low thrust”. This is one condition that is used to detect the ground contact state. The value is calculated as val = (MPC_THR_HOVER - MPC_THR_MIN) * LNDMC_LOW_T_THR + MPC_THR_MIN Increase this value if the system takes long time to detect landing. | 0.1 > 0.9 | 0.3 | norm |
LNDMC_ROT_MAX (FLOAT) | Multicopter max rotation Comment: Maximum allowed angular velocity around each axis allowed in the landed state. | 20.0 | deg/s | |
LNDMC_XY_VEL_MAX (FLOAT) | Multicopter max horizontal velocity Comment: Maximum horizontal velocity allowed in the landed state (m/s) | 1.5 | m/s | |
LNDMC_Z_VEL_MAX (FLOAT) | Multicopter max climb rate Comment: Maximum vertical velocity allowed in the landed state (m/s up and down) | 0.50 | m/s | |
LND_FLIGHT_T_HI (INT32) | Total flight time in microseconds Comment: Total flight time of this autopilot. Higher 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. | 0 > ? | 0 | |
LND_FLIGHT_T_LO (INT32) | Total flight time in microseconds Comment: Total flight time of this autopilot. Lower 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. | 0 > ? | 0 |
Landing target Estimator
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
LTEST_ACC_UNC (FLOAT) | Acceleration uncertainty Comment: Variance of acceleration measurement used for landing target position prediction. Higher values results in tighter following of the measurements and more lenient outlier rejection | 0.01 > ? | 10.0 | (m/s^2)^2 |
LTEST_MEAS_UNC (FLOAT) | Landing target measurement uncertainty Comment: Variance of the landing target measurement from the driver. Higher values results in less agressive following of the measurement and a smoother output as well as fewer rejected measurements. | 0.005 | tan(rad)^2 | |
LTEST_MODE (INT32) | Landing target mode Comment: Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation. Mode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning. Mode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation. Values:
| 0 > 1 | 0 | |
LTEST_POS_UNC_IN (FLOAT) | Initial landing target position uncertainty Comment: Initial variance of the relative landing target position in x and y direction | 0.001 > ? | 0.1 | m^2 |
LTEST_SCALE_X (FLOAT) | Scale factor for sensor measurements in sensor x axis Comment: Landing target x measurements are scaled by this factor before being used | 0.01 > ? | 1.0 | |
LTEST_SCALE_Y (FLOAT) | Scale factor for sensor measurements in sensor y axis Comment: Landing target y measurements are scaled by this factor before being used | 0.01 > ? | 1.0 | |
LTEST_VEL_UNC_IN (FLOAT) | Initial landing target velocity uncertainty Comment: Initial variance of the relative landing target velocity in x and y direction | 0.001 > ? | 0.1 | (m/s)^2 |
Local Position Estimator
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
LPE_ACC_XY (FLOAT) | Accelerometer xy noise density Comment: Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error. | 0.00001 > 2 | 0.012 | m/s^2/sqrt(Hz) |
LPE_ACC_Z (FLOAT) | Accelerometer z noise density Comment: Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) | 0.00001 > 2 | 0.02 | m/s^2/sqrt(Hz) |
LPE_BAR_Z (FLOAT) | Barometric presssure altitude z standard deviation | 0.01 > 100 | 3.0 | m |
LPE_EPH_MAX (FLOAT) | Max EPH allowed for GPS initialization | 1.0 > 5.0 | 3.0 | m |
LPE_EPV_MAX (FLOAT) | Max EPV allowed for GPS initialization | 1.0 > 5.0 | 5.0 | m |
LPE_FAKE_ORIGIN (INT32) | 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 | 0 > 1 | 0 | |
LPE_FGYRO_HP (FLOAT) | Flow gyro high pass filter cut off frequency | 0 > 2 | 0.001 | Hz |
LPE_FLW_OFF_Z (FLOAT) | Optical flow z offset from center | -1 > 1 | 0.0 | m |
LPE_FLW_QMIN (INT32) | Optical flow minimum quality threshold | 0 > 255 | 150 | |
LPE_FLW_R (FLOAT) | Optical flow rotation (roll/pitch) noise gain | 0.1 > 10.0 | 7.0 | m/s / (rad) |
LPE_FLW_RR (FLOAT) | Optical flow angular velocity noise gain | 0.0 > 10.0 | 7.0 | m/s / (rad/s) |
LPE_FLW_SCALE (FLOAT) | Optical flow scale | 0.1 > 10.0 | 1.3 | m |
LPE_FUSION (INT32) | Integer bitmask controlling data fusion Comment: Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector) Bitmask:
| 0 > 255 | 145 | |
LPE_GPS_DELAY (FLOAT) | GPS delay compensaton | 0 > 0.4 | 0.29 | sec |
LPE_GPS_VXY (FLOAT) | GPS xy velocity standard deviation. EPV used if greater than this value | 0.01 > 2 | 0.25 | m/s |
LPE_GPS_VZ (FLOAT) | GPS z velocity standard deviation | 0.01 > 2 | 0.25 | m/s |
LPE_GPS_XY (FLOAT) | Minimum GPS xy standard deviation, uses reported EPH if greater | 0.01 > 5 | 1.0 | m |
LPE_GPS_Z (FLOAT) | Minimum GPS z standard deviation, uses reported EPV if greater | 0.01 > 200 | 3.0 | m |
LPE_LAND_VXY (FLOAT) | Land detector xy velocity standard deviation | 0.01 > 10.0 | 0.05 | m/s |
LPE_LAND_Z (FLOAT) | Land detector z standard deviation | 0.001 > 10.0 | 0.03 | m |
LPE_LAT (FLOAT) | Local origin latitude for nav w/o GPS | -90 > 90 | 47.397742 | deg |
LPE_LDR_OFF_Z (FLOAT) | Lidar z offset from center of vehicle +down | -1 > 1 | 0.00 | m |
LPE_LDR_Z (FLOAT) | Lidar z standard deviation | 0.01 > 1 | 0.03 | m |
LPE_LON (FLOAT) | Local origin longitude for nav w/o GPS | -180 > 180 | 8.545594 | deg |
LPE_LT_COV (FLOAT) | Minimum landing target standard covariance, uses reported covariance if greater | 0.0 > 10 | 0.0001 | m^2 |
LPE_PN_B (FLOAT) | Accel bias propagation noise density | 0 > 1 | 1e-3 | (m/s^2)/s/sqrt(Hz) |
LPE_PN_P (FLOAT) | Position propagation noise density Comment: Increase to trust measurements more. Decrease to trust model more. | 0 > 1 | 0.1 | m/s/sqrt(Hz) |
LPE_PN_T (FLOAT) | Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001) | 0 > 1 | 0.001 | (m/s)/(sqrt(hz)) |
LPE_PN_V (FLOAT) | Velocity propagation noise density Comment: Increase to trust measurements more. Decrease to trust model more. | 0 > 1 | 0.1 | (m/s)/s/sqrt(Hz) |
LPE_SNR_OFF_Z (FLOAT) | Sonar z offset from center of vehicle +down | -1 > 1 | 0.00 | m |
LPE_SNR_Z (FLOAT) | Sonar z standard deviation | 0.01 > 1 | 0.05 | m |
LPE_T_MAX_GRADE (FLOAT) | 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 | 0 > 100 | 1.0 | % |
LPE_VIC_P (FLOAT) | Vicon position standard deviation | 0.0001 > 1 | 0.001 | m |
LPE_VIS_DELAY (FLOAT) | Vision delay compensaton Comment: Set to zero to enable automatic compensation from measurement timestamps | 0 > 0.1 | 0.1 | sec |
LPE_VIS_XY (FLOAT) | Vision xy standard deviation | 0.01 > 1 | 0.1 | m |
LPE_VIS_Z (FLOAT) | Vision z standard deviation | 0.01 > 100 | 0.5 | m |
LPE_VXY_PUB (FLOAT) | Required velocity xy standard deviation to publish position | 0.01 > 1.0 | 0.3 | m/s |
LPE_X_LP (FLOAT) | Cut frequency for state publication | 5 > 1000 | 5.0 | Hz |
LPE_Z_PUB (FLOAT) | Required z standard deviation to publish altitude/ terrain | 0.3 > 5.0 | 1.0 | m |
MAVLink
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
MAV_0_CONFIG (INT32) | Serial Configuration for MAVLink (instance 0) Comment: Configure on which serial port to run MAVLink. Values:
Reboot required: true | 101 | ||
MAV_0_FORWARD (INT32) | Enable MAVLink Message forwarding for instance 0 Comment: If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS). Reboot required: True | 1 | ||
MAV_0_MODE (INT32) | MAVLink Mode for instance 0 Comment: The MAVLink Mode defines the set of streamed messages (for example the vehicle’s attitude) and their sending rates. Values:
Reboot required: True | 0 | ||
MAV_0_RATE (INT32) | Maximum MAVLink sending rate for instance 0 Comment: Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links). Reboot required: True | 0 > ? | 1200 | B/s |
MAV_1_CONFIG (INT32) | Serial Configuration for MAVLink (instance 1) Comment: Configure on which serial port to run MAVLink. Values:
Reboot required: true | 0 | ||
MAV_1_FORWARD (INT32) | Enable MAVLink Message forwarding for instance 1 Comment: If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS). Reboot required: True | 0 | ||
MAV_1_MODE (INT32) | MAVLink Mode for instance 1 Comment: The MAVLink Mode defines the set of streamed messages (for example the vehicle’s attitude) and their sending rates. Values:
Reboot required: True | 2 | ||
MAV_1_RATE (INT32) | Maximum MAVLink sending rate for instance 1 Comment: Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links). Reboot required: True | 0 > ? | 0 | B/s |
MAV_2_CONFIG (INT32) | Serial Configuration for MAVLink (instance 2) Comment: Configure on which serial port to run MAVLink. Values:
Reboot required: true | 0 | ||
MAV_2_FORWARD (INT32) | Enable MAVLink Message forwarding for instance 2 Comment: If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS). Reboot required: True | 0 | ||
MAV_2_MODE (INT32) | MAVLink Mode for instance 2 Comment: The MAVLink Mode defines the set of streamed messages (for example the vehicle’s attitude) and their sending rates. Values:
Reboot required: True | 0 | ||
MAV_2_RATE (INT32) | Maximum MAVLink sending rate for instance 2 Comment: Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links). Reboot required: True | 0 > ? | 0 | B/s |
MAV_BROADCAST (INT32) | Broadcast heartbeats on local network Comment: This allows a ground control station to automatically find the drone on the local network. Values:
| 0 | ||
MAV_COMP_ID (INT32) | MAVLink component ID Reboot required: true | 1 > 250 | 1 | |
MAV_FWDEXTSP (INT32) | Forward external setpoint messages Comment: If set to 1 incoming external setpoint messages will be directly forwarded to the controllers if in offboard control mode | 1 | ||
MAV_HASH_CHK_EN (INT32) | Parameter hash check Comment: Disabling the parameter hash check functionality will make the mavlink instance stream parameters continuously. | 1 | ||
MAV_HB_FORW_EN (INT32) | Hearbeat message forwarding Comment: The mavlink hearbeat message will not be forwarded if this parameter is set to ‘disabled’. The main reason for disabling heartbeats to be forwarded is because they confuse dronekit. | 1 | ||
MAV_ODOM_LP (INT32) | Activate ODOMETRY loopback Comment: If set, it gets the data from ‘vehicle_visual_odometry’ instead of ‘vehicle_odometry’ serving as a loopback of the received ODOMETRY messages on the Mavlink receiver. | 0 | ||
MAV_PROTO_VER (INT32) | MAVLink protocol version Values:
| 0 | ||
MAV_RADIO_ID (INT32) | MAVLink Radio ID Comment: When non-zero the MAVLink app will attempt to configure the radio to this ID and re-set the parameter to 0. If the value is negative it will reset the complete radio config to factory defaults. | -1 > 240 | 0 | |
MAV_SYS_ID (INT32) | MAVLink system ID Reboot required: true | 1 > 250 | 1 | |
MAV_TYPE (INT32) | MAVLink airframe type Values:
| 1 > 27 | 2 | |
MAV_USEHILGPS (INT32) | Use/Accept HIL GPS message even if not in HIL mode Comment: If set to 1 incoming HIL GPS messages are parsed. | 0 |
MKBLCTRL Testmode
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
MKBLCTRL_TEST (INT32) | Test mode (Identify) of MKBLCTRL Driver | 0 |
MPU9x50 Configuration
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
MPU_ACC_LPF_ENM (INT32) | Low pass filter frequency for Accelerometer Values:
| 4 | ||
MPU_GYRO_LPF_ENM (INT32) | Low pass filter frequency for Gyro Values:
| 4 | ||
MPU_SAMPLE_R_ENM (INT32) | Sample rate in Hz Values:
| 2 |
Mission
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
COM_OBS_AVOID (INT32) | Flag to enable obstacle avoidance | 0 | ||
COM_TAKEOFF_ACT (INT32) | Action after TAKEOFF has been accepted Comment: The mode transition after TAKEOFF has completed successfully. Values:
| 0 | ||
MIS_ALTMODE (INT32) | Altitude setpoint mode Comment: 0: the system will follow a zero order hold altitude setpoint 1: the system will follow a first order hold altitude setpoint values follow the definition in enum mission_altitude_mode Values:
| 0 > 1 | 1 | |
MIS_DIST_1WP (FLOAT) | Maximal horizontal distance from home to first waypoint Comment: Failsafe check to prevent running mission stored from previous flight at a new takeoff location. Set a value of zero or less to disable. The mission will not be started if the current waypoint is more distant than MIS_DIS_1WP from the home position. | 0 > 10000 (100) | 900 | m |
MIS_DIST_WPS (FLOAT) | Maximal horizontal distance between waypoint Comment: Failsafe check to prevent running missions which are way too big. Set a value of zero or less to disable. The mission will not be started if any distance between two subsequent waypoints is greater than MIS_DIST_WPS. | 0 > 10000 (100) | 900 | m |
MIS_LTRMIN_ALT (FLOAT) | Minimum Loiter altitude Comment: This is the minimum altitude the system will always obey. The intent is to stay out of ground effect. set to -1, if there shouldn’t be a minimum loiter altitude | -1 > 80 (0.5) | -1.0 | m |
MIS_MNT_YAW_CTL (INT32) | Enable yaw control of the mount. (Only affects multicopters and ROI mission items) Comment: If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction. If disabled, the vehicle will yaw towards the ROI. Values:
| 0 > 1 | 0 | |
MIS_TAKEOFF_ALT (FLOAT) | Take-off altitude Comment: This is the minimum altitude the system will take off to. | 0 > 80 (0.5) | 2.5 | m |
MIS_TAKEOFF_REQ (INT32) | Take-off waypoint required Comment: If set, the mission feasibility checker will check for a takeoff waypoint on the mission. | 0 | ||
MIS_YAW_ERR (FLOAT) | Max yaw error in degrees needed for waypoint heading acceptance | 0 > 90 (1) | 12.0 | deg |
MIS_YAW_TMT (FLOAT) | Time in seconds we wait on reaching target heading at a waypoint if it is forced Comment: If set > 0 it will ignore the target heading for normal waypoint acceptance. If the waypoint forces the heading the timeout will matter. For example on VTOL forwards transition. Mainly useful for VTOLs that have less yaw authority and might not reach target yaw in wind. Disabled by default. | -1 > 20 (1) | -1.0 | s |
MPC_YAW_MODE (INT32) | Yaw mode Comment: Specifies the heading in Auto. Values:
| 0 > 4 | 0 | |
NAV_ACC_RAD (FLOAT) | Acceptance Radius Comment: Default acceptance radius, overridden by acceptance radius of waypoint if set. For fixed wing the L1 turning distance is used for horizontal acceptance. | 0.05 > 200.0 (0.5) | 10.0 | m |
NAV_DLL_ACT (INT32) | Set data link loss failsafe mode Comment: The data link loss failsafe will only be entered after a timeout, set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected action will be executed. Setting this parameter to 4 will enable CASA Outback Challenge rules, which are only recommended to participants of that competition. Values:
| 0 | ||
NAV_FORCE_VT (INT32) | Force VTOL mode takeoff and land | 1 | ||
NAV_FW_ALTL_RAD (FLOAT) | FW Altitude Acceptance Radius before a landing Comment: Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller than the standard vertical acceptance because close to the ground higher accuracy is required. | 0.05 > 200.0 | 5.0 | m |
NAV_FW_ALT_RAD (FLOAT) | FW Altitude Acceptance Radius Comment: Acceptance radius for fixedwing altitude. | 0.05 > 200.0 (0.5) | 10.0 | m |
NAV_LOITER_RAD (FLOAT) | Loiter radius (FW only) Comment: Default value of loiter radius for missions, Hold mode, Return mode, etc. (fixedwing only). | 25 > 1000 (0.5) | 50.0 | m |
NAV_MC_ALT_RAD (FLOAT) | MC Altitude Acceptance Radius Comment: Acceptance radius for multicopter altitude. | 0.05 > 200.0 (0.5) | 0.8 | m |
NAV_RCL_ACT (INT32) | Set RC loss failsafe mode Comment: The RC loss failsafe will only be entered after a timeout, set by COM_RC_LOSS_T in seconds. If RC input checks have been disabled by setting the COM_RC_IN_MODE param it will not be triggered. Setting this parameter to 4 will enable CASA Outback Challenge rules, which are only recommended to participants of that competition. Values:
| 2 | ||
NAV_RCL_LT (FLOAT) | RC Loss Loiter Time (CASA Outback Challenge rules) Comment: The amount of time in seconds the system should loiter at current position before termination. Only applies if NAV_RCL_ACT is set to 2 (CASA Outback Challenge rules). Set to -1 to make the system skip loitering. | -1.0 > ? (0.1) | 120.0 | s |
NAV_TRAFF_AVOID (INT32) | Set traffic avoidance mode Comment: Enabling this will allow the system to respond to transponder data from e.g. ADSB transponders Values:
| 1 |
Mount
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
MNTDO_STAB (INT32) | Stabilize the mount (set to true for servo gimbal, false for passthrough). Does not affect MAVLINK_ROI input | 0 | ||
MNT_MAN_PITCH (INT32) | Auxiliary channel to control pitch (in AUX input or manual mode) Values:
| 0 > 5 | 0 | |
MNT_MAN_ROLL (INT32) | Auxiliary channel to control roll (in AUX input or manual mode) Values:
| 0 > 5 | 0 | |
MNT_MAN_YAW (INT32) | Auxiliary channel to control yaw (in AUX input or manual mode) Values:
| 0 > 5 | 0 | |
MNT_MAV_COMPID (INT32) | Mavlink Component ID of the mount Comment: If MNT_MODE_OUT is MAVLINK, mount configure/control commands will be sent with this component ID. | 154 | ||
MNT_MAV_SYSID (INT32) | Mavlink System ID of the mount Comment: If MNT_MODE_OUT is MAVLINK, mount configure/control commands will be sent with this target ID. | 1 | ||
MNT_MODE_IN (INT32) | Mount input mode Comment: RC uses the AUX input channels (see MNT_MAN* parameters), MAVLINK_ROI uses the MAV_CMD_DO_SET_ROI Mavlink message, and MAVLINK_DO_MOUNT the MAV_CMD_DO_MOUNT_CONFIGURE and MAV_CMD_DO_MOUNT_CONTROL messages to control a mount. Values:
Reboot required: true | -1 > 3 | -1 | |
MNT_MODE_OUT (INT32) | Mount output mode Comment: AUX uses the mixer output Control Group #2. MAVLINK uses the MAV_CMD_DO_MOUNT_CONFIGURE and MAV_CMD_DO_MOUNT_CONTROL MavLink messages to control a mount (set MNT_MAV_SYSID & MNT_MAV_COMPID) Values:
| 0 > 1 | 0 | |
MNT_OB_LOCK_MODE (FLOAT) | Mixer value for selecting a locking mode if required for the gimbal (only in AUX output mode) | -1.0 > 1.0 | 0.0 | |
MNT_OB_NORM_MODE (FLOAT) | Mixer value for selecting normal mode if required by the gimbal (only in AUX output mode) | -1.0 > 1.0 | -1.0 | |
MNT_OFF_PITCH (FLOAT) | Offset for pitch channel output in degrees | -360.0 > 360.0 | 0.0 | |
MNT_OFF_ROLL (FLOAT) | Offset for roll channel output in degrees | -360.0 > 360.0 | 0.0 | |
MNT_OFF_YAW (FLOAT) | Offset for yaw channel output in degrees | -360.0 > 360.0 | 0.0 | |
MNT_RANGE_PITCH (FLOAT) | Range of pitch channel output in degrees (only in AUX output mode) | 1.0 > 720.0 | 360.0 | |
MNT_RANGE_ROLL (FLOAT) | Range of roll channel output in degrees (only in AUX output mode) | 1.0 > 720.0 | 360.0 | |
MNT_RANGE_YAW (FLOAT) | Range of yaw channel output in degrees (only in AUX output mode) | 1.0 > 720.0 | 360.0 |
Multicopter Attitude Control
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
MC_ACRO_EXPO (FLOAT) | Acro mode Expo factor for Roll and Pitch Comment: Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve | 0 > 1 | 0.69 | |
MC_ACRO_EXPO_Y (FLOAT) | Acro mode Expo factor for Yaw Comment: Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve | 0 > 1 | 0.69 | |
MC_ACRO_P_MAX (FLOAT) | Max acro pitch rate default: 2 turns per second | 0.0 > 1800.0 (5) | 720.0 | deg/s |
MC_ACRO_R_MAX (FLOAT) | Max acro roll rate default: 2 turns per second | 0.0 > 1800.0 (5) | 720.0 | deg/s |
MC_ACRO_SUPEXPO (FLOAT) | Acro mode SuperExpo factor for Roll and Pitch Comment: SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect | 0 > 0.95 | 0.7 | |
MC_ACRO_SUPEXPOY (FLOAT) | Acro mode SuperExpo factor for Yaw Comment: SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect | 0 > 0.95 | 0.7 | |
MC_ACRO_Y_MAX (FLOAT) | Max acro yaw rate default 1.5 turns per second | 0.0 > 1800.0 (5) | 540.0 | deg/s |
MC_AIRMODE (INT32) | Multicopter air-mode Comment: The air-mode enables the mixer to increase the total thrust of the multirotor in order to keep attitude and rate control even at low and high throttle. This function should be disabled during tuning as it will help the controller to diverge if the closed-loop is unstable (i.e. the vehicle is not tuned yet). Enabling air-mode for yaw requires the use of an arming switch. Values:
| 0 | ||
MC_BAT_SCALE_EN (INT32) | Battery power level scaler Comment: This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery. | 0 | ||
MC_DTERM_CUTOFF (FLOAT) | Cutoff frequency for the low pass filter on the D-term in the rate controller Comment: The D-term uses the derivative of the rate and thus is the most susceptible to noise. Therefore, using a D-term filter allows to decrease the driver-level filtering, which leads to reduced control latency and permits to increase the P gains. A value of 0 disables the filter. | 0 > 1000 (10) | 0. | Hz |
MC_PITCHRATE_D (FLOAT) | Pitch rate D gain Comment: Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. | 0.0 > ? (0.0005) | 0.003 | |
MC_PITCHRATE_FF (FLOAT) | Pitch rate feedforward Comment: Improves tracking performance. | 0.0 > ? | 0.0 | |
MC_PITCHRATE_I (FLOAT) | Pitch rate I gain Comment: Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset. | 0.0 > ? (0.01) | 0.2 | |
MC_PITCHRATE_K (FLOAT) | Pitch rate controller gain Comment: Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_PITCHRATE_K (MC_PITCHRATE_P error + MC_PITCHRATE_I error_integral + MC_PITCHRATE_D error_derivative) Set MC_PITCHRATE_P=1 to implement a PID in the ideal form. Set MC_PITCHRATE_K=1 to implement a PID in the parallel form. | 0.0 > 5.0 (0.0005) | 1.0 | |
MC_PITCHRATE_MAX (FLOAT) | Max pitch rate Comment: Limit for pitch rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle’s properties, but also by the maximum measurement rate of the gyro. | 0.0 > 1800.0 (5) | 220.0 | deg/s |
MC_PITCHRATE_P (FLOAT) | Pitch rate P gain Comment: Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s. | 0.0 > 0.6 (0.01) | 0.15 | |
MC_PITCH_P (FLOAT) | Pitch P gain Comment: Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad. | 0.0 > 12 (0.1) | 6.5 | 1/s |
MC_PR_INT_LIM (FLOAT) | Pitch rate integrator limit Comment: Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes. | 0.0 > ? (0.01) | 0.30 | |
MC_RATT_TH (FLOAT) | Threshold for Rattitude mode Comment: Manual input needed in order to override attitude control rate setpoints and instead pass manual stick inputs as rate setpoints | 0.0 > 1.0 (0.01) | 0.8 | |
MC_ROLLRATE_D (FLOAT) | Roll rate D gain Comment: Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. | 0.0 > 0.01 (0.0005) | 0.003 | |
MC_ROLLRATE_FF (FLOAT) | Roll rate feedforward Comment: Improves tracking performance. | 0.0 > ? | 0.0 | |
MC_ROLLRATE_I (FLOAT) | Roll rate I gain Comment: Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset. | 0.0 > ? (0.01) | 0.2 | |
MC_ROLLRATE_K (FLOAT) | Roll rate controller gain Comment: Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_ROLLRATE_K (MC_ROLLRATE_P error + MC_ROLLRATE_I error_integral + MC_ROLLRATE_D error_derivative) Set MC_ROLLRATE_P=1 to implement a PID in the ideal form. Set MC_ROLLRATE_K=1 to implement a PID in the parallel form. | 0.0 > 5.0 (0.0005) | 1.0 | |
MC_ROLLRATE_MAX (FLOAT) | Max roll rate Comment: Limit for roll rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle’s properties, but also by the maximum measurement rate of the gyro. | 0.0 > 1800.0 (5) | 220.0 | deg/s |
MC_ROLLRATE_P (FLOAT) | Roll rate P gain Comment: Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s. | 0.0 > 0.5 (0.01) | 0.15 | |
MC_ROLL_P (FLOAT) | Roll P gain Comment: Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad. | 0.0 > 12 (0.1) | 6.5 | 1/s |
MC_RR_INT_LIM (FLOAT) | Roll rate integrator limit Comment: Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes. | 0.0 > ? (0.01) | 0.30 | |
MC_TPA_BREAK_D (FLOAT) | TPA D Breakpoint Comment: Throttle PID Attenuation (TPA) Magnitude of throttle setpoint at which to begin attenuating roll/pitch D gain | 0.0 > 1.0 (0.1) | 1.0 | |
MC_TPA_BREAK_I (FLOAT) | TPA I Breakpoint Comment: Throttle PID Attenuation (TPA) Magnitude of throttle setpoint at which to begin attenuating roll/pitch I gain | 0.0 > 1.0 (0.1) | 1.0 | |
MC_TPA_BREAK_P (FLOAT) | TPA P Breakpoint Comment: Throttle PID Attenuation (TPA) Magnitude of throttle setpoint at which to begin attenuating roll/pitch P gain | 0.0 > 1.0 (0.1) | 1.0 | |
MC_TPA_RATE_D (FLOAT) | TPA Rate D Comment: Throttle PID Attenuation (TPA) Rate at which to attenuate roll/pitch D gain Attenuation factor is 1.0 when throttle magnitude is below the setpoint Above the setpoint, the attenuation factor is (1 - rate (throttle - breakpoint) / (1.0 - breakpoint)) | 0.0 > 1.0 (0.05) | 0.0 | |
MC_TPA_RATE_I (FLOAT) | TPA Rate I Comment: Throttle PID Attenuation (TPA) Rate at which to attenuate roll/pitch I gain Attenuation factor is 1.0 when throttle magnitude is below the setpoint Above the setpoint, the attenuation factor is (1 - rate (throttle - breakpoint) / (1.0 - breakpoint)) | 0.0 > 1.0 (0.05) | 0.0 | |
MC_TPA_RATE_P (FLOAT) | TPA Rate P Comment: Throttle PID Attenuation (TPA) Rate at which to attenuate roll/pitch P gain Attenuation factor is 1.0 when throttle magnitude is below the setpoint Above the setpoint, the attenuation factor is (1 - rate (throttle - breakpoint) / (1.0 - breakpoint)) | 0.0 > 1.0 (0.05) | 0.0 | |
MC_YAWRATE_D (FLOAT) | Yaw rate D gain Comment: Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. | 0.0 > ? (0.01) | 0.0 | |
MC_YAWRATE_FF (FLOAT) | Yaw rate feedforward Comment: Improves tracking performance. | 0.0 > ? (0.01) | 0.0 | |
MC_YAWRATE_I (FLOAT) | Yaw rate I gain Comment: Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset. | 0.0 > ? (0.01) | 0.1 | |
MC_YAWRATE_K (FLOAT) | Yaw rate controller gain Comment: Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_YAWRATE_K (MC_YAWRATE_P error + MC_YAWRATE_I error_integral + MC_YAWRATE_D * error_derivative) Set MC_YAWRATE_P=1 to implement a PID in the ideal form. Set MC_YAWRATE_K=1 to implement a PID in the parallel form. | 0.0 > 5.0 (0.0005) | 1.0 | |
MC_YAWRATE_MAX (FLOAT) | Max yaw rate | 0.0 > 1800.0 (5) | 200.0 | deg/s |
MC_YAWRATE_P (FLOAT) | Yaw rate P gain Comment: Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s. | 0.0 > 0.6 (0.01) | 0.2 | |
MC_YAW_P (FLOAT) | Yaw P gain Comment: Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad. | 0.0 > 5 (0.1) | 2.8 | 1/s |
MC_YR_INT_LIM (FLOAT) | Yaw rate integrator limit Comment: Yaw rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes. | 0.0 > ? (0.01) | 0.30 | |
MPC_YAWRAUTO_MAX (FLOAT) | Max yaw rate in auto mode Comment: Limit the rate of change of the yaw setpoint in autonomous mode to avoid large control output and mixer saturation. | 0.0 > 360.0 (5) | 45.0 | deg/s |
Multicopter Position Control
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
MPC_ACC_DOWN_MAX (FLOAT) | Maximum vertical acceleration in velocity controlled modes down | 2.0 > 15.0 (1) | 3.0 | m/s/s |
MPC_ACC_HOR (FLOAT) | Acceleration for auto and for manual Comment: Note: In manual, this parameter is only used in MPC_POS_MODE 1. | 2.0 > 15.0 (1) | 3.0 | m/s/s |
MPC_ACC_HOR_ESTM (FLOAT) | Horizontal acceleration in manual modes when te estimator speed limit is removed. If full stick is being applied and the estimator stops demanding a speed limit, which it had been before (e.g if GPS is gained while flying on optical flow/vision only), the vehicle will accelerate at this rate until the normal position control speed is achieved | 0.2 > 2.0 (0.1) | 0.5 | m/s/s |
MPC_ACC_HOR_MAX (FLOAT) | Maximum horizontal acceleration for auto mode and for manual mode Comment: Manual mode: Maximum deceleration for MPC_POS_MODE 1 and 2. Maximum acceleration and deceleration for MPC_POS_MODE 3. Auto mode: Used with MPC_AUTO_MODE 0 only. For MPC_AUTO_MODE 1, MPC_ACC_HOR is always used. | 2.0 > 15.0 (1) | 5.0 | m/s/s |
MPC_ACC_UP_MAX (FLOAT) | Maximum vertical acceleration in velocity controlled modes upward | 2.0 > 15.0 (1) | 4.0 | m/s/s |
MPC_ALT_MODE (INT32) | Altitude control mode Comment: Set to 0 to control height relative to the earth frame origin. This origin may move up and down in flight due to sensor drift. Set to 1 to control height relative to estimated distance to ground. The vehicle will move up and down with terrain height variation. Requires a distance to ground sensor. The height controller will revert to using height above origin if the distance to ground estimate becomes invalid as indicated by the local_position.distance_bottom_valid message being false. Set to 2 to control height relative to ground (requires a distance sensor) when stationary and relative to earth frame origin when moving horizontally. The speed threshold is controlled by the MPC_HOLD_MAX_XY parameter. Values:
| 0 > 2 | 0 | |
MPC_AUTO_MODE (INT32) | Auto sub-mode Values:
| 1 | ||
MPC_COL_PREV_ANG (FLOAT) | Angle left/right from the commanded setpoint in which the range data is used to calculate speed limitations. All data further from the commanded direction is not considered Comment: Only used in Position mode. | 0 > 90 | 45. | [deg] |
MPC_COL_PREV_D (FLOAT) | Minimum distance the vehicle should keep to all obstacles Comment: Only used in Position mode. Collision avoidace is disabled by setting this parameter to a negative value | -1 > 15 | -1.0 | meters |
MPC_COL_PREV_DLY (FLOAT) | Average delay of the range sensor message in seconds Comment: Only used in Position mode. | 0 > 1 | 0. | seconds |
MPC_CRUISE_90 (FLOAT) | Cruise speed when angle prev-current/current-next setpoint is 90 degrees. It should be lower than MPC_XY_CRUISE Comment: Applies only in AUTO modes (includes also RTL / hold / etc.) | 1.0 > 20.0 (1) | 3.0 | m/s |
MPC_DEC_HOR_SLOW (FLOAT) | Slow horizontal manual deceleration for manual mode Comment: Note: This is only used when MPC_POS_MODE is set to 1. | 0.5 > 10.0 (1) | 5.0 | m/s/s |
MPC_HOLD_DZ (FLOAT) | Deadzone of sticks where position hold is enabled | 0.0 > 1.0 | 0.1 | |
MPC_HOLD_MAX_XY (FLOAT) | Maximum horizontal velocity for which position hold is enabled (use 0 to disable check) | 0.0 > 3.0 | 0.8 | m/s |
MPC_HOLD_MAX_Z (FLOAT) | Maximum vertical velocity for which position hold is enabled (use 0 to disable check) | 0.0 > 3.0 | 0.6 | m/s |
MPC_JERK_AUTO (FLOAT) | Jerk limit in auto mode Comment: Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions, but it also limits its agility. Note: This is only used in jerk-limited trajectory mode (MPC_AUTO_MODE 1) | 5.0 > 80.0 (1) | 8.0 | m/s/s/s |
MPC_JERK_MAX (FLOAT) | Maximum jerk limit Comment: Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions, but it also limits its agility (how fast it can change directions or break). Setting this to the maximum value essentially disables the limit. Note: This is only used when MPC_POS_MODE is set to a smoothing mode 1 or 3. | 0.5 > 500.0 (1) | 20.0 | m/s/s/s |
MPC_JERK_MIN (FLOAT) | Velocity-based jerk limit Comment: If this is not zero, a velocity-based maximum jerk limit is used: the applied jerk limit linearly increases with the vehicle’s velocity between MPC_JERK_MIN (zero velocity) and MPC_JERK_MAX (maximum velocity). This means that the vehicle’s motions are smooth for low velocities, but still allows fast direction changes or breaking at higher velocities. Set this to zero to use a fixed maximum jerk limit (MPC_JERK_MAX). Note: This is only used when MPC_POS_MODE is set to 1. | 0 > 30.0 (1) | 8.0 | m/s/s/s |
MPC_LAND_ALT1 (FLOAT) | Altitude for 1. step of slow landing (descend) Comment: Below this altitude descending velocity gets limited to a value between “MPC_Z_VEL_MAX” and “MPC_LAND_SPEED” to enable a smooth descent experience Value needs to be higher than “MPC_LAND_ALT2” | 0 > 122 | 10.0 | m |
MPC_LAND_ALT2 (FLOAT) | Altitude for 2. step of slow landing (landing) Comment: Below this altitude descending velocity gets limited to “MPC_LAND_SPEED” Value needs to be lower than “MPC_LAND_ALT1” | 0 > 122 | 5.0 | m |
MPC_LAND_SPEED (FLOAT) | Landing descend rate | 0.6 > ? | 0.7 | m/s |
MPC_MANTHR_MIN (FLOAT) | Minimum manual thrust Comment: Minimum vertical thrust. It’s recommended to set it > 0 to avoid free fall with zero thrust. With MC_AIRMODE set to 1, this can safely be set to 0. | 0.0 > 1.0 (0.01) | 0.08 | norm |
MPC_MAN_TILT_MAX (FLOAT) | Maximal tilt angle in manual or altitude mode | 0.0 > 90.0 | 35.0 | deg |
MPC_MAN_Y_MAX (FLOAT) | Max manual yaw rate | 0.0 > 400 | 150.0 | deg/s |
MPC_POS_MODE (INT32) | Manual-Position control sub-mode Comment: The supported sub-modes are: 0 Default position control where sticks map to position/velocity directly. Maximum speeds is MPC_VEL_MANUAL. 1 Smooth position control where setpoints are adjusted based on acceleration limits and jerk limits. 2 Sport mode that is the same Default position control but with velocity limits set to the maximum allowed speeds (MPC_XY_VEL_MAX) 3 Smooth position control with maximum acceleration and jerk limits (different algorithm than 1). Values:
| 3 | ||
MPC_SPOOLUP_TIME (FLOAT) | Enforced delay between arming and takeoff Comment: For altitude controlled modes the time from arming the motors until a takeoff is possible gets forced to be at least MPC_SPOOLUP_TIME seconds to ensure the motors and propellers can sppol up and reach idle speed before getting commanded to spin faster. This delay is particularly useful for vehicles with slow motor spin-up e.g. because of large propellers. | 0 > 10 | 1.0 | s |
MPC_THR_CURVE (INT32) | Thrust curve in Manual Mode Comment: This parameter defines how the throttle stick input is mapped to commanded thrust in Manual/Stabilized flight mode. In case the default is used (‘Rescale to hover thrust’), the stick input is linearly rescaled, such that a centered stick corresponds to the hover throttle (see MPC_THR_HOVER). Select ‘No Rescale’ to directly map the stick 1:1 to the output. This can be useful in case the hover thrust is very low and the default would lead to too much distortion (e.g. if hover thrust is set to 20%, 80% of the upper thrust range is squeezed into the upper half of the stick range). Note: In case MPC_THR_HOVER is set to 50%, the modes 0 and 1 are the same. Values:
| 0 | ||
MPC_THR_HOVER (FLOAT) | Hover thrust Comment: Vertical thrust required to hover. This value is mapped to center stick for manual throttle control. With this value set to the thrust required to hover, transition from manual to Altitude or Position mode while hovering will occur with the throttle stick near center, which is then interpreted as (near) zero demand for vertical speed. This parameter is also important for the landing detection to work correctly. | 0.1 > 0.8 (0.01) | 0.5 | norm |
MPC_THR_MAX (FLOAT) | Maximum thrust in auto thrust control Comment: Limit max allowed thrust | 0.0 > 1.0 (0.01) | 1.0 | norm |
MPC_THR_MIN (FLOAT) | Minimum thrust in auto thrust control Comment: It’s recommended to set it > 0 to avoid free fall with zero thrust. | 0.05 > 1.0 (0.01) | 0.12 | norm |
MPC_TILTMAX_AIR (FLOAT) | Maximum tilt angle in air Comment: Limits maximum tilt in AUTO and POSCTRL modes during flight. | 20.0 > 180.0 | 45.0 | deg |
MPC_TILTMAX_LND (FLOAT) | Maximum tilt during landing Comment: Limits maximum tilt angle on landing. | 10.0 > 90.0 | 12.0 | deg |
MPC_TKO_RAMP_T (FLOAT) | Position control smooth takeoff ramp time constant Comment: Increasing this value will make automatic and manual takeoff slower. If it’s too slow the drone might scratch the ground and tip over. A time constant of 0 disables the ramp | 0 > 5 | 3.0 | |
MPC_TKO_SPEED (FLOAT) | Takeoff climb rate | 1 > 5 | 1.5 | m/s |
MPC_VELD_LP (FLOAT) | Low pass filter cut freq. for numerical velocity derivative | 0.0 > 10 | 5.0 | Hz |
MPC_VEL_MANUAL (FLOAT) | 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 | 3.0 > 20.0 (1) | 10.0 | m/s |
MPC_XY_CRUISE (FLOAT) | Maximum horizontal velocity in mission Comment: Normal horizontal velocity in AUTO modes (includes also RTL / hold / etc.) and endpoint for position stabilized mode (POSCTRL). | 3.0 > 20.0 (1) | 5.0 | m/s |
MPC_XY_MAN_EXPO (FLOAT) | Manual position control stick exponential curve sensitivity Comment: The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve | 0 > 1 | 0.6 | |
MPC_XY_P (FLOAT) | Proportional gain for horizontal position error | 0.0 > 2.0 | 0.95 | |
MPC_XY_TRAJ_P (FLOAT) | Proportional gain for horizontal trajectory position error | 0.1 > 1.0 | 0.5 | |
MPC_XY_VEL_D (FLOAT) | Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again | 0.005 > 0.1 | 0.01 | |
MPC_XY_VEL_I (FLOAT) | Integral gain for horizontal velocity error Comment: Non-zero value allows to eliminate steady state errors in the presence of disturbances like wind. | 0.0 > 3.0 | 0.02 | |
MPC_XY_VEL_MAX (FLOAT) | Maximum horizontal velocity Comment: Maximum horizontal velocity in AUTO mode. If higher speeds are commanded in a mission they will be capped to this velocity. | 0.0 > 20.0 (1) | 12.0 | m/s |
MPC_XY_VEL_P (FLOAT) | Proportional gain for horizontal velocity error | 0.06 > 0.15 | 0.09 | |
MPC_YAW_EXPO (FLOAT) | Manual control stick yaw rotation exponential curve Comment: The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve | 0 > 1 | 0.6 | |
MPC_Z_MAN_EXPO (FLOAT) | Manual control stick vertical exponential curve Comment: The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve | 0 > 1 | 0.6 | |
MPC_Z_P (FLOAT) | Proportional gain for vertical position error | 0.0 > 1.5 | 1.0 | |
MPC_Z_TRAJ_P (FLOAT) | Proportional gain for vertical trajectory position error | 0.1 > 1.0 | 0.3 | |
MPC_Z_VEL_D (FLOAT) | Differential gain for vertical velocity error | 0.0 > 0.1 | 0.0 | |
MPC_Z_VEL_I (FLOAT) | Integral gain for vertical velocity error Comment: Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff. | 0.01 > 0.1 | 0.1 | |
MPC_Z_VEL_MAX_DN (FLOAT) | Maximum vertical descent velocity Comment: Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL). | 0.5 > 4.0 | 1.0 | m/s |
MPC_Z_VEL_MAX_UP (FLOAT) | Maximum vertical ascent velocity Comment: Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL). | 0.5 > 8.0 | 3.0 | m/s |
MPC_Z_VEL_P (FLOAT) | Proportional gain for vertical velocity error | 0.1 > 0.4 | 0.2 | |
WV_EN (INT32) | Enable weathervane | 0 | ||
WV_ROLL_MIN (FLOAT) | Minimum roll angle setpoint for weathervane controller to demand a yaw-rate | 0 > 5 | 1.0 | deg |
WV_YRATE_MAX (FLOAT) | Maximum yawrate the weathervane controller is allowed to demand | 0 > 120 | 90.0 | deg/s |
OSD
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
OSD_ATXXXX_CFG (INT32) | Enable/Disable the ATXXX OSD Chip Comment: Configure the ATXXXX OSD Chip (mounted on the OmnibusF4SD board) and select the transmission standard. Values:
Reboot required: true | 0 |
PWM Outputs
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
MOT_ORDERING (INT32) | Motor Ordering Comment: Determines the motor ordering. This can be used for example in combination with a 4-in-1 ESC that assumes a motor ordering which is different from PX4. ONLY supported for Quads. ONLY supported for fmu output (Pixracer or Omnibus F4). When changing this, make sure to test the motor response without props first. Values:
| 0 > 1 | 0 | |
MOT_SLEW_MAX (FLOAT) | Minimum motor rise time (slew rate limit) Comment: Minimum time allowed for the motor input signal to pass through a range of 1000 PWM units. A value x means that the motor signal can only go from 1000 to 2000 PWM in maximum x seconds. Zero means that slew rate limiting is disabled. | 0.0 > ? | 0.0 | s/(1000PWM) |
PWM_AUX_DIS1 (INT32) | Set the disarmed PWM for the auxiliary 1 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_DIS2 (INT32) | Set the disarmed PWM for the auxiliary 2 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_DIS3 (INT32) | Set the disarmed PWM for the auxiliary 3 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_DIS4 (INT32) | Set the disarmed PWM for the auxiliary 4 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_DIS5 (INT32) | Set the disarmed PWM for the auxiliary 5 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_DIS6 (INT32) | Set the disarmed PWM for the auxiliary 6 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_DIS7 (INT32) | Set the disarmed PWM for the auxiliary 7 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_DIS8 (INT32) | Set the disarmed PWM for the auxiliary 8 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_DISARMED (INT32) | Set the disarmed PWM for auxiliary outputs Comment: This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. Reboot required: true | 0 > 2200 | 1500 | us |
PWM_AUX_FAIL1 (INT32) | Set the failsafe PWM for the auxiliary 1 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_FAIL2 (INT32) | Set the failsafe PWM for the auxiliary 2 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_FAIL3 (INT32) | Set the failsafe PWM for the auxiliary 3 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_FAIL4 (INT32) | Set the failsafe PWM for the auxiliary 4 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_FAIL5 (INT32) | Set the failsafe PWM for the auxiliary 5 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_FAIL6 (INT32) | Set the failsafe PWM for the auxiliary 6 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_FAIL7 (INT32) | Set the failsafe PWM for the auxiliary 7 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_FAIL8 (INT32) | Set the failsafe PWM for the auxiliary 8 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MAX (INT32) | Set the maximum PWM for the auxiliary outputs Comment: Set to 2000 for industry default or 2100 to increase servo travel. Reboot required: true | 1600 > 2200 | 2000 | us |
PWM_AUX_MAX1 (INT32) | Set the max PWM value for the auxiliary 1 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MAX2 (INT32) | Set the max PWM value for the auxiliary 2 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MAX3 (INT32) | Set the max PWM value for the auxiliary 3 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MAX4 (INT32) | Set the max PWM value for the auxiliary 4 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MAX5 (INT32) | Set the max PWM value for the auxiliary 5 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MAX6 (INT32) | Set the max PWM value for the auxiliary 6 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MAX7 (INT32) | Set the max PWM value for the auxiliary 7 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MAX8 (INT32) | Set the max PWM value for the auxiliary 8 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MIN (INT32) | Set the minimum PWM for the auxiliary outputs Comment: Set to 1000 for industry default or 900 to increase servo travel. Reboot required: true | 800 > 1400 | 1000 | us |
PWM_AUX_MIN1 (INT32) | Set the min PWM value for the auxiliary 1 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MIN2 (INT32) | Set the min PWM value for the auxiliary 2 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MIN3 (INT32) | Set the min PWM value for the auxiliary 3 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MIN4 (INT32) | Set the min PWM value for the auxiliary 4 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MIN5 (INT32) | Set the min PWM value for the auxiliary 5 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MIN6 (INT32) | Set the min PWM value for the auxiliary 6 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MIN7 (INT32) | Set the min PWM value for the auxiliary 7 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_MIN8 (INT32) | Set the min PWM value for the auxiliary 8 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_AUX_RATE (INT32) | Set the PWM output frequency for the auxiliary outputs Comment: Set to 400 for industry default or 1000 for high frequency ESCs. Set to 0 for Oneshot125. Reboot required: true | -1 > 2000 | 50 | Hz |
PWM_AUX_REV1 (INT32) | Invert direction of auxiliary output channel 1 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_AUX_REV2 (INT32) | Invert direction of auxiliary output channel 2 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_AUX_REV3 (INT32) | Invert direction of auxiliary output channel 3 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_AUX_REV4 (INT32) | Invert direction of auxiliary output channel 4 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_AUX_REV5 (INT32) | Invert direction of auxiliary output channel 5 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_AUX_REV6 (INT32) | Invert direction of auxiliary output channel 6 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_AUX_REV7 (INT32) | Invert direction of auxiliary output channel 7 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_AUX_REV8 (INT32) | Invert direction of auxiliary output channel 8 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_AUX_TRIM1 (FLOAT) | Trim value for auxiliary output channel 1 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_AUX_TRIM2 (FLOAT) | Trim value for auxiliary output channel 2 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_AUX_TRIM3 (FLOAT) | Trim value for auxiliary output channel 3 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_AUX_TRIM4 (FLOAT) | Trim value for auxiliary output channel 4 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_AUX_TRIM5 (FLOAT) | Trim value for auxiliary output channel 5 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_AUX_TRIM6 (FLOAT) | Trim value for auxiliary output channel 6 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_AUX_TRIM7 (FLOAT) | Trim value for auxiliary output channel 7 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_AUX_TRIM8 (FLOAT) | Trim value for auxiliary output channel 8 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_DISARMED (INT32) | Set the disarmed PWM for the main outputs Comment: This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. Reboot required: true | 0 > 2200 | 900 | us |
PWM_MAIN_DIS1 (INT32) | Set the disarmed PWM for the main 1 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_DIS2 (INT32) | Set the disarmed PWM for the main 2 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_DIS3 (INT32) | Set the disarmed PWM for the main 3 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_DIS4 (INT32) | Set the disarmed PWM for the main 4 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_DIS5 (INT32) | Set the disarmed PWM for the main 5 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_DIS6 (INT32) | Set the disarmed PWM for the main 6 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_DIS7 (INT32) | Set the disarmed PWM for the main 7 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_DIS8 (INT32) | Set the disarmed PWM for the main 8 output Comment: This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_FAIL1 (INT32) | Set the failsafe PWM for the main 1 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_FAIL2 (INT32) | Set the failsafe PWM for the main 2 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_FAIL3 (INT32) | Set the failsafe PWM for the main 3 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_FAIL4 (INT32) | Set the failsafe PWM for the main 4 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_FAIL5 (INT32) | Set the failsafe PWM for the main 5 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_FAIL6 (INT32) | Set the failsafe PWM for the main 6 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_FAIL7 (INT32) | Set the failsafe PWM for the main 7 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_FAIL8 (INT32) | Set the failsafe PWM for the main 8 output Comment: This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MAX1 (INT32) | Set the max PWM value for the main 1 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MAX2 (INT32) | Set the max PWM value for the main 2 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MAX3 (INT32) | Set the max PWM value for the main 3 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MAX4 (INT32) | Set the max PWM value for the main 4 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MAX5 (INT32) | Set the max PWM value for the main 5 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MAX6 (INT32) | Set the max PWM value for the main 6 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MAX7 (INT32) | Set the max PWM value for the main 7 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MAX8 (INT32) | Set the max PWM value for the main 8 output Comment: This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAX will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MIN1 (INT32) | Set the min PWM value for the main 1 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MIN2 (INT32) | Set the min PWM value for the main 2 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MIN3 (INT32) | Set the min PWM value for the main 3 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MIN4 (INT32) | Set the min PWM value for the main 4 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MIN5 (INT32) | Set the min PWM value for the main 5 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MIN6 (INT32) | Set the min PWM value for the main 6 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MIN7 (INT32) | Set the min PWM value for the main 7 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_MIN8 (INT32) | Set the min PWM value for the main 8 output Comment: This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MIN will be used Reboot required: true | -1 > 2200 | -1 | us |
PWM_MAIN_REV1 (INT32) | Invert direction of main output channel 1 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_MAIN_REV2 (INT32) | Invert direction of main output channel 2 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_MAIN_REV3 (INT32) | Invert direction of main output channel 3 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_MAIN_REV4 (INT32) | Invert direction of main output channel 4 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_MAIN_REV5 (INT32) | Invert direction of main output channel 5 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_MAIN_REV6 (INT32) | Invert direction of main output channel 6 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_MAIN_REV7 (INT32) | Invert direction of main output channel 7 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_MAIN_REV8 (INT32) | Invert direction of main output channel 8 Comment: Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. | 0 | ||
PWM_MAIN_TRIM1 (FLOAT) | Trim value for main output channel 1 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_MAIN_TRIM2 (FLOAT) | Trim value for main output channel 2 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_MAIN_TRIM3 (FLOAT) | Trim value for main output channel 3 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_MAIN_TRIM4 (FLOAT) | Trim value for main output channel 4 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_MAIN_TRIM5 (FLOAT) | Trim value for main output channel 5 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_MAIN_TRIM6 (FLOAT) | Trim value for main output channel 6 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_MAIN_TRIM7 (FLOAT) | Trim value for main output channel 7 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_MAIN_TRIM8 (FLOAT) | Trim value for main output channel 8 Comment: Set to normalized offset | -0.2 > 0.2 | 0 | |
PWM_MAX (INT32) | Set the maximum PWM for the main outputs Comment: Set to 2000 for industry default or 2100 to increase servo travel. Reboot required: true | 1600 > 2200 | 2000 | us |
PWM_MIN (INT32) | Set the minimum PWM for the main outputs Comment: Set to 1000 for industry default or 900 to increase servo travel. Reboot required: true | 800 > 1400 | 1000 | us |
PWM_RATE (INT32) | Set the PWM output frequency for the main outputs Comment: Set to 400 for industry default or 1000 for high frequency ESCs. Set to 0 for Oneshot125. Reboot required: true | -1 > 2000 | 400 | Hz |
PWM_SBUS_MODE (INT32) | S.BUS out Comment: Set to 1 to enable S.BUS version 1 output instead of RSSI. | 0 | ||
THR_MDL_FAC (FLOAT) | Thrust to PWM model parameter Comment: Parameter used to model the relationship between static thrust and motor input PWM. Model is: thrust = (1-factor)PWM + factor * PWM^2 | 0.0 > 1.0 | 0.0 |
Payload drop
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
BD_GPROPERTIES (FLOAT) | Ground drag property Comment: This parameter encodes the ground drag coefficient and the corresponding decrease in wind speed from the plane altitude to ground altitude. | 0.001 > 0.1 | 0.03 | |
BD_OBJ_CD (FLOAT) | Payload drag coefficient of the dropped object Comment: The drag coefficient (cd) is the typical drag constant for air. It is in general object specific, but the closest primitive shape to the actual object should give good results: http://en.wikipedia.org/wiki/Drag_coefficient | 0.08 > 1.5 | 0.1 | |
BD_OBJ_MASS (FLOAT) | Payload mass Comment: A typical small toy ball: 0.025 kg OBC water bottle: 0.6 kg | 0.001 > 5.0 | 0.6 | kg |
BD_OBJ_SURFACE (FLOAT) | Payload front surface area Comment: A typical small toy ball: (0.045 0.045) / 4.0 pi = 0.001590 m^2 OBC water bottle: (0.063 0.063) / 4.0 pi = 0.003117 m^2 | 0.001 > 0.5 | 0.00311724531 | m^2 |
BD_PRECISION (FLOAT) | Drop precision Comment: If the system is closer than this distance on passing over the drop position, it will release the payload. This is a safeguard to prevent a drop out of the required accuracy. | 1.0 > 80.0 | 30.0 | m |
BD_TURNRADIUS (FLOAT) | Plane turn radius Comment: The planes known minimal turn radius - use a higher value to make the plane maneuver more distant from the actual drop position. This is to ensure the wings are level during the drop. | 30.0 > 500.0 | 120.0 | m |
Precision Land
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
PLD_BTOUT (FLOAT) | Landing Target Timeout Comment: Time after which the landing target is considered lost without any new measurements. | 0.0 > 50 (0.5) | 5.0 | s |
PLD_FAPPR_ALT (FLOAT) | Final approach altitude Comment: Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground. | 0.0 > 10 (0.1) | 0.1 | m |
PLD_HACC_RAD (FLOAT) | Horizontal acceptance radius Comment: Start descending if closer above landing target than this. | 0.0 > 10 (0.1) | 0.2 | m |
PLD_MAX_SRCH (INT32) | Maximum number of search attempts Comment: Maximum number of times to seach for the landing target if it is lost during the precision landing. | 0 > 100 | 3 | |
PLD_SRCH_ALT (FLOAT) | Search altitude Comment: Altitude above home to which to climb when searching for the landing target. | 0.0 > 100 (0.1) | 10.0 | m |
PLD_SRCH_TOUT (FLOAT) | Search timeout Comment: Time allowed to search for the landing target before falling back to normal landing. | 0.0 > 100 (0.1) | 10.0 | s |
RC Receiver Configuration
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
RC_RECEIVER_TYPE (INT32) | RC receiver type Comment: Acceptable values: - RC_RECEIVER_SPEKTRUM = 1, - RC_RECEIVER_LEMONRX = 2, | 1 |
RTPS
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
RTPS_CONFIG (INT32) | Serial Configuration for FastRTPS Comment: Configure on which serial port to run FastRTPS. Values:
Reboot required: true | 0 | ||
RTPS_MAV_CONFIG (INT32) | Serial Configuration for MAVLink + FastRTPS Comment: Configure on which serial port to run MAVLink + FastRTPS. Values:
Reboot required: true | 0 |
Radio Calibration
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
RC10_DZ (FLOAT) | RC channel 10 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 0.0 | |
RC10_MAX (FLOAT) | RC channel 10 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC10_MIN (FLOAT) | RC channel 10 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC10_REV (FLOAT) | RC channel 10 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC10_TRIM (FLOAT) | RC channel 10 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC11_DZ (FLOAT) | RC channel 11 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 0.0 | |
RC11_MAX (FLOAT) | RC channel 11 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC11_MIN (FLOAT) | RC channel 11 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC11_REV (FLOAT) | RC channel 11 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC11_TRIM (FLOAT) | RC channel 11 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC12_DZ (FLOAT) | RC channel 12 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 0.0 | |
RC12_MAX (FLOAT) | RC channel 12 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC12_MIN (FLOAT) | RC channel 12 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC12_REV (FLOAT) | RC channel 12 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC12_TRIM (FLOAT) | RC channel 12 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC13_DZ (FLOAT) | RC channel 13 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 0.0 | |
RC13_MAX (FLOAT) | RC channel 13 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC13_MIN (FLOAT) | RC channel 13 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC13_REV (FLOAT) | RC channel 13 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC13_TRIM (FLOAT) | RC channel 13 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC14_DZ (FLOAT) | RC channel 14 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 0.0 | |
RC14_MAX (FLOAT) | RC channel 14 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC14_MIN (FLOAT) | RC channel 14 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC14_REV (FLOAT) | RC channel 14 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC14_TRIM (FLOAT) | RC channel 14 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC15_DZ (FLOAT) | RC channel 15 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 0.0 | |
RC15_MAX (FLOAT) | RC channel 15 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC15_MIN (FLOAT) | RC channel 15 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC15_REV (FLOAT) | RC channel 15 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC15_TRIM (FLOAT) | RC channel 15 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC16_DZ (FLOAT) | RC channel 16 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 0.0 | |
RC16_MAX (FLOAT) | RC channel 16 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC16_MIN (FLOAT) | RC channel 16 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC16_REV (FLOAT) | RC channel 16 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC16_TRIM (FLOAT) | RC channel 16 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC17_DZ (FLOAT) | RC channel 17 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 0.0 | |
RC17_MAX (FLOAT) | RC channel 17 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC17_MIN (FLOAT) | RC channel 17 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC17_REV (FLOAT) | RC channel 17 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC17_TRIM (FLOAT) | RC channel 17 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC18_DZ (FLOAT) | RC channel 18 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 0.0 | |
RC18_MAX (FLOAT) | RC channel 18 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC18_MIN (FLOAT) | RC channel 18 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC18_REV (FLOAT) | RC channel 18 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC18_TRIM (FLOAT) | RC channel 18 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC1_DZ (FLOAT) | RC channel 1 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 10.0 | us |
RC1_MAX (FLOAT) | RC channel 1 maximum Comment: Maximum value for RC channel 1 | 1500.0 > 2200.0 | 2000.0 | us |
RC1_MIN (FLOAT) | RC channel 1 minimum Comment: Minimum value for RC channel 1 | 800.0 > 1500.0 | 1000.0 | us |
RC1_REV (FLOAT) | RC channel 1 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC1_TRIM (FLOAT) | RC channel 1 trim Comment: Mid point value (same as min for throttle) | 800.0 > 2200.0 | 1500.0 | us |
RC2_DZ (FLOAT) | RC channel 2 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 10.0 | us |
RC2_MAX (FLOAT) | RC channel 2 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000.0 | us |
RC2_MIN (FLOAT) | RC channel 2 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000.0 | us |
RC2_REV (FLOAT) | RC channel 2 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC2_TRIM (FLOAT) | RC channel 2 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500.0 | us |
RC3_DZ (FLOAT) | RC channel 3 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 10.0 | us |
RC3_MAX (FLOAT) | RC channel 3 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC3_MIN (FLOAT) | RC channel 3 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC3_REV (FLOAT) | RC channel 3 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC3_TRIM (FLOAT) | RC channel 3 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC4_DZ (FLOAT) | RC channel 4 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 10.0 | us |
RC4_MAX (FLOAT) | RC channel 4 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC4_MIN (FLOAT) | RC channel 4 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC4_REV (FLOAT) | RC channel 4 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC4_TRIM (FLOAT) | RC channel 4 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC5_DZ (FLOAT) | RC channel 5 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 10.0 | |
RC5_MAX (FLOAT) | RC channel 5 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC5_MIN (FLOAT) | RC channel 5 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC5_REV (FLOAT) | RC channel 5 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC5_TRIM (FLOAT) | RC channel 5 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC6_DZ (FLOAT) | RC channel 6 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 10.0 | |
RC6_MAX (FLOAT) | RC channel 6 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC6_MIN (FLOAT) | RC channel 6 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC6_REV (FLOAT) | RC channel 6 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC6_TRIM (FLOAT) | RC channel 6 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC7_DZ (FLOAT) | RC channel 7 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 10.0 | |
RC7_MAX (FLOAT) | RC channel 7 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC7_MIN (FLOAT) | RC channel 7 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC7_REV (FLOAT) | RC channel 7 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC7_TRIM (FLOAT) | RC channel 7 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC8_DZ (FLOAT) | RC channel 8 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 10.0 | |
RC8_MAX (FLOAT) | RC channel 8 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC8_MIN (FLOAT) | RC channel 8 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC8_REV (FLOAT) | RC channel 8 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC8_TRIM (FLOAT) | RC channel 8 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC9_DZ (FLOAT) | RC channel 9 dead zone Comment: The +- range of this value around the trim value will be considered as zero. | 0.0 > 100.0 | 0.0 | |
RC9_MAX (FLOAT) | RC channel 9 maximum Comment: Maximum value for this channel. | 1500.0 > 2200.0 | 2000 | us |
RC9_MIN (FLOAT) | RC channel 9 minimum Comment: Minimum value for this channel. | 800.0 > 1500.0 | 1000 | us |
RC9_REV (FLOAT) | RC channel 9 reverse Comment: Set to -1 to reverse channel. Values:
| -1.0 > 1.0 | 1.0 | |
RC9_TRIM (FLOAT) | RC channel 9 trim Comment: Mid point value (has to be set to the same as min for throttle channel). | 800.0 > 2200.0 | 1500 | us |
RC_CHAN_CNT (INT32) | RC channel count Comment: This parameter is used by Ground Station software to save the number of channels which were used during RC calibration. It is only meant for ground station use. | 0 > 18 | 0 | |
RC_FAILS_THR (INT32) | Failsafe channel PWM threshold Comment: Set to a value slightly above the PWM value assumed by throttle in a failsafe event, but ensure it is below the PWM value assumed by throttle during normal operation. | 0 > 2200 | 0 | us |
RC_FLT_CUTOFF (FLOAT) | Cutoff frequency for the low pass filter on roll, pitch, yaw and throttle Comment: Does not get set unless below RC_FLT_SMP_RATE/2 because of filter instability characteristics. Set to 0 to disable the filter. | 0 > ? | 10.0 | Hz |
RC_FLT_SMP_RATE (FLOAT) | Sample rate of the remote control values for the low pass filter on roll, pitch, yaw and throttle Comment: Has an influence on the cutoff frequency precision. | 1.0 > ? | 50.0 | Hz |
RC_MAP_AUX1 (INT32) | AUX1 Passthrough RC channel Comment: Default function: Camera pitch Values:
| 0 > 18 | 0 | |
RC_MAP_AUX2 (INT32) | AUX2 Passthrough RC channel Comment: Default function: Camera roll Values:
| 0 > 18 | 0 | |
RC_MAP_AUX3 (INT32) | AUX3 Passthrough RC channel Comment: Default function: Camera azimuth / yaw Values:
| 0 > 18 | 0 | |
RC_MAP_AUX4 (INT32) | AUX4 Passthrough RC channel Values:
| 0 > 18 | 0 | |
RC_MAP_AUX5 (INT32) | AUX5 Passthrough RC channel Values:
| 0 > 18 | 0 | |
RC_MAP_AUX6 (INT32) | AUX6 Passthrough RC channel Values:
| 0 > 18 | 0 | |
RC_MAP_FAILSAFE (INT32) | Failsafe channel mapping Comment: The RC mapping index indicates which channel is used for failsafe If 0, whichever channel is mapped to throttle is used otherwise the value indicates the specific RC channel to use Values:
| 0 > 18 | 0 | |
RC_MAP_PARAM1 (INT32) | PARAM1 tuning channel Comment: Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel. Set to 0 to deactivate Values:
| 0 > 18 | 0 | |
RC_MAP_PARAM2 (INT32) | PARAM2 tuning channel Comment: Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel. Set to 0 to deactivate Values:
| 0 > 18 | 0 | |
RC_MAP_PARAM3 (INT32) | PARAM3 tuning channel Comment: Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel. Set to 0 to deactivate * Values:
| 0 > 18 | 0 | |
RC_MAP_PITCH (INT32) | Pitch control channel mapping Comment: The channel index (starting from 1 for channel 1) indicates which channel should be used for reading pitch inputs from. A value of zero indicates the switch is not assigned. Values:
| 0 > 18 | 0 | |
RC_MAP_ROLL (INT32) | Roll control channel mapping Comment: The channel index (starting from 1 for channel 1) indicates which channel should be used for reading roll inputs from. A value of zero indicates the switch is not assigned. Values:
| 0 > 18 | 0 | |
RC_MAP_THROTTLE (INT32) | Throttle control channel mapping Comment: The channel index (starting from 1 for channel 1) indicates which channel should be used for reading throttle inputs from. A value of zero indicates the switch is not assigned. Values:
| 0 > 18 | 0 | |
RC_MAP_YAW (INT32) | Yaw control channel mapping Comment: The channel index (starting from 1 for channel 1) indicates which channel should be used for reading yaw inputs from. A value of zero indicates the switch is not assigned. Values:
| 0 > 18 | 0 | |
RC_RSSI_PWM_CHAN (INT32) | PWM input channel that provides RSSI Comment: 0: do not read RSSI from input channel 1-18: read RSSI from specified input channel Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters. Values:
| 0 > 18 | 0 | |
RC_RSSI_PWM_MAX (INT32) | Max input value for RSSI reading Comment: Only used if RC_RSSI_PWM_CHAN > 0 | 0 > 2000 | 1000 | |
RC_RSSI_PWM_MIN (INT32) | Min input value for RSSI reading Comment: Only used if RC_RSSI_PWM_CHAN > 0 | 0 > 2000 | 2000 | |
TRIM_PITCH (FLOAT) | Pitch trim Comment: The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. | -0.25 > 0.25 (0.01) | 0.0 | |
TRIM_ROLL (FLOAT) | Roll trim Comment: The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. | -0.25 > 0.25 (0.01) | 0.0 | |
TRIM_YAW (FLOAT) | Yaw trim Comment: The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. | -0.25 > 0.25 (0.01) | 0.0 |
Radio Switches
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 | |
---|---|---|---|---|---|
RC_ACRO_TH (FLOAT) | Threshold for selecting acro mode Comment: 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel | -1 > 1 | 0.5 | ||
RC_ARMSWITCH_TH (FLOAT) | Threshold for the arm switch Comment: 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel | -1 > 1 | 0.25 | ||
RC_ASSIST_TH (FLOAT) | Threshold for selecting assist mode Comment: 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel | -1 > 1 | 0.25 | ||
RC_AUTO_TH (FLOAT) | Threshold for selecting auto mode Comment: 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel | -1 > 1 | 0.75 | ||
RC_GEAR_TH (FLOAT) | Threshold for the landing gear switch Comment: 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel | -1 > 1 | 0.25 | ||
RC_KILLSWITCH_TH (FLOAT) | Threshold for the kill switch Comment: 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel | -1 > 1 | 0.25 | ||
RC_LOITER_TH (FLOAT) | Threshold for selecting loiter mode Comment: 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel | -1 > 1 | 0.5 | ||
RC_MAN_TH (FLOAT) | Threshold for the manual switch Comment: 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel | -1 > 1 | 0.5 | ||
RC_MAP_ACRO_SW (INT32) | Acro switch channel Values:
| 0 > 18 | 0 | ||
RC_MAP_ARM_SW (INT32) | Arm switch channel Comment: Use it to arm/disarm via switch instead of default throttle stick. If this is assigned, arming and disarming via stick is disabled. Values:
| 0 > 18 | 0 | ||
RC_MAP_FLAPS (INT32) | Flaps channel Values:
| 0 > 18 | 0 | ||
RC_MAP_FLTMODE (INT32) | Single channel flight mode selection Comment: If this parameter is non-zero, flight modes are only selected by this channel and are assigned to six slots. Values:
| 0 > 18 | 0 | ||
RC_MAP_GEAR_SW (INT32) | Landing gear switch channel Values:
| 0 > 18 | 0 | ||
RC_MAP_KILL_SW (INT32) | Emergency Kill switch channel Values:
| 0 > 18 | 0 | ||
RC_MAP_LOITER_SW (INT32) | Loiter switch channel Values:
| 0 > 18 | 0 | ||
RC_MAP_MAN_SW (INT32) | Manual switch channel mapping Values:
| 0 > 18 | 0 | ||
RC_MAP_MODE_SW (INT32) | Mode switch channel mapping Comment: This is the main flight mode selector. The channel index (starting from 1 for channel 1) indicates which channel should be used for deciding about the main mode. A value of zero indicates the switch is not assigned. Values:
| 0 > 18 | 0 | ||
RC_MAP_OFFB_SW (INT32) | Offboard switch channel Values:
| 0 > 18 | 0 | ||
RC_MAP_POSCTL_SW (INT32) | Position Control switch channel Values:
| 0 > 18 | 0 | ||
RC_MAP_RATT_SW (INT32) | Rattitude switch channel Values:
| 0 > 18 | 0 | ||
RC_MAP_RETURN_SW (INT32) | Return switch channel Values:
| 0 > 18 | 0 | ||
RC_MAP_STAB_SW (INT32) | Stabilize switch channel mapping Values:
| 0 > 18 | 0 | ||
RC_MAP_TRANS_SW (INT32) | VTOL transition switch channel mapping Values:
| 0 > 18 | 0 | ||
RC_OFFB_TH (FLOAT) | Threshold for selecting offboard mode Comment: 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel | -1 > 1 | 0.5 | ||
RC_POSCTL_TH (FLOAT) | Threshold for selecting posctl mode Comment: 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel | -1 > 1 | 0.5 | ||
RC_RATT_TH (FLOAT) | Threshold for selecting rattitude mode Comment: 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel | -1 > 1 | 0.5 | ||
RC_RETURN_TH (FLOAT) | Threshold for selecting return to launch mode Comment: 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel | -1 > 1 | 0.5 | ||
RC_STAB_TH (FLOAT) | Threshold for the stabilize switch Comment: 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel | -1 > 1 | 0.5 | ||
RC_TRANS_TH (FLOAT) | Threshold for the VTOL transition switch Comment: 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel | -1 > 1 | 0.25 |
Return Mode
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
RTL_CONE_ANG (INT32) | Half-angle of the RTL cone Comment: Defines the half-angle of the cone which defines the vehicle RTL behavior. Values:
| 0 > 90 | 0 | degrees |
RTL_DESCEND_ALT (FLOAT) | Return mode loiter altitude Comment: Stay at this altitude above home position after RTL descending. Land (i.e. slowly descend) from this altitude if autolanding allowed. | 2 > 100 (0.5) | 30 | m |
RTL_LAND_DELAY (FLOAT) | Return mode delay Comment: Delay after descend before landing in Return mode. If set to -1 the system will not land but loiter at RTL_DESCEND_ALT. | -1 > 300 (0.5) | -1.0 | s |
RTL_MIN_DIST (FLOAT) | Minimum distance to trigger rising to a safe altitude Comment: If the system is horizontally closer than this distance to home it will land straight on home instead of raising to the return altitude first. | 0.5 > 20 (0.5) | 5.0 | m |
RTL_RETURN_ALT (FLOAT) | RTL altitude Comment: Altitude to fly back in RTL in meters | 0 > 150 (0.5) | 60 | m |
RTL_TYPE (INT32) | Return type Comment: Fly straight to the home location or planned mission landing and land there or use the planned mission to get to those points. Values:
| 0 |
Roboclaw
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
RBCLW_SER_CFG (INT32) | Serial Configuration for Roboclaw Driver Comment: Configure on which serial port to run Roboclaw Driver. Values:
Reboot required: true | 0 |
Roboclaw driver
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
RBCLW_ADDRESS (INT32) | Address of the Roboclaw Comment: The Roboclaw can be configured to have an address from 0x80 to 0x87, inclusive. It must be configured to match this parameter. Values:
| 128 > 135 | 128 | |
RBCLW_BAUD (INT32) | Roboclaw serial baud rate Comment: Baud rate of the serial communication with the Roboclaw. The Roboclaw must be configured to match this rate. Values:
Reboot required: true | 2400 > 460800 | 2400 | |
RBCLW_COUNTS_REV (INT32) | Encoder counts per revolution Comment: Number of encoder counts for one revolution. The roboclaw treats analog encoders (potentiometers) as having 2047 counts per rev. The default value of 1200 corresponds to the default configuration of the Aion R1 rover. | 1 > ? | 1200 | |
RBCLW_READ_PER (INT32) | Encoder read period Comment: How long to wait, in Milliseconds, between reading wheel encoder values over Uart from the Roboclaw | 1 > 1000 | 10 | ms |
RBCLW_WRITE_PER (INT32) | Uart write period Comment: How long to wait, in Milliseconds, between writing actuator controls over Uart to the Roboclaw | 1 > 1000 | 10 | ms |
Rover Position Control
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
GND_L1_DAMPING (FLOAT) | L1 damping Comment: Damping factor for L1 control. | 0.6 > 0.9 (0.05) | 0.75 | |
GND_L1_DIST (FLOAT) | L1 distance Comment: This is the waypoint radius | 0.0 > 100.0 (0.1) | 5.0 | m |
GND_L1_PERIOD (FLOAT) | L1 period Comment: This is the L1 distance and defines the tracking point ahead of the rover it’s following. Using values around 2-5 for a traxxas stampede. Shorten slowly during tuning until response is sharp without oscillation. | 0.0 > 50.0 (0.5) | 10.0 | m |
GND_MAX_ANG (FLOAT) | 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 | 0.0 > 3.14159 (0.01) | 0.7854 | rad |
GND_SPEED_D (FLOAT) | Speed proportional gain Comment: This is the derivative gain for the speed closed loop controller | 0.00 > 50.0 (0.005) | 0.0 | %m/s |
GND_SPEED_I (FLOAT) | Speed Integral gain Comment: This is the integral gain for the speed closed loop controller | 0.00 > 50.0 (0.005) | 0.1 | %m/s |
GND_SPEED_IMAX (FLOAT) | Speed integral maximum value Comment: This is the maxim value the integral can reach to prevent wind-up. | 0.005 > 50.0 (0.005) | 1.0 | %m/s |
GND_SPEED_MAX (FLOAT) | Maximum ground speed | 0.0 > 40 (0.5) | 10.0 | m/s |
GND_SPEED_P (FLOAT) | Speed proportional gain Comment: This is the proportional gain for the speed closed loop controller | 0.005 > 50.0 (0.005) | 2.0 | %m/s |
GND_SPEED_THR_SC (FLOAT) | Speed to throttle scaler Comment: This is a gain to map the speed control output to the throttle linearly. | 0.005 > 50.0 (0.005) | 1.0 | %m/s |
GND_SPEED_TRIM (FLOAT) | Trim ground speed | 0.0 > 40 (0.5) | 3.0 | m/s |
GND_SP_CTRL_MODE (INT32) | Control mode for speed Comment: This allows the user to choose between closed loop gps speed or open loop cruise throttle speed Values:
| 0 > 1 | 1 | |
GND_THR_CRUISE (FLOAT) | Cruise throttle Comment: This is the throttle setting required to achieve the desired cruise speed. 10% is ok for a traxxas stampede vxl with ESC set to training mode | 0.0 > 1.0 (0.01) | 0.1 | norm |
GND_THR_IDLE (FLOAT) | Idle throttle Comment: This is the minimum throttle while on the ground, it should be 0 for a rover | 0.0 > 0.4 (0.01) | 0.0 | norm |
GND_THR_MAX (FLOAT) | Throttle limit max Comment: This is the maximum throttle % that can be used by the controller. For a Traxxas stampede vxl with the ESC set to training, 30 % is enough | 0.0 > 1.0 (0.01) | 0.3 | norm |
GND_THR_MIN (FLOAT) | Throttle limit min Comment: This is the minimum throttle % that can be used by the controller. Set to 0 for rover | 0.0 > 1.0 (0.01) | 0.0 | norm |
GND_WHEEL_BASE (FLOAT) | Distance from front axle to rear axle | 0.0 > ? (0.01) | 2.0 | m |
Runway Takeoff
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
RWTO_AIRSPD_SCL (FLOAT) | Min. airspeed scaling factor for takeoff. Pitch up will be commanded when the following airspeed is reached: FW_AIRSPD_MIN * RWTO_AIRSPD_SCL | 0.0 > 2.0 (0.01) | 1.3 | norm |
RWTO_HDG (INT32) | Specifies which heading should be held during runnway takeoff Comment: 0: airframe heading, 1: heading towards takeoff waypoint Values:
| 0 > 1 | 0 | |
RWTO_MAX_PITCH (FLOAT) | 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 | 0.0 > 60.0 (0.5) | 20.0 | deg |
RWTO_MAX_ROLL (FLOAT) | Max roll during climbout. Roll is limited during climbout to ensure enough lift and prevents aggressive navigation before we’re on a safe height | 0.0 > 60.0 (0.5) | 25.0 | deg |
RWTO_MAX_THR (FLOAT) | Max throttle during runway takeoff. (Can be used to test taxi on runway) | 0.0 > 1.0 (0.01) | 1.0 | norm |
RWTO_NAV_ALT (FLOAT) | 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 | 0.0 > 100.0 (1) | 5.0 | m |
RWTO_PSP (FLOAT) | Pitch setpoint during taxi / before takeoff airspeed is reached. A taildragger with stearable wheel might need to pitch up a little to keep it’s wheel on the ground before airspeed to takeoff is reached | 0.0 > 20.0 (0.5) | 0.0 | deg |
RWTO_TKOFF (INT32) | Runway takeoff with landing gear | 0 |
SD Logging
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
SDLOGDIRS_MAX (INT32) | Maximum number of log directories to keep Comment: If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files. Reboot required: true | 0 > 1000 | 0 | |
SDLOG_MISSION (INT32) | Mission Log Comment: If enabled, a small additional “mission” log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more). Values:
Reboot required: true | 0 | ||
SDLOG_MODE (INT32) | Logging Mode Comment: Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. Values:
Reboot required: true | 0 | ||
SDLOG_PROFILE (INT32) | Logging topic profile (integer bitmask) Comment: This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis and estimator replay, while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and Magnetomer data) 7 : Topics for computer vision and collision avoidance Bitmask:
Reboot required: true | 0 > 255 | 3 | |
SDLOG_UTC_OFFSET (INT32) | UTC offset (unit: min) Comment: the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (960) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets | -1000 > 1000 | 0 | min |
SDLOG_UUID (INT32) | Log UUID Comment: If set to 1, add an ID to the log, which uniquely identifies the vehicle | 1 |
SITL
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
SIM_BAT_DRAIN (FLOAT) | Simulator Battery drain interval | 1 > 86400 (1) | 60 | s |
SIM_BAT_MIN_PCT (FLOAT) | 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 | 0 > 100 (0.1) | 50.0 | % |
Sensor Calibration
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
CAL_ACC0_EN (INT32) | Accelerometer 0 enabled | 1 | ||
CAL_ACC0_ID (INT32) | ID of the Accelerometer that the calibration is for | 0 | ||
CAL_ACC0_XOFF (FLOAT) | Accelerometer X-axis offset | 0.0 | ||
CAL_ACC0_XSCALE (FLOAT) | Accelerometer X-axis scaling factor | 1.0 | ||
CAL_ACC0_YOFF (FLOAT) | Accelerometer Y-axis offset | 0.0 | ||
CAL_ACC0_YSCALE (FLOAT) | Accelerometer Y-axis scaling factor | 1.0 | ||
CAL_ACC0_ZOFF (FLOAT) | Accelerometer Z-axis offset | 0.0 | ||
CAL_ACC0_ZSCALE (FLOAT) | Accelerometer Z-axis scaling factor | 1.0 | ||
CAL_ACC1_EN (INT32) | Accelerometer 1 enabled | 1 | ||
CAL_ACC1_ID (INT32) | ID of the Accelerometer that the calibration is for | 0 | ||
CAL_ACC1_XOFF (FLOAT) | Accelerometer X-axis offset | 0.0 | ||
CAL_ACC1_XSCALE (FLOAT) | Accelerometer X-axis scaling factor | 1.0 | ||
CAL_ACC1_YOFF (FLOAT) | Accelerometer Y-axis offset | 0.0 | ||
CAL_ACC1_YSCALE (FLOAT) | Accelerometer Y-axis scaling factor | 1.0 | ||
CAL_ACC1_ZOFF (FLOAT) | Accelerometer Z-axis offset | 0.0 | ||
CAL_ACC1_ZSCALE (FLOAT) | Accelerometer Z-axis scaling factor | 1.0 | ||
CAL_ACC2_EN (INT32) | Accelerometer 2 enabled | 1 | ||
CAL_ACC2_ID (INT32) | ID of the Accelerometer that the calibration is for | 0 | ||
CAL_ACC2_XOFF (FLOAT) | Accelerometer X-axis offset | 0.0 | ||
CAL_ACC2_XSCALE (FLOAT) | Accelerometer X-axis scaling factor | 1.0 | ||
CAL_ACC2_YOFF (FLOAT) | Accelerometer Y-axis offset | 0.0 | ||
CAL_ACC2_YSCALE (FLOAT) | Accelerometer Y-axis scaling factor | 1.0 | ||
CAL_ACC2_ZOFF (FLOAT) | Accelerometer Z-axis offset | 0.0 | ||
CAL_ACC2_ZSCALE (FLOAT) | Accelerometer Z-axis scaling factor | 1.0 | ||
CAL_ACC_PRIME (INT32) | Primary accel ID | 0 | ||
CAL_BARO_PRIME (INT32) | Primary baro ID | 0 | ||
CAL_GYRO0_EN (INT32) | Gyro 0 enabled | 1 | ||
CAL_GYRO0_ID (INT32) | ID of the Gyro that the calibration is for | 0 | ||
CAL_GYRO0_XOFF (FLOAT) | Gyro X-axis offset | 0.0 | ||
CAL_GYRO0_XSCALE (FLOAT) | Gyro X-axis scaling factor | 1.0 | ||
CAL_GYRO0_YOFF (FLOAT) | Gyro Y-axis offset | 0.0 | ||
CAL_GYRO0_YSCALE (FLOAT) | Gyro Y-axis scaling factor | 1.0 | ||
CAL_GYRO0_ZOFF (FLOAT) | Gyro Z-axis offset | 0.0 | ||
CAL_GYRO0_ZSCALE (FLOAT) | Gyro Z-axis scaling factor | 1.0 | ||
CAL_GYRO1_EN (INT32) | Gyro 1 enabled | 1 | ||
CAL_GYRO1_ID (INT32) | ID of the Gyro that the calibration is for | 0 | ||
CAL_GYRO1_XOFF (FLOAT) | Gyro X-axis offset | 0.0 | ||
CAL_GYRO1_XSCALE (FLOAT) | Gyro X-axis scaling factor | 1.0 | ||
CAL_GYRO1_YOFF (FLOAT) | Gyro Y-axis offset | 0.0 | ||
CAL_GYRO1_YSCALE (FLOAT) | Gyro Y-axis scaling factor | 1.0 | ||
CAL_GYRO1_ZOFF (FLOAT) | Gyro Z-axis offset | 0.0 | ||
CAL_GYRO1_ZSCALE (FLOAT) | Gyro Z-axis scaling factor | 1.0 | ||
CAL_GYRO2_EN (INT32) | Gyro 2 enabled | 1 | ||
CAL_GYRO2_ID (INT32) | ID of the Gyro that the calibration is for | 0 | ||
CAL_GYRO2_XOFF (FLOAT) | Gyro X-axis offset | 0.0 | ||
CAL_GYRO2_XSCALE (FLOAT) | Gyro X-axis scaling factor | 1.0 | ||
CAL_GYRO2_YOFF (FLOAT) | Gyro Y-axis offset | 0.0 | ||
CAL_GYRO2_YSCALE (FLOAT) | Gyro Y-axis scaling factor | 1.0 | ||
CAL_GYRO2_ZOFF (FLOAT) | Gyro Z-axis offset | 0.0 | ||
CAL_GYRO2_ZSCALE (FLOAT) | Gyro Z-axis scaling factor | 1.0 | ||
CAL_GYRO_PRIME (INT32) | Primary gyro ID | 0 | ||
CAL_MAG0_EN (INT32) | Mag 0 enabled | 1 | ||
CAL_MAG0_ID (INT32) | ID of Magnetometer the calibration is for | 0 | ||
CAL_MAG0_ROT (INT32) | Rotation of magnetometer 0 relative to airframe Comment: An internal magnetometer will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Values:
Reboot required: true | -1 > 30 | -1 | |
CAL_MAG0_XOFF (FLOAT) | Magnetometer X-axis offset | 0.0 | ||
CAL_MAG0_XSCALE (FLOAT) | Magnetometer X-axis scaling factor | 1.0 | ||
CAL_MAG0_YOFF (FLOAT) | Magnetometer Y-axis offset | 0.0 | ||
CAL_MAG0_YSCALE (FLOAT) | Magnetometer Y-axis scaling factor | 1.0 | ||
CAL_MAG0_ZOFF (FLOAT) | Magnetometer Z-axis offset | 0.0 | ||
CAL_MAG0_ZSCALE (FLOAT) | Magnetometer Z-axis scaling factor | 1.0 | ||
CAL_MAG1_EN (INT32) | Mag 1 enabled | 1 | ||
CAL_MAG1_ID (INT32) | ID of Magnetometer the calibration is for | 0 | ||
CAL_MAG1_ROT (INT32) | Rotation of magnetometer 1 relative to airframe Comment: An internal magnetometer will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Values:
Reboot required: true | -1 > 30 | -1 | |
CAL_MAG1_XOFF (FLOAT) | Magnetometer X-axis offset | 0.0 | ||
CAL_MAG1_XSCALE (FLOAT) | Magnetometer X-axis scaling factor | 1.0 | ||
CAL_MAG1_YOFF (FLOAT) | Magnetometer Y-axis offset | 0.0 | ||
CAL_MAG1_YSCALE (FLOAT) | Magnetometer Y-axis scaling factor | 1.0 | ||
CAL_MAG1_ZOFF (FLOAT) | Magnetometer Z-axis offset | 0.0 | ||
CAL_MAG1_ZSCALE (FLOAT) | Magnetometer Z-axis scaling factor | 1.0 | ||
CAL_MAG2_EN (INT32) | Mag 2 enabled | 1 | ||
CAL_MAG2_ID (INT32) | ID of Magnetometer the calibration is for | 0 | ||
CAL_MAG2_ROT (INT32) | Rotation of magnetometer 2 relative to airframe Comment: An internal magnetometer will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Values:
Reboot required: true | -1 > 30 | -1 | |
CAL_MAG2_XOFF (FLOAT) | Magnetometer X-axis offset | 0.0 | ||
CAL_MAG2_XSCALE (FLOAT) | Magnetometer X-axis scaling factor | 1.0 | ||
CAL_MAG2_YOFF (FLOAT) | Magnetometer Y-axis offset | 0.0 | ||
CAL_MAG2_YSCALE (FLOAT) | Magnetometer Y-axis scaling factor | 1.0 | ||
CAL_MAG2_ZOFF (FLOAT) | Magnetometer Z-axis offset | 0.0 | ||
CAL_MAG2_ZSCALE (FLOAT) | Magnetometer Z-axis scaling factor | 1.0 | ||
CAL_MAG3_EN (INT32) | Mag 3 enabled | 1 | ||
CAL_MAG3_ID (INT32) | ID of Magnetometer the calibration is for | 0 | ||
CAL_MAG3_ROT (INT32) | Rotation of magnetometer 2 relative to airframe Comment: An internal magnetometer will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Values:
Reboot required: true | -1 > 30 | -1 | |
CAL_MAG3_XOFF (FLOAT) | Magnetometer X-axis offset | 0.0 | ||
CAL_MAG3_XSCALE (FLOAT) | Magnetometer X-axis scaling factor | 1.0 | ||
CAL_MAG3_YOFF (FLOAT) | Magnetometer Y-axis offset | 0.0 | ||
CAL_MAG3_YSCALE (FLOAT) | Magnetometer Y-axis scaling factor | 1.0 | ||
CAL_MAG3_ZOFF (FLOAT) | Magnetometer Z-axis offset | 0.0 | ||
CAL_MAG3_ZSCALE (FLOAT) | Magnetometer Z-axis scaling factor | 1.0 | ||
CAL_MAG_PRIME (INT32) | Primary mag ID | 0 | ||
SENS_DPRES_ANSC (FLOAT) | Differential pressure sensor analog scaling Comment: Pick the appropriate scaling from the datasheet. this number defines the (linear) conversion from voltage to Pascal (pa). For the MPXV7002DP this is 1000. NOTE: If the sensor always registers zero, try switching the static and dynamic tubes. | 0 | ||
SENS_DPRES_OFF (FLOAT) | Differential pressure sensor offset Comment: The offset (zero-reading) in Pascal | 0.0 | ||
SENS_FLOW_MAXHGT (FLOAT) | Maximum height above ground when reliant on optical flow Comment: This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably. The height setpoint will be limited to be no greater than this value when the navigation system is completely reliant on optical flow data and the height above ground estimate is valid. The sensor may be usable above this height, but accuracy will progressively degrade. | 1.0 > 25.0 (0.1) | 3.0 | m |
SENS_FLOW_MAXR (FLOAT) | 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 | 1.0 > ? | 2.5 | rad/s |
SENS_FLOW_MINHGT (FLOAT) | Minimum height above ground when reliant on optical flow Comment: This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably. The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus. | 0.0 > 1.0 (0.1) | 0.7 | m |
Sensors
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
CAL_AIR_CMODEL (INT32) | Airspeed sensor compensation model for the SDP3x Comment: Model with Pitot CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Model without Pitot (1.5 mm tubes) CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Tube Pressure Drop CAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot. Values:
| 0 | ||
CAL_AIR_TUBED_MM (FLOAT) | Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation | 0.1 > 100 | 1.5 | millimeter |
CAL_AIR_TUBELEN (FLOAT) | Airspeed sensor tube length Comment: See the CAL_AIR_CMODEL explanation on how this parameter should be set. | 0.01 > 2.00 | 0.2 | meter |
CAL_MAG_SIDES (INT32) | Bitfield selecting mag sides for calibration Comment: DETECT_ORIENTATION_TAIL_DOWN = 1 DETECT_ORIENTATION_NOSE_DOWN = 2 DETECT_ORIENTATION_LEFT = 4 DETECT_ORIENTATION_RIGHT = 8 DETECT_ORIENTATION_UPSIDE_DOWN = 16 DETECT_ORIENTATION_RIGHTSIDE_UP = 32 Values:
| 34 > 63 | 63 | |
IMU_ACCEL_CUTOFF (FLOAT) | Driver level cutoff frequency for accel Comment: The cutoff frequency for the 2nd order butterworth filter on the accel driver. This features is currently supported by the mpu6000 and mpu9250. This only affects the signal sent to the controllers, not the estimators. 0 disables the filter. Reboot required: true | 0 > 1000 | 30.0 | Hz |
IMU_GYRO_CUTOFF (FLOAT) | Driver level cutoff frequency for gyro Comment: The cutoff frequency for the 2nd order butterworth filter on the gyro driver. This features is currently supported by the mpu6000 and mpu9250. This only affects the signal sent to the controllers, not the estimators. 0 disables the filter. Reboot required: true | 0 > 1000 | 30.0 | Hz |
INA226_CONFIG (INT32) | INA226 Power Monitor Config | 0 > 65535 (1) | 18139 | u |
INA226_CURRENT (FLOAT) | INA226 Power Monitor Max Current | 0.1 > 200.0 (0.1) | 164.0 | |
INA226_SHUNT (FLOAT) | INA226 Power Monitor Shunt | 0.000000001 > 0.1 (.000000001) | 0.0005 | |
SENS_BARO_QNH (FLOAT) | QNH for barometer | 500 > 1500 | 1013.25 | hPa |
SENS_BOARD_ROT (INT32) | Board rotation Comment: This parameter defines the rotation of the FMU board relative to the platform. Values:
Reboot required: true | 0 | ||
SENS_BOARD_X_OFF (FLOAT) | Board rotation X (Roll) offset Comment: This parameter defines a rotational offset in degrees around the X (Roll) axis It allows the user to fine tune the board offset in the event of misalignment. | 0.0 | deg | |
SENS_BOARD_Y_OFF (FLOAT) | Board rotation Y (Pitch) offset Comment: This parameter defines a rotational offset in degrees around the Y (Pitch) axis. It allows the user to fine tune the board offset in the event of misalignment. | 0.0 | deg | |
SENS_BOARD_Z_OFF (FLOAT) | Board rotation Z (YAW) offset Comment: This parameter defines a rotational offset in degrees around the Z (Yaw) axis. It allows the user to fine tune the board offset in the event of misalignment. | 0.0 | deg | |
SENS_CM8JL65_CFG (INT32) | Serial Configuration for Lanbao PSK-CM8JL65-CC5 Comment: Configure on which serial port to run Lanbao PSK-CM8JL65-CC5. Values:
Reboot required: true | 0 | ||
SENS_CM8JL65_R_0 (INT32) | Distance Sensor Rotation Comment: Distance Sensor Rotation as MAV_SENSOR_ORIENTATION enum Values:
Reboot required: True | 25 | ||
SENS_EN_BATT (INT32) | SMBUS Smart battery driver (BQ40Z50) Reboot required: true | 0 | ||
SENS_EN_LL40LS (INT32) | Lidar-Lite (LL40LS) Values:
Reboot required: true | 0 > 2 | 0 | |
SENS_EN_MB12XX (INT32) | Maxbotix Sonar (mb12xx) Reboot required: true | 0 | ||
SENS_EN_MPDT (INT32) | Enable Mappydot rangefinder (i2c) Values:
Reboot required: true | 0 > 1 | 0 | |
SENS_EN_PGA460 (INT32) | PGA460 Ultrasonic driver (PGA460) Reboot required: true | 0 | ||
SENS_EN_PX4FLOW (INT32) | PX4 Flow Optical Flow Reboot required: true | 0 | ||
SENS_EN_SF0X (INT32) | Lightware Laser Rangefinder hardware model Values:
Reboot required: true | 1 | ||
SENS_EN_SF1XX (INT32) | Lightware SF1xx/SF20/LW20 laser rangefinder (i2c) Values:
Reboot required: true | 0 > 5 | 0 | |
SENS_EN_THERMAL (INT32) | Thermal control of sensor temperature Values:
| -1 | ||
SENS_EN_TRANGER (INT32) | TeraRanger Rangefinder (i2c) Values:
Reboot required: true | 0 > 3 | 0 | |
SENS_FLOW_ROT (INT32) | PX4Flow board rotation Comment: This parameter defines the yaw rotation of the PX4FLOW board relative to the vehicle body frame. Zero rotation is defined as X on flow board pointing towards front of vehicle. The recommneded installation default for the PX4FLOW board is with the Y axis forward (270 deg yaw). Values:
Reboot required: true | 6 | ||
SENS_IMU_TEMP (FLOAT) | Target IMU temperature | 0 > 85.0 | 55.0 | C |
SENS_IMU_TEMP_I (FLOAT) | IMU heater controller integrator gain value | 0 > 1.0 | 0.025 | microseconds/C |
SENS_IMU_TEMP_P (FLOAT) | IMU heater controller proportional gain value | 0 > 2.0 | 1.0 | microseconds/C |
SENS_LEDDAR1_CFG (INT32) | Serial Configuration for LeddarOne Rangefinder Comment: Configure on which serial port to run LeddarOne Rangefinder. Values:
Reboot required: true | 0 | ||
SENS_MB12_0_ROT (INT32) | MaxBotix MB12XX Sensor 0 Rotation Comment: This parameter defines the rotation of the sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MB12_10_ROT (INT32) | MaxBotix MB12XX Sensor 10 Rotation Comment: This parameter defines the rotation of the sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MB12_11_ROT (INT32) | MaxBotix MB12XX Sensor 12 Rotation Comment: This parameter defines the rotation of the sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MB12_1_ROT (INT32) | MaxBotix MB12XX Sensor 1 Rotation Comment: This parameter defines the rotation of the sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MB12_2_ROT (INT32) | MaxBotix MB12XX Sensor 2 Rotation Comment: This parameter defines the rotation of the sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MB12_3_ROT (INT32) | MaxBotix MB12XX Sensor 3 Rotation Comment: This parameter defines the rotation of the sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MB12_4_ROT (INT32) | MaxBotix MB12XX Sensor 4 Rotation Comment: This parameter defines the rotation of the sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MB12_5_ROT (INT32) | MaxBotix MB12XX Sensor 5 Rotation Comment: This parameter defines the rotation of the sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MB12_6_ROT (INT32) | MaxBotix MB12XX Sensor 6 Rotation Comment: This parameter defines the rotation of the sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MB12_7_ROT (INT32) | MaxBotix MB12XX Sensor 7 Rotation Comment: This parameter defines the rotation of the sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MB12_8_ROT (INT32) | MaxBotix MB12XX Sensor 8 Rotation Comment: This parameter defines the rotation of the sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MB12_9_ROT (INT32) | MaxBotix MB12XX Sensor 9 Rotation Comment: This parameter defines the rotation of the sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MPDT0_ROT (INT32) | MappyDot Sensor 0 Rotation Comment: This parameter defines the rotation of the Mappydot sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MPDT10_ROT (INT32) | MappyDot Sensor 10 Rotation Comment: This parameter defines the rotation of the Mappydot sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MPDT11_ROT (INT32) | MappyDot Sensor 12 Rotation Comment: This parameter defines the rotation of the Mappydot sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MPDT1_ROT (INT32) | MappyDot Sensor 1 Rotation Comment: This parameter defines the rotation of the Mappydot sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MPDT2_ROT (INT32) | MappyDot Sensor 2 Rotation Comment: This parameter defines the rotation of the Mappydot sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MPDT3_ROT (INT32) | MappyDot Sensor 3 Rotation Comment: This parameter defines the rotation of the Mappydot sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MPDT4_ROT (INT32) | MappyDot Sensor 4 Rotation Comment: This parameter defines the rotation of the Mappydot sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MPDT5_ROT (INT32) | MappyDot Sensor 5 Rotation Comment: This parameter defines the rotation of the Mappydot sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MPDT6_ROT (INT32) | MappyDot Sensor 6 Rotation Comment: This parameter defines the rotation of the Mappydot sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MPDT7_ROT (INT32) | MappyDot Sensor 7 Rotation Comment: This parameter defines the rotation of the Mappydot sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MPDT8_ROT (INT32) | MappyDot Sensor 8 Rotation Comment: This parameter defines the rotation of the Mappydot sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_MPDT9_ROT (INT32) | MappyDot Sensor 9 Rotation Comment: This parameter defines the rotation of the Mappydot sensor relative to the platform. Values:
Reboot required: true | 0 > 7 | 0 | |
SENS_SF0X_CFG (INT32) | Serial Configuration for Lightware Laser Rangefinder Comment: Configure on which serial port to run Lightware Laser Rangefinder. Values:
Reboot required: true | 0 | ||
SENS_TEMP_ID (INT32) | Target IMU device ID to regulate temperature | 1442826 | ||
SENS_TFMINI_CFG (INT32) | Serial Configuration for Benewake TFmini Rangefinder Comment: Configure on which serial port to run Benewake TFmini Rangefinder. Values:
Reboot required: true | 0 | ||
SENS_ULAND_CFG (INT32) | Serial Configuration for uLanding Radar Comment: Configure on which serial port to run uLanding Radar. Values:
Reboot required: true | 0 |
Serial
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
RC_PORT_CONFIG (INT32) | Serial Configuration for RC Input Driver Comment: Configure on which serial port to run RC Input Driver. Setting this to ‘Disabled’ will use a board-specific default port for RC input. Values:
Reboot required: true | 300 | ||
SER_GPS1_BAUD (INT32) | Baudrate for the GPS 1 Serial Port Comment: Configure the Baudrate for the GPS 1 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. Values:
Reboot required: true | 0 | ||
SER_GPS2_BAUD (INT32) | Baudrate for the GPS 2 Serial Port Comment: Configure the Baudrate for the GPS 2 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. Values:
Reboot required: true | 0 | ||
SER_RC_BAUD (INT32) | Baudrate for the Radio Controller Serial Port Comment: Configure the Baudrate for the Radio Controller Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. Values:
Reboot required: true | 0 | ||
SER_TEL1_BAUD (INT32) | Baudrate for the TELEM 1 Serial Port Comment: Configure the Baudrate for the TELEM 1 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. Values:
Reboot required: true | 57600 | ||
SER_TEL2_BAUD (INT32) | Baudrate for the TELEM 2 Serial Port Comment: Configure the Baudrate for the TELEM 2 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. Values:
Reboot required: true | 921600 | ||
SER_TEL3_BAUD (INT32) | Baudrate for the TELEM 3 Serial Port Comment: Configure the Baudrate for the TELEM 3 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. Values:
Reboot required: true | 57600 | ||
SER_TEL4_BAUD (INT32) | Baudrate for the TELEM/SERIAL 4 Serial Port Comment: Configure the Baudrate for the TELEM/SERIAL 4 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. Values:
Reboot required: true | 57600 | ||
SER_URT6_BAUD (INT32) | Baudrate for the UART 6 Serial Port Comment: Configure the Baudrate for the UART 6 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. Values:
Reboot required: true | 57600 |
Simulation In Hardware
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
SIH_IXX (FLOAT) | Vehicle inertia about X axis Comment: The intertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. | 0.0 > ? (0.005) | 0.025 | kgmm |
SIH_IXY (FLOAT) | Vehicle cross term inertia xy Comment: The intertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. | (0.005) | 0.0 | kgmm |
SIH_IXZ (FLOAT) | Vehicle cross term inertia xz Comment: The intertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. | (0.005) | 0.0 | kgmm |
SIH_IYY (FLOAT) | Vehicle inertia about Y axis Comment: The intertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. | 0.0 > ? (0.005) | 0.025 | kgmm |
SIH_IYZ (FLOAT) | Vehicle cross term inertia yz Comment: The intertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. | (0.005) | 0.0 | kgmm |
SIH_IZZ (FLOAT) | Vehicle inertia about Z axis Comment: The intertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. | 0.0 > ? (0.005) | 0.030 | kgmm |
SIH_KDV (FLOAT) | First order drag coefficient Comment: Physical coefficient representing the friction with air particules. The greater this value, the slower the quad will move. Drag force function of velocity: D=-KDVV. The maximum freefall velocity can be computed as V=10MASS/KDV [m/s] | 0.0 > ? (0.05) | 1.0 | N/(m/s) |
SIH_KDW (FLOAT) | First order angular damper coefficient Comment: Physical coefficient representing the friction with air particules during rotations. The greater this value, the slower the quad will rotate. Aerodynamic moment function of body rate: Ma=-KDW*W_B. This value can be set to 0 if unknown. | 0.0 > ? (0.005) | 0.025 | Nm/(rad/s) |
SIH_LOC_H0 (FLOAT) | Initial AMSL ground altitude Comment: This value represents the Above Mean Sea Level (AMSL) altitude where the simulation begins. If using FlightGear as a visual animation, this value can be tweaked such that the vehicle lies on the ground at takeoff. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. | -420.0 > 8848.0 (0.01) | 32.34 | m |
SIH_LOC_LAT0 (INT32) | Initial geodetic latitude Comment: This value represents the North-South location on Earth where the simulation begins. A value of 45 deg should be written 450000000. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. | -850000000 > 850000000 | 454671160 | 1e-7 deg |
SIH_LOC_LON0 (INT32) | Initial geodetic longitude Comment: This value represents the East-West location on Earth where the simulation begins. A value of 45 deg should be written 450000000. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. | -1800000000 > 1800000000 | -737578370 | 1e-7 deg |
SIH_LOC_MU_X (FLOAT) | North magnetic field at the initial location Comment: This value represents the North magnetic field at the initial location. A magnetic field calculator can be found on the NOAA website Note, the values need to be converted from nano Tesla to Gauss LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. | -1.0 > 1.0 (0.001) | 0.179 | Gauss |
SIH_LOC_MU_Y (FLOAT) | East magnetic field at the initial location Comment: This value represents the East magnetic field at the initial location. A magnetic field calculator can be found on the NOAA website Note, the values need to be converted from nano Tesla to Gauss LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. | -1.0 > 1.0 (0.001) | -0.045 | Gauss |
SIH_LOC_MU_Z (FLOAT) | Down magnetic field at the initial location Comment: This value represents the Down magnetic field at the initial location. A magnetic field calculator can be found on the NOAA website Note, the values need to be converted from nano Tesla to Gauss LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. | -1.0 > 1.0 (0.001) | 0.504 | Gauss |
SIH_L_PITCH (FLOAT) | Pitch arm length Comment: This is the arm length generating the pitching moment This value can be measured with a ruler. This corresponds to half the distance between the front and rear motors. | 0.0 > ? (0.05) | 0.2 | m |
SIH_L_ROLL (FLOAT) | Roll arm length Comment: This is the arm length generating the rolling moment This value can be measured with a ruler. This corresponds to half the distance between the left and right motors. | 0.0 > ? (0.05) | 0.2 | m |
SIH_MASS (FLOAT) | Vehicle mass Comment: This value can be measured by weighting the quad on a scale. | 0.0 > ? (0.1) | 1.0 | kg |
SIH_Q_MAX (FLOAT) | Max propeller torque Comment: This is the maximum torque delivered by one propeller when the motor is running at full speed. This value is usually about few percent of the maximum thrust force. | 0.0 > ? (0.05) | 0.1 | Nm |
SIH_T_MAX (FLOAT) | Max propeller thrust force Comment: This is the maximum force delivered by one propeller when the motor is running at full speed. This value is usually about 5 times the mass of the quadrotor. | 0.0 > ? (0.5) | 5.0 | N |
Snapdragon UART ESC
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
UART_ESC_BAUD (INT32) | ESC UART baud rate Comment: Default rate is 250Kbps, whic is used in off-the-shelf QRP ESC products. | 250000 | ||
UART_ESC_MODEL (INT32) | ESC model Comment: See esc_model_t enum definition in uart_esc_dev.h for all supported ESC model enum values. Values:
| 2 | ||
UART_ESC_MOTOR1 (INT32) | Motor 1 Mapping | 4 | ||
UART_ESC_MOTOR2 (INT32) | Motor 2 Mapping | 2 | ||
UART_ESC_MOTOR3 (INT32) | Motor 3 Mapping | 1 | ||
UART_ESC_MOTOR4 (INT32) | Motor 4 Mapping | 3 |
System
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
LED_RGB1_MAXBRT (INT32) | RGB Led brightness limit Comment: Set to 0 to disable, 1 for minimum brightness up to 31 (max) | 0 > 31 | 31 | |
LED_RGB_MAXBRT (INT32) | RGB Led brightness limit Comment: Set to 0 to disable, 1 for minimum brightness up to 15 (max) | 0 > 15 | 15 | |
SYS_AUTOCONFIG (INT32) | Automatically configure default values Comment: Set to 1 to reset parameters on next system startup (setting defaults). Platform-specific values are used if available. RC* parameters are preserved. Values:
| 0 | ||
SYS_AUTOSTART (INT32) | Auto-start script index Comment: CHANGING THIS VALUE REQUIRES A RESTART. Defines the auto-start script used to bootstrap the system. Reboot required: true | 0 > 9999999 | 0 | |
SYS_BL_UPDATE (INT32) | Bootloader update Comment: If enabled, update the bootloader on the next boot. WARNING: do not cut the power during an update process, otherwise you will have to recover using some alternative method (e.g. JTAG). Instructions: - Insert an SD card - Enable this parameter - Reboot the board (plug the power or send a reboot command) - Wait until the board comes back up (or at least 2 minutes) - If it does not come back, check the file bootlog.txt on the SD card Reboot required: true | 0 | ||
SYS_CAL_ACCEL (INT32) | Enable auto start of accelerometer thermal calibration at the next power up Comment: 0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the the temperature calibration starts. default (0, no calibration) | 0 > 1 | 0 | |
SYS_CAL_BARO (INT32) | Enable auto start of barometer thermal calibration at the next power up Comment: 0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the the temperature calibration starts. default (0, no calibration) | 0 > 1 | 0 | |
SYS_CAL_GYRO (INT32) | Enable auto start of rate gyro thermal calibration at the next power up Comment: 0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the the temperature calibration starts. default (0, no calibration) | 0 > 1 | 0 | |
SYS_CAL_TDEL (INT32) | Required temperature rise during thermal calibration Comment: A temperature increase greater than this value is required during calibration. Calibration will complete for each sensor when the temperature increase above the starting temeprature exceeds the value set by SYS_CAL_TDEL. If the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit. | 10 > ? | 24 | deg C |
SYS_CAL_TMAX (INT32) | Maximum starting temperature for thermal calibration Comment: Temperature calibration will not start if the temperature of any sensor is higher than the value set by SYS_CAL_TMAX. | 10 | deg C | |
SYS_CAL_TMIN (INT32) | Minimum starting temperature for thermal calibration Comment: Temperature calibration for each sensor will ignore data if the temperature is lower than the value set by SYS_CAL_TMIN. | 5 | deg C | |
SYS_FMU_TASK (INT32) | Run the FMU as a task to reduce latency Comment: If true, the FMU will run in a separate task instead of on the work queue. Set this if low latency is required, for example for racing. This is a trade-off between RAM usage and latency: running as a task, it requires a separate stack and directly polls on the control topics, whereas running on the work queue, it runs at a fixed update rate. Reboot required: true | 1 | ||
SYS_HAS_BARO (INT32) | Control if the vehicle has a barometer Comment: Disable this if the board has no barometer, such as some of the the Omnibus F4 SD variants. If disabled, the preflight checks will not check for the presence of a barometer. Reboot required: true | 1 | ||
SYS_HAS_MAG (INT32) | Control if the vehicle has a magnetometer Comment: Disable this if the board has no magnetometer, such as the Omnibus F4 SD. If disabled, the preflight checks will not check for the presence of a magnetometer. Reboot required: true | 1 | ||
SYS_HITL (INT32) | Enable HITL/SIH mode on next boot Comment: While enabled the system will boot in Hardware-In-The-Loop (HITL) or Simulation-In-Hardware (SIH) mode and not enable all sensors and checks. When disabled the same vehicle can be flown normally. Values:
Reboot required: true | 0 | ||
SYS_MC_EST_GROUP (INT32) | Set multicopter estimator group Comment: Set the group of estimators used for multicopters and VTOLs Values:
Reboot required: true | 2 | ||
SYS_PARAM_VER (INT32) | Parameter version Comment: This is used internally only: an airframe configuration might set an expected parameter version value via PARAM_DEFAULTS_VER. This is checked on bootup against SYS_PARAM_VER, and if they do not match, parameters from the airframe configuration are reloaded. | 0 > ? | 1 | |
SYS_RESTART_TYPE (INT32) | Set restart type Comment: Set by px4io to indicate type of restart Values:
| 0 > 2 | 2 | |
SYS_STCK_EN (INT32) | Enable stack checking | 1 | ||
SYS_USE_IO (INT32) | Set usage of IO board Comment: Can be used to use a standard startup script but with a FMU only set-up. Set to 0 to force the FMU only set-up. Reboot required: true | 0 > 1 | 1 |
Telemetry
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
TEL_BST_EN (INT32) | Blacksheep telemetry Enable Comment: If true, the FMU will try to connect to Blacksheep telemetry on start up Reboot required: true | 0 | ||
TEL_FRSKY_CONFIG (INT32) | Serial Configuration for FrSky Telemetry Comment: Configure on which serial port to run FrSky Telemetry. Values:
Reboot required: true | 0 | ||
TEL_HOTT_CONFIG (INT32) | Serial Configuration for HoTT Telemetry Comment: Configure on which serial port to run HoTT Telemetry. Values:
Reboot required: true | 0 |
Testing
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
TEST_1 (INT32) |
| 2 | ||
TEST_2 (INT32) |
| 4 | ||
TEST_3 (FLOAT) |
| 5.0 | ||
TEST_D (FLOAT) |
| 0.01 | ||
TEST_DEV (FLOAT) |
| 2.0 | ||
TEST_D_LP (FLOAT) |
| 10.0 | ||
TEST_HP (FLOAT) |
| 10.0 | ||
TEST_I (FLOAT) |
| 0.1 | ||
TEST_I_MAX (FLOAT) |
| 1.0 | ||
TEST_LP (FLOAT) |
| 10.0 | ||
TEST_MAX (FLOAT) |
| 1.0 | ||
TEST_MEAN (FLOAT) |
| 1.0 | ||
TEST_MIN (FLOAT) |
| -1.0 | ||
TEST_P (FLOAT) |
| 0.2 | ||
TEST_PARAMS (INT32) |
| 12345678 | ||
TEST_RC2_X (INT32) |
| 16 | ||
TEST_RC_X (INT32) |
| 8 | ||
TEST_TRIM (FLOAT) |
| 0.5 |
Thermal Compensation
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
TC_A0_ID (INT32) | ID of Accelerometer that the calibration is for | 0 | ||
TC_A0_SCL_0 (FLOAT) | Accelerometer scale factor - X axis | 1.0 | ||
TC_A0_SCL_1 (FLOAT) | Accelerometer scale factor - Y axis | 1.0 | ||
TC_A0_SCL_2 (FLOAT) | Accelerometer scale factor - Z axis | 1.0 | ||
TC_A0_TMAX (FLOAT) | Accelerometer calibration maximum temperature | 100.0 | ||
TC_A0_TMIN (FLOAT) | Accelerometer calibration minimum temperature | 0.0 | ||
TC_A0_TREF (FLOAT) | Accelerometer calibration reference temperature | 25.0 | ||
TC_A0_X0_0 (FLOAT) | Accelerometer offset temperature ^0 polynomial coefficient - X axis | 0.0 | ||
TC_A0_X0_1 (FLOAT) | Accelerometer offset temperature ^0 polynomial coefficient - Y axis | 0.0 | ||
TC_A0_X0_2 (FLOAT) | Accelerometer offset temperature ^0 polynomial coefficient - Z axis | 0.0 | ||
TC_A0_X1_0 (FLOAT) | Accelerometer offset temperature ^1 polynomial coefficient - X axis | 0.0 | ||
TC_A0_X1_1 (FLOAT) | Accelerometer offset temperature ^1 polynomial coefficient - Y axis | 0.0 | ||
TC_A0_X1_2 (FLOAT) | Accelerometer offset temperature ^1 polynomial coefficient - Z axis | 0.0 | ||
TC_A0_X2_0 (FLOAT) | Accelerometer offset temperature ^2 polynomial coefficient - X axis | 0.0 | ||
TC_A0_X2_1 (FLOAT) | Accelerometer offset temperature ^2 polynomial coefficient - Y axis | 0.0 | ||
TC_A0_X2_2 (FLOAT) | Accelerometer offset temperature ^2 polynomial coefficient - Z axis | 0.0 | ||
TC_A0_X3_0 (FLOAT) | Accelerometer offset temperature ^3 polynomial coefficient - X axis | 0.0 | ||
TC_A0_X3_1 (FLOAT) | Accelerometer offset temperature ^3 polynomial coefficient - Y axis | 0.0 | ||
TC_A0_X3_2 (FLOAT) | Accelerometer offset temperature ^3 polynomial coefficient - Z axis | 0.0 | ||
TC_A1_ID (INT32) | ID of Accelerometer that the calibration is for | 0 | ||
TC_A1_SCL_0 (FLOAT) | Accelerometer scale factor - X axis | 1.0 | ||
TC_A1_SCL_1 (FLOAT) | Accelerometer scale factor - Y axis | 1.0 | ||
TC_A1_SCL_2 (FLOAT) | Accelerometer scale factor - Z axis | 1.0 | ||
TC_A1_TMAX (FLOAT) | Accelerometer calibration maximum temperature | 100.0 | ||
TC_A1_TMIN (FLOAT) | Accelerometer calibration minimum temperature | 0.0 | ||
TC_A1_TREF (FLOAT) | Accelerometer calibration reference temperature | 25.0 | ||
TC_A1_X0_0 (FLOAT) | Accelerometer offset temperature ^0 polynomial coefficient - X axis | 0.0 | ||
TC_A1_X0_1 (FLOAT) | Accelerometer offset temperature ^0 polynomial coefficient - Y axis | 0.0 | ||
TC_A1_X0_2 (FLOAT) | Accelerometer offset temperature ^0 polynomial coefficient - Z axis | 0.0 | ||
TC_A1_X1_0 (FLOAT) | Accelerometer offset temperature ^1 polynomial coefficient - X axis | 0.0 | ||
TC_A1_X1_1 (FLOAT) | Accelerometer offset temperature ^1 polynomial coefficient - Y axis | 0.0 | ||
TC_A1_X1_2 (FLOAT) | Accelerometer offset temperature ^1 polynomial coefficient - Z axis | 0.0 | ||
TC_A1_X2_0 (FLOAT) | Accelerometer offset temperature ^2 polynomial coefficient - X axis | 0.0 | ||
TC_A1_X2_1 (FLOAT) | Accelerometer offset temperature ^2 polynomial coefficient - Y axis | 0.0 | ||
TC_A1_X2_2 (FLOAT) | Accelerometer offset temperature ^2 polynomial coefficient - Z axis | 0.0 | ||
TC_A1_X3_0 (FLOAT) | Accelerometer offset temperature ^3 polynomial coefficient - X axis | 0.0 | ||
TC_A1_X3_1 (FLOAT) | Accelerometer offset temperature ^3 polynomial coefficient - Y axis | 0.0 | ||
TC_A1_X3_2 (FLOAT) | Accelerometer offset temperature ^3 polynomial coefficient - Z axis | 0.0 | ||
TC_A2_ID (INT32) | ID of Accelerometer that the calibration is for | 0 | ||
TC_A2_SCL_0 (FLOAT) | Accelerometer scale factor - X axis | 1.0 | ||
TC_A2_SCL_1 (FLOAT) | Accelerometer scale factor - Y axis | 1.0 | ||
TC_A2_SCL_2 (FLOAT) | Accelerometer scale factor - Z axis | 1.0 | ||
TC_A2_TMAX (FLOAT) | Accelerometer calibration maximum temperature | 100.0 | ||
TC_A2_TMIN (FLOAT) | Accelerometer calibration minimum temperature | 0.0 | ||
TC_A2_TREF (FLOAT) | Accelerometer calibration reference temperature | 25.0 | ||
TC_A2_X0_0 (FLOAT) | Accelerometer offset temperature ^0 polynomial coefficient - X axis | 0.0 | ||
TC_A2_X0_1 (FLOAT) | Accelerometer offset temperature ^0 polynomial coefficient - Y axis | 0.0 | ||
TC_A2_X0_2 (FLOAT) | Accelerometer offset temperature ^0 polynomial coefficient - Z axis | 0.0 | ||
TC_A2_X1_0 (FLOAT) | Accelerometer offset temperature ^1 polynomial coefficient - X axis | 0.0 | ||
TC_A2_X1_1 (FLOAT) | Accelerometer offset temperature ^1 polynomial coefficient - Y axis | 0.0 | ||
TC_A2_X1_2 (FLOAT) | Accelerometer offset temperature ^1 polynomial coefficient - Z axis | 0.0 | ||
TC_A2_X2_0 (FLOAT) | Accelerometer offset temperature ^2 polynomial coefficient - X axis | 0.0 | ||
TC_A2_X2_1 (FLOAT) | Accelerometer offset temperature ^2 polynomial coefficient - Y axis | 0.0 | ||
TC_A2_X2_2 (FLOAT) | Accelerometer offset temperature ^2 polynomial coefficient - Z axis | 0.0 | ||
TC_A2_X3_0 (FLOAT) | Accelerometer offset temperature ^3 polynomial coefficient - X axis | 0.0 | ||
TC_A2_X3_1 (FLOAT) | Accelerometer offset temperature ^3 polynomial coefficient - Y axis | 0.0 | ||
TC_A2_X3_2 (FLOAT) | Accelerometer offset temperature ^3 polynomial coefficient - Z axis | 0.0 | ||
TC_A_ENABLE (INT32) | Thermal compensation for accelerometer sensors | 0 > 1 | 0 | |
TC_B0_ID (INT32) | ID of Barometer that the calibration is for | 0 | ||
TC_B0_SCL (FLOAT) | Barometer scale factor - X axis | 1.0 | ||
TC_B0_TMAX (FLOAT) | Barometer calibration maximum temperature | 75.0 | ||
TC_B0_TMIN (FLOAT) | Barometer calibration minimum temperature | 5.0 | ||
TC_B0_TREF (FLOAT) | Barometer calibration reference temperature | 40.0 | ||
TC_B0_X0 (FLOAT) | Barometer offset temperature ^0 polynomial coefficient | 0.0 | ||
TC_B0_X1 (FLOAT) | Barometer offset temperature ^1 polynomial coefficients | 0.0 | ||
TC_B0_X2 (FLOAT) | Barometer offset temperature ^2 polynomial coefficient | 0.0 | ||
TC_B0_X3 (FLOAT) | Barometer offset temperature ^3 polynomial coefficient | 0.0 | ||
TC_B0_X4 (FLOAT) | Barometer offset temperature ^4 polynomial coefficient | 0.0 | ||
TC_B0_X5 (FLOAT) | Barometer offset temperature ^5 polynomial coefficient | 0.0 | ||
TC_B1_ID (INT32) | ID of Barometer that the calibration is for | 0 | ||
TC_B1_SCL (FLOAT) | Barometer scale factor - X axis | 1.0 | ||
TC_B1_TMAX (FLOAT) | Barometer calibration maximum temperature | 75.0 | ||
TC_B1_TMIN (FLOAT) | Barometer calibration minimum temperature | 5.0 | ||
TC_B1_TREF (FLOAT) | Barometer calibration reference temperature | 40.0 | ||
TC_B1_X0 (FLOAT) | Barometer offset temperature ^0 polynomial coefficient | 0.0 | ||
TC_B1_X1 (FLOAT) | Barometer offset temperature ^1 polynomial coefficients | 0.0 | ||
TC_B1_X2 (FLOAT) | Barometer offset temperature ^2 polynomial coefficient | 0.0 | ||
TC_B1_X3 (FLOAT) | Barometer offset temperature ^3 polynomial coefficient | 0.0 | ||
TC_B1_X4 (FLOAT) | Barometer offset temperature ^4 polynomial coefficient | 0.0 | ||
TC_B1_X5 (FLOAT) | Barometer offset temperature ^5 polynomial coefficient | 0.0 | ||
TC_B2_ID (INT32) | ID of Barometer that the calibration is for | 0 | ||
TC_B2_SCL (FLOAT) | Barometer scale factor - X axis | 1.0 | ||
TC_B2_TMAX (FLOAT) | Barometer calibration maximum temperature | 75.0 | ||
TC_B2_TMIN (FLOAT) | Barometer calibration minimum temperature | 5.0 | ||
TC_B2_TREF (FLOAT) | Barometer calibration reference temperature | 40.0 | ||
TC_B2_X0 (FLOAT) | Barometer offset temperature ^0 polynomial coefficient | 0.0 | ||
TC_B2_X1 (FLOAT) | Barometer offset temperature ^1 polynomial coefficients | 0.0 | ||
TC_B2_X2 (FLOAT) | Barometer offset temperature ^2 polynomial coefficient | 0.0 | ||
TC_B2_X3 (FLOAT) | Barometer offset temperature ^3 polynomial coefficient | 0.0 | ||
TC_B2_X4 (FLOAT) | Barometer offset temperature ^4 polynomial coefficient | 0.0 | ||
TC_B2_X5 (FLOAT) | Barometer offset temperature ^5 polynomial coefficient | 0.0 | ||
TC_B_ENABLE (INT32) | Thermal compensation for barometric pressure sensors | 0 > 1 | 0 | |
TC_G0_ID (INT32) | ID of Gyro that the calibration is for | 0 | ||
TC_G0_SCL_0 (FLOAT) | Gyro scale factor - X axis | 1.0 | ||
TC_G0_SCL_1 (FLOAT) | Gyro scale factor - Y axis | 1.0 | ||
TC_G0_SCL_2 (FLOAT) | Gyro scale factor - Z axis | 1.0 | ||
TC_G0_TMAX (FLOAT) | Gyro calibration maximum temperature | 100.0 | ||
TC_G0_TMIN (FLOAT) | Gyro calibration minimum temperature | 0.0 | ||
TC_G0_TREF (FLOAT) | Gyro calibration reference temperature | 25.0 | ||
TC_G0_X0_0 (FLOAT) | Gyro rate offset temperature ^0 polynomial coefficient - X axis | 0.0 | ||
TC_G0_X0_1 (FLOAT) | Gyro rate offset temperature ^0 polynomial coefficient - Y axis | 0.0 | ||
TC_G0_X0_2 (FLOAT) | Gyro rate offset temperature ^0 polynomial coefficient - Z axis | 0.0 | ||
TC_G0_X1_0 (FLOAT) | Gyro rate offset temperature ^1 polynomial coefficient - X axis | 0.0 | ||
TC_G0_X1_1 (FLOAT) | Gyro rate offset temperature ^1 polynomial coefficient - Y axis | 0.0 | ||
TC_G0_X1_2 (FLOAT) | Gyro rate offset temperature ^1 polynomial coefficient - Z axis | 0.0 | ||
TC_G0_X2_0 (FLOAT) | Gyro rate offset temperature ^2 polynomial coefficient - X axis | 0.0 | ||
TC_G0_X2_1 (FLOAT) | Gyro rate offset temperature ^2 polynomial coefficient - Y axis | 0.0 | ||
TC_G0_X2_2 (FLOAT) | Gyro rate offset temperature ^2 polynomial coefficient - Z axis | 0.0 | ||
TC_G0_X3_0 (FLOAT) | Gyro rate offset temperature ^3 polynomial coefficient - X axis | 0.0 | ||
TC_G0_X3_1 (FLOAT) | Gyro rate offset temperature ^3 polynomial coefficient - Y axis | 0.0 | ||
TC_G0_X3_2 (FLOAT) | Gyro rate offset temperature ^3 polynomial coefficient - Z axis | 0.0 | ||
TC_G1_ID (INT32) | ID of Gyro that the calibration is for | 0 | ||
TC_G1_SCL_0 (FLOAT) | Gyro scale factor - X axis | 1.0 | ||
TC_G1_SCL_1 (FLOAT) | Gyro scale factor - Y axis | 1.0 | ||
TC_G1_SCL_2 (FLOAT) | Gyro scale factor - Z axis | 1.0 | ||
TC_G1_TMAX (FLOAT) | Gyro calibration maximum temperature | 100.0 | ||
TC_G1_TMIN (FLOAT) | Gyro calibration minimum temperature | 0.0 | ||
TC_G1_TREF (FLOAT) | Gyro calibration reference temperature | 25.0 | ||
TC_G1_X0_0 (FLOAT) | Gyro rate offset temperature ^0 polynomial coefficient - X axis | 0.0 | ||
TC_G1_X0_1 (FLOAT) | Gyro rate offset temperature ^0 polynomial coefficient - Y axis | 0.0 | ||
TC_G1_X0_2 (FLOAT) | Gyro rate offset temperature ^0 polynomial coefficient - Z axis | 0.0 | ||
TC_G1_X1_0 (FLOAT) | Gyro rate offset temperature ^1 polynomial coefficient - X axis | 0.0 | ||
TC_G1_X1_1 (FLOAT) | Gyro rate offset temperature ^1 polynomial coefficient - Y axis | 0.0 | ||
TC_G1_X1_2 (FLOAT) | Gyro rate offset temperature ^1 polynomial coefficient - Z axis | 0.0 | ||
TC_G1_X2_0 (FLOAT) | Gyro rate offset temperature ^2 polynomial coefficient - X axis | 0.0 | ||
TC_G1_X2_1 (FLOAT) | Gyro rate offset temperature ^2 polynomial coefficient - Y axis | 0.0 | ||
TC_G1_X2_2 (FLOAT) | Gyro rate offset temperature ^2 polynomial coefficient - Z axis | 0.0 | ||
TC_G1_X3_0 (FLOAT) | Gyro rate offset temperature ^3 polynomial coefficient - X axis | 0.0 | ||
TC_G1_X3_1 (FLOAT) | Gyro rate offset temperature ^3 polynomial coefficient - Y axis | 0.0 | ||
TC_G1_X3_2 (FLOAT) | Gyro rate offset temperature ^3 polynomial coefficient - Z axis | 0.0 | ||
TC_G2_ID (INT32) | ID of Gyro that the calibration is for | 0 | ||
TC_G2_SCL_0 (FLOAT) | Gyro scale factor - X axis | 1.0 | ||
TC_G2_SCL_1 (FLOAT) | Gyro scale factor - Y axis | 1.0 | ||
TC_G2_SCL_2 (FLOAT) | Gyro scale factor - Z axis | 1.0 | ||
TC_G2_TMAX (FLOAT) | Gyro calibration maximum temperature | 100.0 | ||
TC_G2_TMIN (FLOAT) | Gyro calibration minimum temperature | 0.0 | ||
TC_G2_TREF (FLOAT) | Gyro calibration reference temperature | 25.0 | ||
TC_G2_X0_0 (FLOAT) | Gyro rate offset temperature ^0 polynomial coefficient - X axis | 0.0 | ||
TC_G2_X0_1 (FLOAT) | Gyro rate offset temperature ^0 polynomial coefficient - Y axis | 0.0 | ||
TC_G2_X0_2 (FLOAT) | Gyro rate offset temperature ^0 polynomial coefficient - Z axis | 0.0 | ||
TC_G2_X1_0 (FLOAT) | Gyro rate offset temperature ^1 polynomial coefficient - X axis | 0.0 | ||
TC_G2_X1_1 (FLOAT) | Gyro rate offset temperature ^1 polynomial coefficient - Y axis | 0.0 | ||
TC_G2_X1_2 (FLOAT) | Gyro rate offset temperature ^1 polynomial coefficient - Z axis | 0.0 | ||
TC_G2_X2_0 (FLOAT) | Gyro rate offset temperature ^2 polynomial coefficient - X axis | 0.0 | ||
TC_G2_X2_1 (FLOAT) | Gyro rate offset temperature ^2 polynomial coefficient - Y axis | 0.0 | ||
TC_G2_X2_2 (FLOAT) | Gyro rate offset temperature ^2 polynomial coefficient - Z axis | 0.0 | ||
TC_G2_X3_0 (FLOAT) | Gyro rate offset temperature ^3 polynomial coefficient - X axis | 0.0 | ||
TC_G2_X3_1 (FLOAT) | Gyro rate offset temperature ^3 polynomial coefficient - Y axis | 0.0 | ||
TC_G2_X3_2 (FLOAT) | Gyro rate offset temperature ^3 polynomial coefficient - Z axis | 0.0 | ||
TC_G_ENABLE (INT32) | Thermal compensation for rate gyro sensors | 0 > 1 | 0 |
UAVCAN
参数名 | 参数描述 | 最小最大值 (增量) | 默认值 | 单位 |
---|---|---|---|---|
CANNODE_BITRATE (INT32) | UAVCAN CAN bus bitrate | 20000 > 1000000 | 1000000 | |
CANNODE_NODE_ID (INT32) | UAVCAN Node ID Comment: Read the specs at http://uavcan.org to learn more about Node ID. | 1 > 125 | 120 | |
ESC_BITRATE (INT32) | UAVCAN CAN bus bitrate | 20000 > 1000000 | 1000000 | |
ESC_NODE_ID (INT32) | UAVCAN Node ID Comment: Read the specs at http://uavcan.org to learn more about Node ID. | 1 > 125 | 120 | |
UAVCAN_BITRATE (INT32) | UAVCAN CAN bus bitrate Reboot required: true | 20000 > 1000000 | 1000000 | bit/s |
UAVCAN_ENABLE (INT32) | UAVCAN mode Comment: 0 - UAVCAN disabled. 1 - Enables support for UAVCAN sensors without dynamic node ID allocation and firmware update. 2 - Enables support for UAVCAN sensors with dynamic node ID allocation and firmware update. 3 - Enables support for UAVCAN sensors and actuators with dynamic node ID allocation and firmware update. Also sets the motor control outputs to UAVCAN. Values:
Reboot required: true | 0 > 3 | 0 | |
UAVCAN_ESC_IDLT (INT32) | UAVCAN ESC will spin at idle throttle when armed, even if the mixer outputs zero setpoints Reboot required: true | 1 | ||
UAVCAN_NODE_ID (INT32) | UAVCAN Node ID Comment: Read the specs at http://uavcan.org to learn more about Node ID. Reboot required: true | 1 > 125 | 1 |
VTOL Attitude Control
Name | Description | Min > Max (Incr.) | Default | Units |
---|---|---|---|---|
VT_ARSP_BLEND (FLOAT) | Transition blending airspeed Comment: Airspeed at which we can start blending both fw and mc controls. Set to 0 to disable. | 0.00 > 30.00 (1) | 8.0 | m/s |
VT_ARSP_TRANS (FLOAT) | Transition airspeed Comment: Airspeed at which we can switch to fw mode | 0.00 > 30.00 (1) | 10.0 | m/s |
VT_B_DEC_MSS (FLOAT) | Approximate deceleration during back transition Comment: The approximate deceleration during a back transition in m/s/s Used to calculate back transition distance in mission mode. A lower value will make the VTOL transition further from the destination waypoint. | 0.00 > 20.00 (1) | 2.0 | m/s/s |
VT_B_REV_DEL (FLOAT) | Delay in seconds before applying back transition throttle Set this to a value greater than 0 to give the motor time to spin down Comment: unit s | 0 > 10 (1) | 0.0 | |
VT_B_REV_OUT (FLOAT) | 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 | 0 > 1 (0.01) | 0.0 | |
VT_B_TRANS_DUR (FLOAT) | Duration of a back transition Comment: Time in seconds used for a back transition | 0.00 > 20.00 (1) | 4.0 | s |
VT_B_TRANS_RAMP (FLOAT) | Back transition MC motor ramp up time Comment: This sets the duration during which the MC motors ramp up to the commanded thrust during the back transition stage. | 0.0 > 20.0 | 3.0 | s |
VT_B_TRANS_THR (FLOAT) | Target throttle value for the transition to hover flight. standard vtol: pusher tailsitter, tiltrotor: main throttle Comment: Note for standard vtol: For ESCs and mixers that support reverse thrust on low PWM values set this to a negative value to apply active breaking For ESCs that support thrust reversal with a control channel please set VT_B_REV_OUT and set this to a positive value to apply active breaking | -1 > 1 (0.01) | 0.0 | |
VT_DWN_PITCH_MAX (FLOAT) | Maximum allowed down-pitch the controller is able to demand. This prevents large, negative lift values being created when facing strong winds. The vehicle will use the pusher motor to accelerate forward if necessary | 0.0 > 45.0 | 5.0 | |
VT_ELEV_MC_LOCK (INT32) | Lock elevons in multicopter mode Comment: If set to 1 the elevons are locked in multicopter mode | 1 | ||
VT_FWD_THRUST_SC (FLOAT) | Fixed wing thrust scale for hover forward flight Comment: Scale applied to fixed wing thrust being used as source for forward acceleration in multirotor mode. This technique can be used to avoid the plane having to pitch down a lot in order to move forward. Setting this value to 0 (default) will disable this strategy. | 0.0 > 2.0 | 0.0 | |
VT_FW_ALT_ERR (FLOAT) | Adaptive QuadChute Comment: Maximum negative altitude error for fixed wing flight. If the altitude drops below this value below the altitude setpoint the vehicle will transition back to MC mode and enter failsafe RTL. | 0.0 > 200.0 | 0.0 | |
VT_FW_DIFTHR_EN (INT32) | Differential thrust in forwards flight Comment: Set to 1 to enable differential thrust in fixed-wing flight. | 0 > 1 | 0 | |
VT_FW_DIFTHR_SC (FLOAT) | Differential thrust scaling factor Comment: This factor specifies how the yaw input gets mapped to differential thrust in forwards flight. | 0.0 > 1.0 (0.1) | 0.1 | |
VT_FW_MIN_ALT (FLOAT) | QuadChute Altitude Comment: Minimum altitude for fixed wing flight, when in fixed wing the altitude drops below this altitude the vehicle will transition back to MC mode and enter failsafe RTL | 0.0 > 200.0 | 0.0 | |
VT_FW_MOT_OFFID (INT32) | The channel number of motors that must be turned off in fixed wing mode | 0 > 12345678 (1) | 0 | |
VT_FW_PERM_STAB (INT32) | Permanent stabilization in fw mode Comment: If set to one this parameter will cause permanent attitude stabilization in fw mode. This parameter has been introduced for pure convenience sake. | 0 | ||
VT_FW_QC_P (INT32) | QuadChute Max Pitch Comment: Maximum pitch angle before QuadChute engages Above this the vehicle will transition back to MC mode and enter failsafe RTL | 0 > 180 | 0 | |
VT_FW_QC_R (INT32) | QuadChute Max Roll Comment: Maximum roll angle before QuadChute engages Above this the vehicle will transition back to MC mode and enter failsafe RTL | 0 > 180 | 0 | |
VT_F_TRANS_DUR (FLOAT) | Duration of a front transition Comment: Time in seconds used for a transition | 0.00 > 20.00 (1) | 5.0 | s |
VT_F_TRANS_THR (FLOAT) | Target throttle value for the transition to fixed wing flight. standard vtol: pusher tailsitter, tiltrotor: main throttle | 0.0 > 1.0 (0.01) | 1.0 | |
VT_F_TR_OL_TM (FLOAT) | Airspeed less front transition time (open loop) Comment: The duration of the front transition when there is no airspeed feedback available. | 1.0 > 30.0 | 6.0 | seconds |
VT_IDLE_PWM_MC (INT32) | Idle speed of VTOL when in multicopter mode | 900 > 2000 (1) | 900 | us |
VT_MOT_ID (INT32) | The channel number of motors which provide lift during hover | 0 > 12345678 (1) | 0 | |
VT_PSHER_RMP_DT (FLOAT) | 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 | ? > 20 (0.01) | 3.0 | |
VT_TILT_FW (FLOAT) | Position of tilt servo in fw mode | 0.0 > 1.0 (0.01) | 1.0 | |
VT_TILT_MC (FLOAT) | Position of tilt servo in mc mode | 0.0 > 1.0 (0.01) | 0.0 | |
VT_TILT_TRANS (FLOAT) | Position of tilt servo in transition mode | 0.0 > 1.0 (0.01) | 0.3 | |
VT_TRANS_MIN_TM (FLOAT) | Front transition minimum time Comment: Minimum time in seconds for front transition. | 0.0 > 20.0 | 2.0 | s |
VT_TRANS_P2_DUR (FLOAT) | Duration of front transition phase 2 Comment: Time in seconds it should take for the rotors to rotate forward completely from the point when the plane has picked up enough airspeed and is ready to go into fixed wind mode. | 0.1 > 5.0 (0.01) | 0.5 | s |
VT_TRANS_TIMEOUT (FLOAT) | Front transition timeout Comment: Time in seconds after which transition will be cancelled. Disabled if set to 0. | 0.00 > 30.00 (1) | 15.0 | s |
VT_TYPE (INT32) | VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2) Values:
Reboot required: true | 0 > 2 | 0 | |
WV_GAIN (FLOAT) | Weather-vane roll angle to yawrate Comment: The desired gain to convert roll sp into yaw rate sp. | 0.0 > 3.0 (0.01) | 1.0 | 1/s |
Miscellaneous
Name | Description | Min > Max (Incr.) | Default | Units |
---|---|---|---|---|
EXFW_HDNG_P (FLOAT) |
| 0.1 | ||
EXFW_PITCH_P (FLOAT) |
| 0.2 | ||
EXFW_ROLL_P (FLOAT) |
| 0.2 | ||
MPC_LAND_RC_HELP (INT32) | Enable user assisted descent speed for autonomous land routine. When enabled, descent speed will be equal to MPC_LAND_SPEED at half throttle, MPC_Z_VEL_MAX_DN at zero throttle, and 0.5 * MPC_LAND_SPEED at full throttle Values:
| 0 > 1 | 0 | |
RV_YAW_P (FLOAT) |
| 0.1 | ||
SEG_Q2V (FLOAT) |
| 1.0 | ||
SEG_TH2V_I (FLOAT) |
| 0.0 | ||
SEG_TH2V_I_MAX (FLOAT) |
| 0.0 | ||
SEG_TH2V_P (FLOAT) |
| 10.0 |