mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
fw defaults param fix
This commit is contained in:
parent
ff338d8920
commit
adab451013
@ -7,9 +7,10 @@ then
|
||||
#
|
||||
# Default parameters for FW
|
||||
#
|
||||
param set NAV_LAND_ALT 90
|
||||
param set NAV_RTL_ALT 100
|
||||
param set NAV_RTL_LAND_T -1
|
||||
param set RTL_RETURN_ALT 100
|
||||
param set RTL_DESCEND_ALT 100
|
||||
param set RTL_LAND_DELAY -1
|
||||
|
||||
param set NAV_ACC_RAD 50
|
||||
|
||||
param set PE_VELNE_NOISE 0.3
|
||||
|
||||
@ -73,7 +73,7 @@ PARAM_DEFINE_FLOAT(RTL_DESCEND_ALT, 30);
|
||||
* 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.
|
||||
* If set to -1 the system will not land but loiter at RTL_DESCEND_ALT.
|
||||
*
|
||||
* @unit s
|
||||
* @min -1
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user