BAT_CAPACITY FLOAT Battery capacity Defines the capacity of the attached battery. -1.0 mA BAT_C_SCALING FLOAT Scaling factor for battery current sensor 0.0124 BAT_N_CELLS INT32 Number of cells Defines the number of cells the attached battery consists of. 3 S BAT_V_CHARGED FLOAT Full cell voltage Defines the voltage where a single cell of the battery is considered full. 4.2 V BAT_V_EMPTY FLOAT Empty cell voltage Defines the voltage where a single cell of the battery is considered empty. 3.4 V BAT_V_LOAD_DROP FLOAT Voltage drop per cell on 100% load This implicitely defines the internal resistance to maximum current ratio and assumes linearity. 0.07 V BAT_V_SCALE_IO INT32 Scaling factor for battery voltage sensor on PX4IO 10000 BAT_V_SCALING FLOAT Scaling factor for battery voltage sensor on FMU v2 0.0082 BAT_V_SCALING FLOAT Scaling factor for battery voltage sensor on AeroCore For R70 = 133K, R71 = 10K --> scale = 1.8 * 143 / (4096*10) = 0.0063 0.0063 BAT_V_SCALING FLOAT Scaling factor for battery voltage sensor on FMU v1 FMUv1 standalone: 1/(10 / (47+10)) * (3.3 / 4095) = 0.00459340659 FMUv1 with PX4IO: 0.00459340659 FMUv1 with PX4IOAR: (3.3f * 52.0f / 5.0f / 4095.0f) = 0.00838095238 0.00459340659 NAV_AH_ALT FLOAT Airfield home alt Altitude of airfield home waypoint 600.0 0.0 m NAV_AH_LAT INT32 Airfield home Lat Latitude of airfield home waypoint -265847810 0 degrees * 1e7 NAV_AH_LON INT32 Airfield home Lon Longitude of airfield home waypoint 1518423250 0 degrees * 1e7 NAV_DLL_AH_T FLOAT Aifield hole wait time The amount of time in seconds the system should wait at the airfield home waypoint 120.0 0.0 seconds NAV_DLL_CHSK INT32 Skip comms hold wp If set to 1 the system will skip the comms hold wp on data link loss and will directly fly to airfield home 0 0 1 NAV_DLL_CH_ALT FLOAT Comms hold alt Altitude of comms hold waypoint 600.0 0.0 m NAV_DLL_CH_LAT INT32 Comms hold Lat Latitude of comms hold waypoint -266072120 0 degrees * 1e7 NAV_DLL_CH_LON INT32 Comms hold Lon Longitude of comms hold waypoint 1518453890 0 degrees * 1e7 NAV_DLL_CH_T FLOAT Comms hold wait time The amount of time in seconds the system should wait at the comms hold waypoint 120.0 0.0 seconds NAV_DLL_N INT32 Number of allowed Datalink timeouts After more than this number of data link timeouts the aircraft returns home directly 2 0 1000 FW_AIRSPD_MAX FLOAT Maximum Airspeed If the airspeed is above this value, the TECS controller will try to decrease airspeed more aggressively. 20.0 0.0 40 m/s FW_AIRSPD_MIN FLOAT Minimum Airspeed If the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. 10.0 0.0 40 m/s FW_AIRSPD_TRIM FLOAT Trim Airspeed The TECS controller tries to fly at this airspeed. 15.0 0.0 40 m/s FW_ATT_TC FLOAT Attitude Time Constant This defines the latency between a 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.5 0.4 1.0 seconds FW_MAN_P_MAX FLOAT Max Manual Pitch Max pitch for manual control in attitude stabilized mode 45.0 0.0 90.0 deg FW_MAN_R_MAX FLOAT Max Manual Roll Max roll for manual control in attitude stabilized mode 45.0 0.0 90.0 deg FW_PR_FF FLOAT Pitch rate feed forward Direct feed forward from rate setpoint to control surface output 0.4 0.0 10.0 FW_PR_I FLOAT Pitch rate integrator gain This gain defines how much control response will result out of a steady state error. It trims any constant error. 0.0 0.0 50.0 FW_PR_IMAX FLOAT Pitch rate integrator limit The portion of the integrator part in the control surface deflection is limited to this value 0.2 0.0 1.0 FW_PR_P FLOAT Pitch rate proportional gain This defines how much the elevator input will be commanded depending on the current body angular rate error. 0.05 FW_PSP_OFF FLOAT Pitch Setpoint Offset 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. 0.0 -90.0 90.0 deg FW_P_RMAX_NEG FLOAT Maximum negative / down pitch rate This limits the maximum pitch down up angular rate the controller will output (in degrees per second). Setting a value of zero disables the limit. 0.0 0.0 90.0 deg/s FW_P_RMAX_POS FLOAT Maximum positive / up pitch rate This limits the maximum pitch up angular rate the controller will output (in degrees per second). Setting a value of zero disables the limit. 0.0 0.0 90.0 deg/s FW_RR_FF FLOAT Roll rate feed forward Direct feed forward from rate setpoint to control surface output 0.3 0.0 10.0 FW_RR_I FLOAT Roll rate integrator Gain This gain defines how much control response will result out of a steady state error. It trims any constant error. 0.0 0.0 100.0 FW_RR_IMAX FLOAT Roll Integrator Anti-Windup The portion of the integrator part in the control surface deflection is limited to this value. 0.2 0.0 1.0 FW_RR_P FLOAT Roll rate proportional Gain This defines how much the aileron input will be commanded depending on the current body angular rate error. 0.05 FW_RSP_OFF FLOAT Roll Setpoint Offset 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. 0.0 -90.0 90.0 deg FW_R_RMAX FLOAT Maximum Roll Rate This limits the maximum roll rate the controller will output (in degrees per second). Setting a value of zero disables the limit. 0.0 0.0 90.0 deg/s FW_YCO_METHOD INT32 Method used for yaw coordination The param value sets the method used to calculate the yaw rate 0: open-loop zero lateral acceleration based on kinematic constraints 1: closed-loop: try to reduce lateral acceleration to 0 by measuring the acceleration 0 0 1 m/s FW_YCO_VMIN FLOAT Minimal speed for yaw coordination For airspeeds above this value, the yaw rate is calculated for a coordinated turn. Set to a very high value to disable. 1000.0 m/s FW_YR_FF FLOAT Yaw rate feed forward Direct feed forward from rate setpoint to control surface output 0.3 0.0 10.0 FW_YR_I FLOAT Yaw rate integrator gain This gain defines how much control response will result out of a steady state error. It trims any constant error. 0.0 0.0 50.0 FW_YR_IMAX FLOAT Yaw rate integrator limit The portion of the integrator part in the control surface deflection is limited to this value 0.2 0.0 1.0 FW_YR_P FLOAT Yaw rate proportional gain This defines how much the rudder input will be commanded depending on the current body angular rate error. 0.05 FW_Y_RMAX FLOAT Maximum Yaw Rate This limits the maximum yaw rate the controller will output (in degrees per second). Setting a value of zero disables the limit. 0.0 0.0 90.0 deg/s FW_T_HGT_OMEGA FLOAT Complementary filter "omega" parameter for height 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. 3.0 FW_T_HRATE_FF FLOAT Height rate FF factor 0.0 FW_T_HRATE_P FLOAT Height rate P factor 0.05 FW_T_INTEG_GAIN FLOAT Integrator gain 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. 0.1 FW_T_PTCH_DAMP FLOAT Pitch damping factor 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 FW_T_RLL2THR FLOAT Roll -> Throttle feedforward 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. 10.0 FW_T_SINK_MAX FLOAT Maximum descent rate 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. 5.0 FW_T_SINK_MIN FLOAT Minimum descent rate 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. 2.0 FW_T_SPDWEIGHT FLOAT Speed <--> Altitude priority 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). 1.0 FW_T_SPD_OMEGA FLOAT Complementary filter "omega" parameter for speed 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 arispeed sensor, whilst reducing it weights the solution more towards use of the accelerometer data. 2.0 FW_T_SRATE_P FLOAT Speed rate P factor 0.05 FW_T_THRO_CONST FLOAT TECS Throttle time constant 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. 8.0 FW_T_THR_DAMP FLOAT Throttle damping factor This is the damping gain for the throttle demand loop. Increase to add damping to correct for oscillations in speed and height. 0.5 FW_T_TIME_CONST FLOAT TECS time constant 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. 5.0 FW_T_VERT_ACC FLOAT Maximum vertical acceleration This is the maximum vertical acceleration (in metres/second square) 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. 7.0 NAV_GPSF_LT FLOAT Loiter time The amount of time in seconds the system should do open loop loiter and wait for gps recovery before it goes into flight termination. 30.0 0.0 seconds NAV_GPSF_P FLOAT Open loop loiter pitch Pitch in degrees during the open loop loiter 0.0 -30.0 30.0 deg NAV_GPSF_R FLOAT Open loop loiter roll Roll in degrees during the open loop loiter 15.0 0.0 30.0 deg NAV_GPSF_TR FLOAT Open loop loiter thrust Thrust value which is set during the open loop loiter 0.7 0.0 1.0 GF_ALTMODE INT32 Geofence altitude mode Select which altitude reference should be used 0 = WGS84, 1 = AMSL 0 0 1 GF_COUNT INT32 Geofence counter limit Set how many subsequent position measurements outside of the fence are needed before geofence violation is triggered -1 -1 10 GF_ON INT32 Enable geofence Set to 1 to enable geofence. Defaults to 1 because geofence is only enabled when the geofence.txt file is present. 1 0 1 GF_SOURCE INT32 Geofence source 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 0 0 1 FW_CLMBOUT_DIFF FLOAT Climbout Altitude difference 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 zero to disable climbout mode (not recommended). 25.0 FW_L1_DAMPING FLOAT L1 damping Damping factor for L1 control. 0.75 0.6 0.9 FW_L1_PERIOD FLOAT L1 period This is the L1 distance and defines the tracking point ahead of the aircraft its following. A value of 25 meters works for most aircraft. Shorten slowly during tuning until response is sharp without oscillation. 25.0 1.0 100.0 FW_LND_ANG FLOAT Landing slope angle 5.0 FW_LND_FLALT FLOAT Landing flare altitude (relative to landing altitude) 8.0 meter FW_LND_HHDIST FLOAT Landing heading hold horizontal distance 15.0 FW_LND_HVIRT FLOAT FW_LND_HVIRT 10.0 FW_LND_TLALT FLOAT Landing throttle limit altitude (relative landing altitude) Default of -1.0f lets the system default to applying throttle limiting at 2/3 of the flare altitude. -1.0 meter FW_LND_USETER INT32 Enable or disable usage of terrain estimate during landing 0: disabled, 1: enabled 0 FW_P_LIM_MAX FLOAT Positive pitch limit The maximum positive pitch the controller will output. 45.0 0.0 60.0 degrees FW_P_LIM_MIN FLOAT Negative pitch limit The minimum negative pitch the controller will output. -45.0 -60.0 0.0 degrees FW_R_LIM FLOAT Controller roll limit The maximum roll the controller will output. 45.0 0.0 degrees FW_THR_CRUISE FLOAT Cruise throttle This is the throttle setting required to achieve the desired cruise speed. Most airframes have a value of 0.5-0.7. 0.7 0.0 1.0 FW_THR_LND_MAX FLOAT Throttle limit value before flare This throttle value will be set as throttle limit at FW_LND_TLALT, before arcraft will flare. 1.0 FW_THR_MAX FLOAT Throttle limit max 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. 1.0 FW_THR_MIN FLOAT Throttle limit min 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 FW_THR_SLEW_MAX FLOAT Throttle max slew rate Maximum slew rate for the commanded throttle 0.0 0.0 1.0 FW_T_CLMB_MAX FLOAT Maximum climb rate 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. 5.0 LNDFW_AIRSPD_MAX FLOAT Airspeed max Maximum airspeed allowed to trigger a land (m/s) 10.00 LNDFW_VEL_XY_MAX FLOAT Fixedwing max horizontal velocity Maximum horizontal velocity allowed to trigger a land (m/s) 0.20 LNDFW_VEL_Z_MAX FLOAT Fixedwing max climb rate Maximum vertical velocity allowed to trigger a land (m/s up and down) 10.00 LNDMC_ROT_MAX FLOAT Multicopter max rotation Maximum allowed around each axis to trigger a land (degrees per second) 20.0 LNDMC_THR_MAX FLOAT Multicopter max throttle Maximum actuator output on throttle before triggering a land 0.20 LNDMC_XY_VEL_MAX FLOAT Multicopter max horizontal velocity Maximum horizontal velocity allowed to trigger a land (m/s) 1.00 LNDMC_Z_VEL_MAX FLOAT Multicopter max climb rate Maximum vertical velocity allowed to trigger a land (m/s up and down) 0.30 LAUN_ALL_ON INT32 Enable launch detection 0 0 1 LAUN_CAT_A FLOAT Catapult accelerometer theshold LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection. 30.0 0 LAUN_CAT_MDEL FLOAT Motor delay 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 LAUN_THR_PRE, set to 0 to deactivate 0.0 0 seconds LAUN_CAT_PMAX FLOAT Maximum pitch before the throttle is powered up (during motor delay phase) 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). 30.0 0 45 deg LAUN_CAT_T FLOAT Catapult time theshold LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection. 0.05 0 LAUN_THR_PRE FLOAT Throttle setting while detecting launch The throttle is set to this value while the system is waiting for the take-off. 0.0 0 1 MAV_COMP_ID INT32 MAVLink component ID 50 MAV_FWDEXTSP INT32 Forward external setpoint messages If set to 1 incomming external setpoint messages will be directly forwarded to the controllers if in offboard control mode 1 MAV_SYS_ID INT32 MAVLink system ID 1 MAV_TYPE INT32 MAVLink type MAV_TYPE_FIXED_WING MAV_USEHILGPS INT32 Use/Accept HIL GPS message (even if not in HIL mode) If set to 1 incomming HIL GPS messages are parsed 0 MKBLCTRL_TEST INT32 Enables testmode (Identify) of MKBLCTRL Driver 0 MIS_ALTMODE INT32 Altitude setpoint mode 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 0 0 1 MIS_DIST_1WP FLOAT Maximal horizontal distance from home to first waypoint 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 current position. 500 0 1000 MIS_ONBOARD_EN INT32 Enable persistent onboard mission storage When enabled, missions that have been uploaded by the GCS are stored and reloaded after reboot persistently. 1 0 1 MIS_TAKEOFF_ALT FLOAT Take-off altitude Even if first waypoint has altitude less then MIS_TAKEOFF_ALT above home position, system will climb to MIS_TAKEOFF_ALT on takeoff, then go to waypoint. 10.0 meters MIS_YAWMODE INT32 Multirotor only. Yaw setpoint mode 0: Set the yaw heading to the yaw value specified for the destination waypoint. 1: Maintain a yaw heading pointing towards the next waypoint. 2: Maintain a yaw heading that always points to the home location. 3: Maintain a yaw heading that always points away from the home location (ie: back always faces home). The values are defined in the enum mission_altitude_mode 0 0 3 NAV_ACC_RAD FLOAT Acceptance Radius Default acceptance radius, overridden by acceptance radius of waypoint if set. 10.0 0.05 200 meters NAV_DLL_OBC INT32 Set OBC mode for data link loss If set to 1 the behaviour on data link loss is set to a mode according to the OBC rules 0 0 NAV_LOITER_RAD FLOAT Loiter radius (FW only) Default value of loiter radius for missions, loiter, RTL, etc. (fixedwing only). 50.0 20 200 meters NAV_RCL_OBC INT32 Set OBC mode for rc loss If set to 1 the behaviour on data link loss is set to a mode according to the OBC rules 0 0 MC_ACRO_P_MAX FLOAT Max acro pitch rate 90.0 0.0 360.0 deg/s MC_ACRO_R_MAX FLOAT Max acro roll rate 90.0 0.0 360.0 deg/s MC_ACRO_Y_MAX FLOAT Max acro yaw rate 120.0 0.0 deg/s MC_PITCHRATE_D FLOAT Pitch rate D gain Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. 0.002 0.0 MC_PITCHRATE_FF FLOAT Pitch rate feedforward Improves tracking performance. 0.0 0.0 MC_PITCHRATE_I FLOAT Pitch rate I gain Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset. 0.0 0.0 MC_PITCHRATE_MAX FLOAT Max pitch rate Limit for pitch rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. 360.0 0.0 360.0 deg/s MC_PITCHRATE_P FLOAT Pitch rate P gain Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s. 0.1 0.0 MC_PITCH_P FLOAT Pitch P gain Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad. 6.0 0.0 1/s MC_ROLLRATE_D FLOAT Roll rate D gain Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. 0.002 0.0 MC_ROLLRATE_FF FLOAT Roll rate feedforward Improves tracking performance. 0.0 0.0 MC_ROLLRATE_I FLOAT Roll rate I gain Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset. 0.0 0.0 MC_ROLLRATE_MAX FLOAT Max roll rate Limit for roll rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. 360.0 0.0 360.0 deg/s MC_ROLLRATE_P FLOAT Roll rate P gain Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s. 0.1 0.0 MC_ROLL_P FLOAT Roll P gain Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad. 6.0 0.0 MC_YAWRATE_D FLOAT Yaw rate D gain Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. 0.0 0.0 MC_YAWRATE_FF FLOAT Yaw rate feedforward Improves tracking performance. 0.0 0.0 MC_YAWRATE_I FLOAT Yaw rate I gain Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset. 0.0 0.0 MC_YAWRATE_MAX FLOAT Max yaw rate Limit for yaw rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. 120.0 0.0 360.0 deg/s MC_YAWRATE_P FLOAT Yaw rate P gain Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s. 0.3 0.0 MC_YAW_FF FLOAT Yaw feed forward Feed forward weight for manual yaw control. 0 will give slow responce and no overshot, 1 - fast responce and big overshot. 0.5 0.0 1.0 MC_YAW_P FLOAT Yaw P gain Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad. 2.0 0.0 1/s MPC_LAND_SPEED FLOAT Landing descend rate 1.0 0.0 m/s MPC_MAN_P_MAX FLOAT Max manual pitch 35.0 0.0 90.0 deg MPC_MAN_R_MAX FLOAT Max manual roll 35.0 0.0 90.0 deg MPC_MAN_Y_MAX FLOAT Max manual yaw rate 120.0 0.0 deg/s MPC_THR_MAX FLOAT Maximum thrust Limit max allowed thrust. 1.0 0.0 1.0 MPC_THR_MIN FLOAT Minimum thrust Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust. 0.1 0.0 1.0 MPC_TILTMAX_AIR FLOAT Maximum tilt angle in air Limits maximum tilt in AUTO and POSCTRL modes during flight. 45.0 0.0 90.0 deg MPC_TILTMAX_LND FLOAT Maximum tilt during landing Limits maximum tilt angle on landing. 15.0 0.0 90.0 deg MPC_XY_FF FLOAT Horizontal velocity feed forward Feed forward weight for position control in position control mode (POSCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot. 0.5 0.0 1.0 MPC_XY_P FLOAT Proportional gain for horizontal position error 1.0 0.0 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.01 0.0 MPC_XY_VEL_I FLOAT Integral gain for horizontal velocity error Non-zero value allows to resist wind. 0.02 0.0 MPC_XY_VEL_MAX FLOAT Maximum horizontal velocity Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (POSCTRL). 5.0 0.0 m/s MPC_XY_VEL_P FLOAT Proportional gain for horizontal velocity error 0.1 0.0 MPC_Z_FF FLOAT Vertical velocity feed forward Feed forward weight for altitude control in stabilized modes (ALTCTRL, POSCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot. 0.5 0.0 1.0 MPC_Z_P FLOAT Proportional gain for vertical position error 1.0 0.0 MPC_Z_VEL_D FLOAT Differential gain for vertical velocity error 0.0 0.0 MPC_Z_VEL_I FLOAT Integral gain for vertical velocity error Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff. 0.02 0.0 MPC_Z_VEL_MAX FLOAT Maximum vertical velocity Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL). 5.0 0.0 m/s MPC_Z_VEL_P FLOAT Proportional gain for vertical velocity error 0.1 0.0 BD_GPROPERTIES FLOAT Ground drag property This parameter encodes the ground drag coefficient and the corresponding decrease in wind speed from the plane altitude to ground altitude. 0.03 0.001 0.1 unknown BD_OBJ_CD FLOAT Payload drag coefficient of the dropped object 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.1 0.08 1.5 meter BD_OBJ_MASS FLOAT Payload mass A typical small toy ball: 0.025 kg OBC water bottle: 0.6 kg 0.6 0.001 5.0 kilogram BD_OBJ_SURFACE FLOAT Payload front surface area 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.00311724531 0.001 0.5 m^2 BD_PRECISION FLOAT Drop precision 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. 30.0 1.0 80.0 meter BD_TURNRADIUS FLOAT Plane turn radius 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. 120.0 30.0 500.0 meter PE_ABIAS_PNOISE FLOAT Accelerometer bias estimate process noise Generic defaults: 0.0001f, multicopters: 0.0001f, ground vehicles: 0.0001f. Increasing this value makes the bias estimation faster and noisier. 0.0002 0.00001 0.001 PE_ACC_PNOISE FLOAT Accelerometer process noise Generic defaults: 0.25, multicopters: 0.25, ground vehicles: 0.25. Increasing this value makes the filter trust the accelerometer less and other sensors more. 0.25 0.05 1.0 PE_EAS_NOISE FLOAT Airspeed measurement noise Increasing this value will make the filter trust this sensor less and trust other sensors more. 1.4 0.5 5.0 PE_GBIAS_PNOISE FLOAT Gyro bias estimate process noise Generic defaults: 1e-07f, multicopters: 1e-07f, ground vehicles: 1e-07f. Increasing this value will make the gyro bias converge faster but noisier. 1e-06 0.0000001 0.00001 PE_GPS_ALT_WGT FLOAT GPS vs. barometric altitude update weight RE-CHECK this. 0.9 0.0 1.0 PE_GYRO_PNOISE FLOAT Gyro process noise Generic defaults: 0.015, multicopters: 0.015, ground vehicles: 0.015. This noise controls how much the filter trusts the gyro measurements. Increasing it makes the filter trust the gyro less and other sensors more. 0.015 0.001 0.05 PE_HGT_DELAY_MS INT32 Height estimate delay The delay in milliseconds of the height estimate from the barometer. 350 0 1000 PE_MAGB_PNOISE FLOAT Magnetometer body frame offsets process noise Generic defaults: 0.0003, multicopters: 0.0003, ground vehicles: 0.0003. Increasing this value makes the magnetometer body bias estimate converge faster but also noisier. 0.0003 0.0001 0.01 PE_MAGE_PNOISE FLOAT Magnetometer earth frame offsets process noise Generic defaults: 0.0001, multicopters: 0.0001, ground vehicles: 0.0001. Increasing this value makes the magnetometer earth bias estimate converge faster but also noisier. 0.0003 0.0001 0.01 PE_MAG_DELAY_MS INT32 Mag estimate delay The delay in milliseconds of the magnetic field estimate from the magnetometer. 30 0 1000 PE_MAG_NOISE FLOAT Magnetometer measurement noise Generic defaults: 0.05, multicopters: 0.05, ground vehicles: 0.05 0.05 0.1 10.0 PE_POSDEV_INIT FLOAT Threshold for filter initialization If the standard deviation of the GPS position estimate is below this threshold in meters, the filter will initialize. 5.0 0.3 10.0 PE_POSD_NOISE FLOAT Position noise in down (vertical) direction Generic defaults: 0.5, multicopters: 1.0, ground vehicles: 1.0 0.5 0.1 10.0 PE_POSNE_NOISE FLOAT Position noise in north-east (horizontal) direction Generic defaults: 0.5, multicopters: 0.5, ground vehicles: 0.5 0.5 0.1 10.0 PE_POS_DELAY_MS INT32 Position estimate delay The delay in milliseconds of the position estimate from GPS. 210 0 1000 PE_TAS_DELAY_MS INT32 True airspeeed estimate delay The delay in milliseconds of the airspeed estimate. 210 0 1000 PE_VELD_NOISE FLOAT Velocity noise in down (vertical) direction Generic default: 0.5, multicopters: 0.7, ground vehicles: 0.7 0.5 0.05 5.0 PE_VELNE_NOISE FLOAT Velocity measurement noise in north-east (horizontal) direction Generic default: 0.3, multicopters: 0.5, ground vehicles: 0.5 0.3 0.05 5.0 PE_VEL_DELAY_MS INT32 Velocity estimate delay The delay in milliseconds of the velocity estimate from GPS. 230 0 1000 CBRK_NO_VISION INT32 Disable vision input Set to the appropriate key (328754) to disable vision input. 0 0 1 INAV_DELAY_GPS FLOAT GPS delay GPS delay compensation 0.2 0.0 1.0 s INAV_ENABLED INT32 INAV enabled If set to 1, use INAV for position estimation the system uses the combined attitude / position filter framework. 1 0 1 INAV_FLOW_K FLOAT Optical flow scale factor Factor to convert raw optical flow (in pixels) to radians [rad/px]. 0.15 0.0 1.0 rad/px INAV_FLOW_Q_MIN FLOAT Minimal acceptable optical flow quality 0 - lowest quality, 1 - best quality. 0.5 0.0 1.0 INAV_LAND_DISP FLOAT Land detector altitude dispersion threshold Dispersion threshold for triggering land detector. 0.7 0.0 10.0 m INAV_LAND_T FLOAT Land detector time Vehicle assumed landed if no altitude changes happened during this time on low throttle. 3.0 0.0 10.0 s INAV_LAND_THR FLOAT Land detector throttle threshold Value should be lower than minimal hovering thrust. Half of it is good choice. 0.2 0.0 1.0 INAV_SONAR_ERR FLOAT Sonar maximal error for new surface If sonar measurement error is larger than this value it skiped (spike) or accepted as new surface level (if offset is stable). 0.5 0.0 1.0 m INAV_SONAR_FILT FLOAT Weight for sonar filter Sonar filter detects spikes on sonar measurements and used to detect new surface level. 0.05 0.0 1.0 INAV_W_ACC_BIAS FLOAT Accelerometer bias estimation weight Weight (cutoff frequency) for accelerometer bias estimation. 0 to disable. 0.05 0.0 0.1 INAV_W_GPS_FLOW FLOAT XY axis weight factor for GPS when optical flow available When optical flow data available, multiply GPS weights (for position and velocity) by this factor. 0.1 0.0 1.0 INAV_W_XY_FLOW FLOAT XY axis weight for optical flow Weight (cutoff frequency) for optical flow (velocity) measurements. 5.0 0.0 10.0 INAV_W_XY_GPS_P FLOAT XY axis weight for GPS position Weight (cutoff frequency) for GPS position measurements. 1.0 0.0 10.0 INAV_W_XY_GPS_V FLOAT XY axis weight for GPS velocity Weight (cutoff frequency) for GPS velocity measurements. 2.0 0.0 10.0 INAV_W_XY_RES_V FLOAT XY axis weight for resetting velocity When velocity sources lost slowly decrease estimated horizontal velocity with this weight. 0.5 0.0 10.0 INAV_W_XY_VIS_P FLOAT XY axis weight for vision position Weight (cutoff frequency) for vision position measurements. 7.0 0.0 10.0 INAV_W_XY_VIS_V FLOAT XY axis weight for vision velocity Weight (cutoff frequency) for vision velocity measurements. 0.0 0.0 10.0 INAV_W_Z_BARO FLOAT Z axis weight for barometer Weight (cutoff frequency) for barometer altitude measurements. 0.5 0.0 10.0 INAV_W_Z_GPS_P FLOAT Z axis weight for GPS Weight (cutoff frequency) for GPS altitude measurements. GPS altitude data is very noisy and should be used only as slow correction for baro offset. 0.005 0.0 10.0 INAV_W_Z_GPS_V FLOAT Z velocity weight for GPS Weight (cutoff frequency) for GPS altitude velocity measurements. 0.0 0.0 10.0 INAV_W_Z_SONAR FLOAT Z axis weight for sonar Weight (cutoff frequency) for sonar measurements. 3.0 0.0 10.0 INAV_W_Z_VIS_P FLOAT Z axis weight for vision Weight (cutoff frequency) for vision altitude measurements. vision altitude data is very noisy and should be used only as slow correction for baro offset. 0.5 0.0 10.0 NAV_RCL_LT FLOAT Loiter Time The amount of time in seconds the system should loiter at current position before termination Set to -1 to make the system skip loitering 120.0 -1.0 seconds RTL_DESCEND_ALT FLOAT RTL loiter altitude Stay at this altitude above home position after RTL descending. Land (i.e. slowly descend) from this altitude if autolanding allowed. 30 2 100 meters RTL_LAND_DELAY FLOAT RTL delay Delay after descend before landing in RTL mode. If set to -1 the system will not land but loiter at NAV_LAND_ALT. -1.0 -1 300 seconds RTL_LOITER_RAD FLOAT Loiter radius after RTL (FW only) Default value of loiter radius after RTL (fixedwing only). 50.0 20 200 meters RTL_RETURN_ALT FLOAT RTL altitude Altitude to fly back in RTL in meters 60 0 150 meters RC1_DZ FLOAT RC Channel 1 dead zone The +- range of this value around the trim value will be considered as zero. 10.0 0.0 100.0 RC1_MAX FLOAT RC Channel 1 Maximum Maximum value for RC channel 1 2000.0 1500.0 2200.0 RC1_MIN FLOAT RC Channel 1 Minimum Minimum value for RC channel 1 1000.0 800.0 1500.0 RC1_REV FLOAT RC Channel 1 Reverse Set to -1 to reverse channel. 1.0 -1.0 1.0 RC1_TRIM FLOAT RC Channel 1 Trim Mid point value (same as min for throttle) 1500.0 800.0 2200.0 RC2_DZ FLOAT RC Channel 2 dead zone The +- range of this value around the trim value will be considered as zero. 10.0 0.0 100.0 RC2_MAX FLOAT RC Channel 2 Maximum Maximum value for RC channel 2 2000.0 1500.0 2200.0 RC2_MIN FLOAT RC Channel 2 Minimum Minimum value for RC channel 2 1000.0 800.0 1500.0 RC2_REV FLOAT RC Channel 2 Reverse Set to -1 to reverse channel. 1.0 -1.0 1.0 RC2_TRIM FLOAT RC Channel 2 Trim Mid point value (same as min for throttle) 1500.0 800.0 2200.0 RC_CHAN_CNT INT32 RC channel count 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 0 18 RC_DSM_BIND INT32 DSM binding trigger -1 = Idle, 0 = Start DSM2 bind, 1 = Start DSMX bind -1 RC_FAILS_THR INT32 Failsafe channel PWM threshold 0 800 2200 RC_MAP_ACRO_SW INT32 Acro switch channel mapping 0 0 18 RC_MAP_AUX1 INT32 Auxiliary switch 1 channel mapping Default function: Camera pitch 0 0 18 RC_MAP_AUX2 INT32 Auxiliary switch 2 channel mapping Default function: Camera roll 0 0 18 RC_MAP_AUX3 INT32 Auxiliary switch 3 channel mapping Default function: Camera azimuth / yaw 0 0 18 RC_MAP_FLAPS INT32 Flaps channel mapping 0 0 18 RC_MAP_LOITER_SW INT32 Loiter switch channel mapping 0 0 18 RC_MAP_MODE_SW INT32 Mode switch channel mapping 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. 0 0 18 RC_MAP_OFFB_SW INT32 Offboard switch channel mapping 0 0 18 RC_MAP_PARAM1 INT32 Channel which changes a parameter Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel. Set to 0 to deactivate * 0 0 18 RC_MAP_PARAM2 INT32 Channel which changes a parameter Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel. Set to 0 to deactivate * 0 0 18 RC_MAP_PARAM3 INT32 Channel which changes a parameter Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel. Set to 0 to deactivate * 0 0 18 RC_MAP_PITCH INT32 Pitch control channel mapping 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. 2 0 18 RC_MAP_POSCTL_SW INT32 Posctl switch channel mapping 0 0 18 RC_MAP_RETURN_SW INT32 Return switch channel mapping 0 0 18 RC_MAP_ROLL INT32 Roll control channel mapping 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. 1 0 18 RC_MAP_THROTTLE INT32 Throttle control channel mapping 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. 3 0 18 RC_MAP_YAW INT32 Yaw control channel mapping 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. 4 0 18 RC_TH_USER INT32 RC mode switch threshold automaic distribution This parameter is used by Ground Station software to specify whether the threshold values for flight mode switches were automatically calculated. 0 indicates that the threshold values were set by the user. Any other value indicates that the threshold value where automatically set by the ground station software. It is only meant for ground station use. 1 0 1 SDLOG_EXT INT32 Enable extended logging mode A value of -1 indicates the commandline argument should be obeyed. A value of 0 disables extended logging mode, a value of 1 enables it. This parameter is only read out before logging starts (which commonly is before arming). -1 -1 1 SDLOG_RATE INT32 Logging rate A value of -1 indicates the commandline argument should be obeyed. A value of 0 sets the minimum rate, any other value is interpreted as rate in Hertz. This parameter is only read out before logging starts (which commonly is before arming). -1 -1 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_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_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_BOARD_ID INT32 ID of the board this parameter set was calibrated on 0 CAL_GYRO0_ID INT32 ID of the Gyro that the calibration is for 0 CAL_GYRO0_XOFF FLOAT Gyro X-axis offset 0.0 -10.0 10.0 CAL_GYRO0_XSCALE FLOAT Gyro X-axis scaling factor 1.0 -1.5 1.5 CAL_GYRO0_YOFF FLOAT Gyro Y-axis offset 0.0 -10.0 10.0 CAL_GYRO0_YSCALE FLOAT Gyro Y-axis scaling factor 1.0 -1.5 1.5 CAL_GYRO0_ZOFF FLOAT Gyro Z-axis offset 0.0 -5.0 5.0 CAL_GYRO0_ZSCALE FLOAT Gyro Z-axis scaling factor 1.0 -1.5 1.5 CAL_GYRO1_ID INT32 ID of the Gyro that the calibration is for 0 CAL_GYRO1_XOFF FLOAT Gyro X-axis offset 0.0 -10.0 10.0 CAL_GYRO1_XSCALE FLOAT Gyro X-axis scaling factor 1.0 -1.5 1.5 CAL_GYRO1_YOFF FLOAT Gyro Y-axis offset 0.0 -10.0 10.0 CAL_GYRO1_YSCALE FLOAT Gyro Y-axis scaling factor 1.0 -1.5 1.5 CAL_GYRO1_ZOFF FLOAT Gyro Z-axis offset 0.0 -5.0 5.0 CAL_GYRO1_ZSCALE FLOAT Gyro Z-axis scaling factor 1.0 -1.5 1.5 CAL_GYRO2_ID INT32 ID of the Gyro that the calibration is for 0 CAL_GYRO2_XOFF FLOAT Gyro X-axis offset 0.0 -10.0 10.0 CAL_GYRO2_XSCALE FLOAT Gyro X-axis scaling factor 1.0 -1.5 1.5 CAL_GYRO2_YOFF FLOAT Gyro Y-axis offset 0.0 -10.0 10.0 CAL_GYRO2_YSCALE FLOAT Gyro Y-axis scaling factor 1.0 -1.5 1.5 CAL_GYRO2_ZOFF FLOAT Gyro Z-axis offset 0.0 -5.0 5.0 CAL_GYRO2_ZSCALE FLOAT Gyro Z-axis scaling factor 1.0 -1.5 1.5 CAL_MAG0_ID INT32 ID of Magnetometer the calibration is for 0 CAL_MAG0_ROT INT32 Rotation of magnetometer 0 relative to airframe 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. -1 -1 30 CAL_MAG0_XOFF FLOAT Magnetometer X-axis offset 0.0 -500.0 500.0 CAL_MAG0_XSCALE FLOAT Magnetometer X-axis scaling factor 1.0 CAL_MAG0_YOFF FLOAT Magnetometer Y-axis offset 0.0 -500.0 500.0 CAL_MAG0_YSCALE FLOAT Magnetometer Y-axis scaling factor 1.0 CAL_MAG0_ZOFF FLOAT Magnetometer Z-axis offset 0.0 -500.0 500.0 CAL_MAG0_ZSCALE FLOAT Magnetometer Z-axis scaling factor 1.0 CAL_MAG1_ID INT32 ID of Magnetometer the calibration is for 0 CAL_MAG1_ROT INT32 Rotation of magnetometer 1 relative to airframe 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. -1 -1 30 CAL_MAG1_XOFF FLOAT Magnetometer X-axis offset 0.0 -500.0 500.0 CAL_MAG1_XSCALE FLOAT Magnetometer X-axis scaling factor 1.0 CAL_MAG1_YOFF FLOAT Magnetometer Y-axis offset 0.0 -500.0 500.0 CAL_MAG1_YSCALE FLOAT Magnetometer Y-axis scaling factor 1.0 CAL_MAG1_ZOFF FLOAT Magnetometer Z-axis offset 0.0 -500.0 500.0 CAL_MAG1_ZSCALE FLOAT Magnetometer Z-axis scaling factor 1.0 CAL_MAG2_ID INT32 ID of Magnetometer the calibration is for 0 CAL_MAG2_ROT INT32 Rotation of magnetometer 2 relative to airframe 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. -1 -1 30 CAL_MAG2_XOFF FLOAT Magnetometer X-axis offset 0.0 -500.0 500.0 CAL_MAG2_XSCALE FLOAT Magnetometer X-axis scaling factor 1.0 CAL_MAG2_YOFF FLOAT Magnetometer Y-axis offset 0.0 -500.0 500.0 CAL_MAG2_YSCALE FLOAT Magnetometer Y-axis scaling factor 1.0 CAL_MAG2_ZOFF FLOAT Magnetometer Z-axis offset 0.0 -500.0 500.0 CAL_MAG2_ZSCALE FLOAT Magnetometer Z-axis scaling factor 1.0 SENS_BARO_QNH FLOAT QNH for barometer 1013.25 500 1500 hPa SENS_BOARD_ROT INT32 Board rotation This parameter defines the rotation of the FMU board relative to the platform. Possible values are: 0 = No rotation 1 = Yaw 45° 2 = Yaw 90° 3 = Yaw 135° 4 = Yaw 180° 5 = Yaw 225° 6 = Yaw 270° 7 = Yaw 315° 8 = Roll 180° 9 = Roll 180°, Yaw 45° 10 = Roll 180°, Yaw 90° 11 = Roll 180°, Yaw 135° 12 = Pitch 180° 13 = Roll 180°, Yaw 225° 14 = Roll 180°, Yaw 270° 15 = Roll 180°, Yaw 315° 16 = Roll 90° 17 = Roll 90°, Yaw 45° 18 = Roll 90°, Yaw 90° 19 = Roll 90°, Yaw 135° 20 = Roll 270° 21 = Roll 270°, Yaw 45° 22 = Roll 270°, Yaw 90° 23 = Roll 270°, Yaw 135° 24 = Pitch 90° 25 = Pitch 270° 0 SENS_BOARD_X_OFF FLOAT Board rotation X (Roll) offset 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 SENS_BOARD_Y_OFF FLOAT Board rotation Y (Pitch) offset 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 SENS_BOARD_Z_OFF FLOAT Board rotation Z (YAW) offset 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 SENS_DPRES_ANSC FLOAT Differential pressure sensor analog scaling 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 The offset (zero-reading) in Pascal 0.0 SENS_EXT_MAG INT32 Set usage of external magnetometer * Set to 0 (default) to auto-detect (will try to get the external as primary) * Set to 1 to force the external magnetometer as primary * Set to 2 to force the internal magnetometer as primary 0 0 2 SENS_EXT_MAG_ROT INT32 External magnetometer rotation This parameter defines the rotation of the external magnetometer relative to the platform (not relative to the FMU). See SENS_BOARD_ROT for possible values. 0 SENS_FLOW_ROT INT32 PX4Flow board rotation This parameter defines the rotation of the PX4FLOW board relative to the platform. Zero rotation is defined as Y on flow board pointing towards front of vehicle Possible values are: 0 = No rotation 1 = Yaw 45° 2 = Yaw 90° 3 = Yaw 135° 4 = Yaw 180° 5 = Yaw 225° 6 = Yaw 270° 7 = Yaw 315° 0 SYS_AUTOCONFIG INT32 Automatically configure default values Set to 1 to reset parameters on next system startup (setting defaults). Platform-specific values are used if available. RC* parameters are preserved. 0 0 1 SYS_AUTOSTART INT32 Auto-start script index Defines the auto-start script used to bootstrap the system. 0 SYS_COMPANION INT32 Companion computer interface Configures the baud rate of the companion computer interface. Set to zero to disable, set to 921600 to enable. CURRENTLY ONLY SUPPORTS 921600 BAUD! Use extras.txt for other baud rates. 0 0 921600 SYS_PARAM_VER INT32 Parameter version This monotonically increasing number encodes the parameter compatibility set. whenever it increases parameters might not be backwards compatible and ground control stations should suggest a fresh configuration. 1 0 SYS_RESTART_TYPE INT32 Set restart type Set by px4io to indicate type of restart 2 0 2 SYS_USE_IO INT32 Set usage of IO board 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. 1 0 1 UAVCAN_BITRATE INT32 UAVCAN CAN bus bitrate 1000000 20000 1000000 UAVCAN_ENABLE INT32 Enable UAVCAN Enables support for UAVCAN-interfaced actuators and sensors. 0 0 1 UAVCAN_NODE_ID INT32 UAVCAN Node ID Read the specs at http://uavcan.org to learn more about Node ID. 1 1 125 VT_ARSP_LP_GAIN FLOAT Total airspeed estimate low-pass filter gain Gain for tuning the low-pass filter for the total airspeed estimate 0.3 0.0 0.99 VT_FW_PERM_STAB INT32 Permanent stabilization in fw mode If set to one this parameter will cause permanent attitude stabilization in fw mode. This parameter has been introduced for pure convenience sake. 0 0 1 VT_FW_PITCH_TRIM FLOAT Fixed wing pitch trim This parameter allows to adjust the neutral elevon position in fixed wing mode. 0.0 -1 1 VT_IDLE_PWM_MC INT32 Idle speed of VTOL when in multicopter mode 900 900 VT_MC_ARSPD_MAX FLOAT Maximum airspeed in multicopter mode This is the maximum speed of the air flowing over the control surfaces. 30.0 0.0 VT_MC_ARSPD_MIN FLOAT Minimum airspeed in multicopter mode This is the minimum speed of the air flowing over the control surfaces. 10.0 0.0 VT_MC_ARSPD_TRIM FLOAT Trim airspeed when in multicopter mode This is the airflow over the control surfaces for which no airspeed scaling is applied in multicopter mode. 10.0 0.0 VT_MOT_COUNT INT32 VTOL number of engines 0 1 VT_POWER_MAX FLOAT Motor max power Indicates the maximum power the motor is able to produce. Used to calculate propeller efficiency map. 120.0 1 VT_PROP_EFF FLOAT Propeller efficiency parameter Influences propeller efficiency at different power settings. Should be tuned beforehand. 0.0 0.5 0.9 ATT_J11 FLOAT Moment of inertia matrix diagonal entry (1, 1) 0.0018 kg*m^2 ATT_J22 FLOAT Moment of inertia matrix diagonal entry (2, 2) 0.0018 kg*m^2 ATT_J33 FLOAT Moment of inertia matrix diagonal entry (3, 3) 0.0037 kg*m^2 ATT_J_EN INT32 Moment of inertia enabled in estimator If set to != 0 the moment of inertia will be used in the estimator 0 0 1 EKF_ATT_V3_Q0 FLOAT Body angular rate process noise 1e-4 EKF_ATT_V3_Q1 FLOAT Body angular acceleration process noise 0.08 EKF_ATT_V3_Q2 FLOAT Acceleration process noise 0.009 EKF_ATT_V3_Q3 FLOAT Magnet field vector process noise 0.005 EKF_ATT_V4_R0 FLOAT Gyro measurement noise 0.0008 EKF_ATT_V4_R1 FLOAT Accel measurement noise 10000.0 EKF_ATT_V4_R2 FLOAT Mag measurement noise 100.0 COM_AUTOS_PAR INT32 If not equal to zero the commander will automatically save parameters to persistent storage once changed. Default is on, as the interoperability with currently deployed GCS solutions depends on parameters being sticky. Developers can default it to off 1 0 1 COM_DL_LOSS_EN INT32 Datalink loss mode enabled Set to 1 to enable actions triggered when the datalink is lost. 0 0 1 COM_DL_LOSS_T INT32 After this amount of seconds without datalink the data link lost mode triggers 10 0 30 second COM_DL_REG_T INT32 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 0 30 second COM_EF_C2T FLOAT Engine failure triggers only below this current/throttle value 5.0 0.0 7.0 COM_EF_THROT FLOAT Engine failure triggers only above this throttle value 0.5 0.0 1.0 COM_EF_TIME FLOAT Engine failure triggers only if the throttle threshold and the current to throttle threshold are violated for this time 10.0 0.0 7.0 second COM_RC_LOSS_T FLOAT After this amount of seconds without RC connection the rc lost flag is set to true 0.5 0 35 second MT_ACC_D FLOAT D gain for the airspeed control Maps the change of airspeed error to the acceleration setpoint 0.0 0.0 10.0 MT_ACC_D_LP FLOAT Lowpass for ACC error derivative calculation (see MT_ACC_D) 0.5 MT_ACC_MAX FLOAT Maximal acceleration (air) 40.0 m/s^2 MT_ACC_MIN FLOAT Minimal acceleration (air) -40.0 m/s^2 MT_ACC_P FLOAT P gain for the airspeed control Maps the airspeed error to the acceleration setpoint 0.3 0.0 10.0 MT_AD_LP FLOAT Airspeed derivative calculation lowpass 0.5 MT_ALT_LP FLOAT Lowpass (cutoff freq.) for altitude 1.0 MT_A_LP FLOAT Lowpass (cutoff freq.) for airspeed 0.5 MT_ENABLED INT32 mTECS enabled Set to 1 to enable mTECS 0 0 1 MT_FPA_D FLOAT D gain for the altitude control Maps the change of altitude error to the flight path angle setpoint 0.0 0.0 10.0 MT_FPA_D_LP FLOAT Lowpass for FPA error derivative calculation (see MT_FPA_D) 1.0 MT_FPA_LP FLOAT Lowpass (cutoff freq.) for the flight path angle 1.0 MT_FPA_MAX FLOAT Maximal flight path angle setpoint 30.0 -90.0 90.0 deg MT_FPA_MIN FLOAT Minimal flight path angle setpoint -20.0 -90.0 90.0 deg MT_FPA_P FLOAT P gain for the altitude control Maps the altitude error to the flight path angle setpoint 0.3 0.0 10.0 MT_LND_PIT_MAX FLOAT Maximal pitch in landing mode 15.0 -90.0 90.0 deg MT_LND_PIT_MIN FLOAT Minimal pitch in landing mode -5.0 -90.0 90.0 deg MT_LND_THR_MAX FLOAT Maximal throttle in landing mode (only last phase of landing) 0.0 0.0 1.0 MT_LND_THR_MIN FLOAT Minimal throttle in landing mode (only last phase of landing) 0.0 0.0 1.0 MT_PIT_FF FLOAT Energy Distribution Rate Control Feedforward Maps the energy distribution rate setpoint to the pitch setpoint 0.4 0.0 10.0 MT_PIT_I FLOAT Energy Distribution Rate Control I Maps the integrated energy distribution rate error to the pitch setpoint 0.03 0.0 10.0 MT_PIT_I_MAX FLOAT Integrator Limit for Energy Distribution Rate Control 10.0 0.0 10.0 MT_PIT_MAX FLOAT Maximal Pitch Setpoint in Degrees 20.0 -90.0 90.0 deg MT_PIT_MIN FLOAT Minimal Pitch Setpoint in Degrees -45.0 -90.0 90.0 deg MT_PIT_OFF FLOAT Total Energy Distribution Offset (Cruise pitch sp) 0.0 0.0 10.0 MT_PIT_P FLOAT Energy Distribution Rate Control P Maps the energy distribution rate error to the pitch setpoint 0.03 0.0 10.0 MT_THR_FF FLOAT Total Energy Rate Control Feedforward Maps the total energy rate setpoint to the throttle setpoint 0.7 0.0 10.0 MT_THR_I FLOAT Total Energy Rate Control I Maps the integrated total energy rate to the throttle setpoint 0.25 0.0 10.0 MT_THR_I_MAX FLOAT Integrator Limit for Total Energy Rate Control 10.0 0.0 10.0 MT_THR_MAX FLOAT Maximal Throttle Setpoint 1.0 0.0 1.0 MT_THR_MIN FLOAT Minimal Throttle Setpoint 0.0 0.0 1.0 MT_THR_OFF FLOAT Total Energy Rate Control Offset (Cruise throttle sp) 0.7 0.0 10.0 MT_THR_P FLOAT Total Energy Rate Control P Maps the total energy rate error to the throttle setpoint 0.1 0.0 10.0 MT_TKF_PIT_MAX FLOAT Maximal pitch during takeoff 45.0 -90.0 90.0 deg MT_TKF_PIT_MIN FLOAT Minimal pitch during takeoff 0.0 -90.0 90.0 deg MT_TKF_THR_MAX FLOAT Maximal throttle during takeoff 1.0 0.0 1.0 MT_TKF_THR_MIN FLOAT Minimal throttle during takeoff 1.0 0.0 1.0 MT_USP_PIT_MAX FLOAT Maximal pitch in underspeed mode 0.0 -90.0 90.0 deg MT_USP_PIT_MIN FLOAT Minimal pitch in underspeed mode -45.0 -90.0 90.0 deg MT_USP_THR_MAX FLOAT Maximal throttle in underspeed mode 1.0 0.0 1.0 MT_USP_THR_MIN FLOAT Minimal throttle in underspeed mode 1.0 0.0 1.0 ATT_ACC_COMP INT32 ATT_ACC_COMP 2 ATT_MAG_DECL FLOAT ATT_MAG_DECL 0.0 EXFW_HDNG_P FLOAT EXFW_HDNG_P 0.1 EXFW_PITCH_P FLOAT EXFW_PITCH_P 0.2 EXFW_ROLL_P FLOAT EXFW_ROLL_P 0.2 FPE_DEBUG INT32 FPE_DEBUG 0 FPE_LO_THRUST FLOAT FPE_LO_THRUST 0.4 FPE_SONAR_LP_L FLOAT FPE_SONAR_LP_L 0.2 FPE_SONAR_LP_U FLOAT FPE_SONAR_LP_U 0.5 FWB_CR2THR_D FLOAT FWB_CR2THR_D 0.0 FWB_CR2THR_D_LP FLOAT FWB_CR2THR_D_LP 0.0 FWB_CR2THR_I FLOAT FWB_CR2THR_I 0.0 FWB_CR2THR_I_MAX FLOAT FWB_CR2THR_I_MAX 0.0 FWB_CR2THR_P FLOAT FWB_CR2THR_P 0.01 FWB_CR_MAX FLOAT FWB_CR_MAX 1.0 FWB_H2THR_D FLOAT FWB_H2THR_D 0.0 FWB_H2THR_D_LP FLOAT FWB_H2THR_D_LP 0.0 FWB_H2THR_I FLOAT FWB_H2THR_I 0.0 FWB_H2THR_I_MAX FLOAT FWB_H2THR_I_MAX 0.0 FWB_H2THR_P FLOAT FWB_H2THR_P 0.01 FWB_P2AIL FLOAT FWB_P2AIL 0.3 FWB_PHI2P FLOAT FWB_PHI2P 1.0 FWB_PHI_LIM_MAX FLOAT FWB_PHI_LIM_MAX 0.3 FWB_PSI2PHI FLOAT FWB_PSI2PHI 0.5 FWB_P_LP FLOAT FWB_P_LP 300.0 FWB_Q2ELV FLOAT FWB_Q2ELV 0.1 FWB_Q_LP FLOAT FWB_Q_LP 300.0 FWB_R2RDR FLOAT FWB_R2RDR 0.1 FWB_R_HP FLOAT FWB_R_HP 1.0 FWB_R_LP FLOAT FWB_R_LP 300.0 FWB_THE2Q_D FLOAT FWB_THE2Q_D 0.0 FWB_THE2Q_D_LP FLOAT FWB_THE2Q_D_LP 0.0 FWB_THE2Q_I FLOAT FWB_THE2Q_I 0.0 FWB_THE2Q_I_MAX FLOAT FWB_THE2Q_I_MAX 0.0 FWB_THE2Q_P FLOAT FWB_THE2Q_P 1.0 FWB_THE_MAX FLOAT FWB_THE_MAX 0.5 FWB_THE_MIN FLOAT FWB_THE_MIN -0.5 FWB_TRIM_THR FLOAT FWB_TRIM_THR 0.8 FWB_TRIM_V FLOAT FWB_TRIM_V 12.0 FWB_V2THE_D FLOAT FWB_V2THE_D 0.0 FWB_V2THE_D_LP FLOAT FWB_V2THE_D_LP 0.0 FWB_V2THE_I FLOAT FWB_V2THE_I 0.0 FWB_V2THE_I_MAX FLOAT FWB_V2THE_I_MAX 0.0 FWB_V2THE_P FLOAT FWB_V2THE_P 1.0 FWB_V_CMD FLOAT FWB_V_CMD 12.0 FWB_V_MAX FLOAT FWB_V_MAX 16.0 FWB_V_MIN FLOAT FWB_V_MIN 10.0 FWB_XT2YAW FLOAT FWB_XT2YAW 0.005 FWB_XT2YAW_MAX FLOAT FWB_XT2YAW_MAX 1.57 FW_FLARE_PMAX FLOAT Flare, maximum pitch Maximum pitch during flare, a positive sign means nose up Applied once FW_LND_TLALT is reached 15.0 FW_FLARE_PMIN FLOAT Flare, minimum pitch Minimum pitch during flare, a positive sign means nose up Applied once FW_LND_TLALT is reached 2.5 RC10_DZ FLOAT RC10_DZ 0.0 RC10_MAX FLOAT RC10_MAX 2000 RC10_MIN FLOAT RC10_MIN 1000 RC10_REV FLOAT RC10_REV 1.0 RC10_TRIM FLOAT RC10_TRIM 1500 RC11_DZ FLOAT RC11_DZ 0.0 RC11_MAX FLOAT RC11_MAX 2000 RC11_MIN FLOAT RC11_MIN 1000 RC11_REV FLOAT RC11_REV 1.0 RC11_TRIM FLOAT RC11_TRIM 1500 RC12_DZ FLOAT RC12_DZ 0.0 RC12_MAX FLOAT RC12_MAX 2000 RC12_MIN FLOAT RC12_MIN 1000 RC12_REV FLOAT RC12_REV 1.0 RC12_TRIM FLOAT RC12_TRIM 1500 RC13_DZ FLOAT RC13_DZ 0.0 RC13_MAX FLOAT RC13_MAX 2000 RC13_MIN FLOAT RC13_MIN 1000 RC13_REV FLOAT RC13_REV 1.0 RC13_TRIM FLOAT RC13_TRIM 1500 RC14_DZ FLOAT RC14_DZ 0.0 RC14_MAX FLOAT RC14_MAX 2000 RC14_MIN FLOAT RC14_MIN 1000 RC14_REV FLOAT RC14_REV 1.0 RC14_TRIM FLOAT RC14_TRIM 1500 RC15_DZ FLOAT RC15_DZ 0.0 RC15_MAX FLOAT RC15_MAX 2000 RC15_MIN FLOAT RC15_MIN 1000 RC15_REV FLOAT RC15_REV 1.0 RC15_TRIM FLOAT RC15_TRIM 1500 RC16_DZ FLOAT RC16_DZ 0.0 RC16_MAX FLOAT RC16_MAX 2000 RC16_MIN FLOAT RC16_MIN 1000 RC16_REV FLOAT RC16_REV 1.0 RC16_TRIM FLOAT RC16_TRIM 1500 RC17_DZ FLOAT RC17_DZ 0.0 RC17_MAX FLOAT RC17_MAX 2000 RC17_MIN FLOAT RC17_MIN 1000 RC17_REV FLOAT RC17_REV 1.0 RC17_TRIM FLOAT RC17_TRIM 1500 RC18_DZ FLOAT RC18_DZ 0.0 RC18_MAX FLOAT RC18_MAX 2000 RC18_MIN FLOAT RC18_MIN 1000 RC18_REV FLOAT RC18_REV 1.0 RC18_TRIM FLOAT RC18_TRIM 1500 RC3_DZ FLOAT RC3_DZ 10.0 RC3_MAX FLOAT RC3_MAX 2000 RC3_MIN FLOAT RC3_MIN 1000 RC3_REV FLOAT RC3_REV 1.0 RC3_TRIM FLOAT RC3_TRIM 1500 RC4_DZ FLOAT RC4_DZ 10.0 RC4_MAX FLOAT RC4_MAX 2000 RC4_MIN FLOAT RC4_MIN 1000 RC4_REV FLOAT RC4_REV 1.0 RC4_TRIM FLOAT RC4_TRIM 1500 RC5_DZ FLOAT RC5_DZ 10.0 RC5_MAX FLOAT RC5_MAX 2000 RC5_MIN FLOAT RC5_MIN 1000 RC5_REV FLOAT RC5_REV 1.0 RC5_TRIM FLOAT RC5_TRIM 1500 RC6_DZ FLOAT RC6_DZ 10.0 RC6_MAX FLOAT RC6_MAX 2000 RC6_MIN FLOAT RC6_MIN 1000 RC6_REV FLOAT RC6_REV 1.0 RC6_TRIM FLOAT RC6_TRIM 1500 RC7_DZ FLOAT RC7_DZ 10.0 RC7_MAX FLOAT RC7_MAX 2000 RC7_MIN FLOAT RC7_MIN 1000 RC7_REV FLOAT RC7_REV 1.0 RC7_TRIM FLOAT RC7_TRIM 1500 RC8_DZ FLOAT RC8_DZ 10.0 RC8_MAX FLOAT RC8_MAX 2000 RC8_MIN FLOAT RC8_MIN 1000 RC8_REV FLOAT RC8_REV 1.0 RC8_TRIM FLOAT RC8_TRIM 1500 RC9_DZ FLOAT RC9_DZ 0.0 RC9_MAX FLOAT RC9_MAX 2000 RC9_MIN FLOAT RC9_MIN 1000 RC9_REV FLOAT RC9_REV 1.0 RC9_TRIM FLOAT RC9_TRIM 1500 RC_ACRO_TH FLOAT Threshold for selecting acro mode min:-1 max:+1 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<th 0.5 RC_ASSIST_TH FLOAT Threshold for selecting assist mode min:-1 max:+1 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<th 0.25 RC_AUTO_TH FLOAT Threshold for selecting auto mode min:-1 max:+1 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<th 0.75 RC_LOITER_TH FLOAT Threshold for selecting loiter mode min:-1 max:+1 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<th 0.5 RC_MAP_FAILSAFE INT32 Failsafe channel mapping 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 0 0 18 RC_OFFB_TH FLOAT Threshold for selecting offboard mode min:-1 max:+1 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<th 0.5 RC_POSCTL_TH FLOAT Threshold for selecting posctl mode min:-1 max:+1 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<th 0.5 RC_RETURN_TH FLOAT Threshold for selecting return to launch mode min:-1 max:+1 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<th 0.5 RC_RL1_DSM_VCC INT32 RC_RL1_DSM_VCC 0 RV_YAW_P FLOAT RV_YAW_P 0.1 SEG_Q2V FLOAT SEG_Q2V 1.0 SEG_TH2V_I FLOAT SEG_TH2V_I 0.0 SEG_TH2V_I_MAX FLOAT SEG_TH2V_I_MAX 0.0 SEG_TH2V_P FLOAT SEG_TH2V_P 10.0 SO3_COMP_KI FLOAT SO3_COMP_KI 0.05 SO3_COMP_KP FLOAT SO3_COMP_KP 1.0 SO3_PITCH_OFFS FLOAT SO3_PITCH_OFFS 0.0 SO3_ROLL_OFFS FLOAT SO3_ROLL_OFFS 0.0 SO3_YAW_OFFS FLOAT SO3_YAW_OFFS 0.0 TEST_D FLOAT TEST_D 0.01 TEST_DEV FLOAT TEST_DEV 2.0 TEST_D_LP FLOAT TEST_D_LP 10.0 TEST_HP FLOAT TEST_HP 10.0 TEST_I FLOAT TEST_I 0.1 TEST_I_MAX FLOAT TEST_I_MAX 1.0 TEST_LP FLOAT TEST_LP 10.0 TEST_MAX FLOAT TEST_MAX 1.0 TEST_MEAN FLOAT TEST_MEAN 1.0 TEST_MIN FLOAT TEST_MIN -1.0 TEST_P FLOAT TEST_P 0.2 TEST_TRIM FLOAT TEST_TRIM 0.5 TRIM_PITCH FLOAT TRIM_PITCH 0.0 TRIM_ROLL FLOAT TRIM_ROLL 0.0 TRIM_YAW FLOAT TRIM_YAW 0.0