diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index bc88ed0539..507a34a3a0 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -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 diff --git a/ArduCopter/config.h b/ArduCopter/config.h index d8ad95b22b..db8a5b01fa 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -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