diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 661dad0..e5f4f68 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -1441,6 +1441,9 @@ Lockdown + + Flag to enable obstacle avoidance + 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. @@ -1511,6 +1514,17 @@ s 3 + + RC loss exceptions + Specify modes in which RC loss is ignored and the failsafe action not triggered. + 0 + 31 + + Mission + Hold + Offboard + + RC input arm/disarm command duration The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second. @@ -1562,11 +1576,46 @@ Rearming grace period Re-arming grace allows to rearm the drone with manual command without running prearmcheck during 5 s after disarming. + + Action after TAKEOFF has been accepted + The mode transition after TAKEOFF has completed successfully. + + Hold + Mission (if valid) + + Horizontal velocity error threshold 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. m/s + + Set data link loss failsafe mode + 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. + 0 + 6 + + Disabled + Hold mode + Return mode + Land mode + Terminate + Lockdown + + + + Set RC loss failsafe mode + 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. + 1 + 6 + + Hold mode + Return mode + Land mode + Terminate + Lockdown + + Maximum allowed RTL flight in minutes This is used to determine when the vehicle should be switched to RTL due to low battery. Note, particularly for multirotors this should reflect flight time at cruise speed, not while stationary @@ -4810,17 +4859,6 @@ - - Flag to enable obstacle avoidance - - - Action after TAKEOFF has been accepted - The mode transition after TAKEOFF has completed successfully. - - Hold - Mission (if valid) - - 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 home position. @@ -4910,18 +4948,6 @@ 1 0.5 - - Set data link loss failsafe mode - 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. - - Disabled - Hold mode - Return mode - Land mode - Terminate - Lockdown - - Force VTOL mode takeoff and land @@ -4960,18 +4986,6 @@ 1 0.5 - - Set RC loss failsafe mode - 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. - - Disabled - Hold mode - Return mode - Land mode - Terminate - Lockdown - - Set traffic avoidance mode Enabling this will allow the system to respond to transponder data from e.g. ADSB transponders