Copter: add PILOT_TKOFF_ALT_DEFAULT definition

No functional change
This commit is contained in:
Randy Mackay 2015-04-30 14:24:48 +09:00
parent 33a274c928
commit e0ef57fdb5
2 changed files with 12 additions and 1 deletions

View File

@ -78,7 +78,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Units: Centimeters
// @Range: 0.0 1000.0
// @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
// @DisplayName: Takeoff trigger deadzone

View File

@ -367,6 +367,17 @@
# define FS_THR_VALUE_DEFAULT 975
#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
# define LAND_SPEED 50 // the descent speed for the final stage of landing in cm/s
#endif