diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index b9d9145087..71738a77e3 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -100,7 +100,7 @@ public: k_param_auto_slew_rate, k_param_sonar_type, k_param_super_simple, - k_param_rtl_land_enabled, + k_param_rtl_land_enabled, // Depricated!! k_param_axis_enabled, k_param_copter_leds_mode, //158 k_param_ahrs, // AHRS group @@ -112,6 +112,7 @@ public: k_param_crosstrack_gain, k_param_auto_land_timeout, k_param_rtl_approach_alt, + k_param_tilt_comp, //164 // @@ -213,7 +214,8 @@ public: AP_Float low_voltage; AP_Int8 super_simple; AP_Int8 rtl_land_enabled; - AP_Float rtl_approach_alt; + AP_Int16 rtl_approach_alt; + AP_Float tilt_comp; AP_Int8 axis_enabled; AP_Int8 copter_leds_mode; // Operating mode of LED lighting system @@ -333,8 +335,9 @@ public: optflow_enabled (OPTFLOW), low_voltage (LOW_VOLTAGE), super_simple (SUPER_SIMPLE), - rtl_land_enabled (RTL_AUTO_LAND), - rtl_approach_alt (0.0), + rtl_land_enabled (0), + rtl_approach_alt (RTL_APPROACH_ALT), + tilt_comp (.0054), axis_enabled (AXIS_LOCK_ENABLED), copter_leds_mode (9), diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index fb70b2a9be..d1a6987692 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -83,6 +83,7 @@ static const AP_Param::Info var_info[] PROGMEM = { // @Description: Setting this to Enabled(1) will enable landing after RTL. Setting this to Disabled(0) will disable landing after RTL. // @Values: 0:Disabled,1:Enabled // @User: Standard + // @ DEPRICATED GSCALAR(rtl_land_enabled, "RTL_LAND"), // @Param: APPROACH_ALT @@ -94,6 +95,8 @@ static const AP_Param::Info var_info[] PROGMEM = { // @User: Standard GSCALAR(rtl_approach_alt, "APPROACH_ALT"), + GSCALAR(tilt_comp, "TILT"), + GSCALAR(waypoint_mode, "WP_MODE"), GSCALAR(command_total, "WP_TOTAL"), GSCALAR(command_index, "WP_INDEX"),