mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Copter: add PILOT_TKOFF_ALT_DEFAULT definition
No functional change
This commit is contained in:
parent
33a274c928
commit
e0ef57fdb5
@ -78,7 +78,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Units: Centimeters
|
// @Units: Centimeters
|
||||||
// @Range: 0.0 1000.0
|
// @Range: 0.0 1000.0
|
||||||
// @Increment: 10
|
// @Increment: 10
|
||||||
GSCALAR(pilot_takeoff_alt, "PILOT_TKOFF_ALT", 0.0f),
|
GSCALAR(pilot_takeoff_alt, "PILOT_TKOFF_ALT", PILOT_TKOFF_ALT_DEFAULT),
|
||||||
|
|
||||||
// @Param: PILOT_TKOFF_DZ
|
// @Param: PILOT_TKOFF_DZ
|
||||||
// @DisplayName: Takeoff trigger deadzone
|
// @DisplayName: Takeoff trigger deadzone
|
||||||
|
@ -367,6 +367,17 @@
|
|||||||
# define FS_THR_VALUE_DEFAULT 975
|
# define FS_THR_VALUE_DEFAULT 975
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
// Takeoff
|
||||||
|
//
|
||||||
|
#ifndef PILOT_TKOFF_ALT_DEFAULT
|
||||||
|
# define PILOT_TKOFF_ALT_DEFAULT 0 // default final alt above home for pilot initiated takeoff
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
// Landing
|
||||||
|
//
|
||||||
#ifndef LAND_SPEED
|
#ifndef LAND_SPEED
|
||||||
# define LAND_SPEED 50 // the descent speed for the final stage of landing in cm/s
|
# define LAND_SPEED 50 // the descent speed for the final stage of landing in cm/s
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user