diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp
index c11917869e..5b261b1ff5 100644
--- a/ArduPlane/Parameters.cpp
+++ b/ArduPlane/Parameters.cpp
@@ -205,15 +205,6 @@ const AP_Param::Info Plane::var_info[] = {
     // @User: Advanced
     GSCALAR(takeoff_pitch_limit_reduction_sec, "TKOFF_PLIM_SEC",  2),
 
-    // @Param: LAND_THR_SLEW
-    // @DisplayName: Landing throttle slew rate
-    // @Description: This parameter sets the slew rate for the throttle during auto landing. When this is zero the THR_SLEWRATE parameter is used during landing. The value is a percentage throttle change per second, so a value of 20 means to advance the throttle over 5 seconds on landing. Values below 50 are not recommended as it may cause a stall when airspeed is low and you can not throttle up fast enough.
-    // @Units: percent
-    // @Range: 0 127
-    // @Increment: 1
-    // @User: User
-    GSCALAR(land_throttle_slewrate, "LAND_THR_SLEW",  0),
-
     // @Param: TKOFF_FLAP_PCNT
     // @DisplayName: Takeoff flap percentage
     // @Description: The amount of flaps (as a percentage) to apply in automatic takeoff
@@ -244,29 +235,6 @@ const AP_Param::Info Plane::var_info[] = {
     // @User: Advanced
     GSCALAR(use_reverse_thrust,     "USE_REV_THRUST",  USE_REVERSE_THRUST_AUTO_LAND_APPROACH),
 
-    // @Param: LAND_DISARMDELAY
-    // @DisplayName: Landing disarm delay
-    // @Description: After a landing has completed using a LAND waypoint, automatically disarm after this many seconds have passed. Use 0 to not disarm.
-    // @Units: seconds
-    // @Increment: 1
-    // @Range: 0 127
-    // @User: Advanced
-    GSCALAR(land_disarm_delay,       "LAND_DISARMDELAY",  20),
-
-    // @Param: LAND_THEN_NEUTRL
-    // @DisplayName: Set servos to neutral after landing
-    // @Description: When enabled, after an autoland and auto-disarm via LAND_DISARMDELAY happens then set all servos to neutral. This is helpful when an aircraft has a rough landing upside down or a crazy angle causing the servos to strain.
-    // @Values: 0:Disabled, 1:Servos to Neutral, 2:Servos to Zero PWM
-    // @User: Advanced
-    GSCALAR(land_then_servos_neutral,       "LAND_THEN_NEUTRL",  0),
-
-    // @Param: LAND_ABORT_THR
-    // @DisplayName: Landing abort using throttle
-    // @Description: Allow a landing abort to trigger with a throttle > 95%
-    // @Values: 0:Disabled, 1:Enabled
-    // @User: Advanced
-    GSCALAR(land_abort_throttle_enable,       "LAND_ABORT_THR",  0),
-
 	// @Param: NAV_CONTROLLER
 	// @DisplayName: Navigation controller selection
 	// @Description: Which navigation controller to enable. Currently the only navigation controller available is L1. From time to time other experimental controllers will be added which are selected using this parameter.
@@ -928,14 +896,6 @@ const AP_Param::Info Plane::var_info[] = {
     // @User: Advanced
     GSCALAR(flap_2_speed,           "FLAP_2_SPEED",   FLAP_2_SPEED),
 
-    // @Param: LAND_FLAP_PERCNT
-    // @DisplayName: Landing flap percentage
-    // @Description: The amount of flaps (as a percentage) to apply in the landing approach and flare of an automatic landing
-    // @Range: 0 100
-    // @Units: Percent
-    // @User: Advanced
-    GSCALAR(land_flap_percent,     "LAND_FLAP_PERCNT", 0),
-
 #if HAVE_PX4_MIXER
     // @Param: OVERRIDE_CHAN
     // @DisplayName: PX4IO override channel
@@ -1392,6 +1352,11 @@ const AP_Param::ConversionInfo conversion_table[] = {
     { Parameters::k_param_land_pre_flare_sec, 0,      AP_PARAM_FLOAT, "LAND_PF_SEC" },
     { Parameters::k_param_land_pre_flare_alt, 0,      AP_PARAM_FLOAT, "LAND_PF_ALT" },
     { Parameters::k_param_land_pre_flare_airspeed, 0, AP_PARAM_FLOAT, "LAND_PF_ARSPD" },
+    { Parameters::k_param_land_throttle_slewrate, 0,  AP_PARAM_INT8,  "LAND_THR_SLEW" },
+    { Parameters::k_param_land_disarm_delay,  0,      AP_PARAM_INT8,  "LAND_DISARMDELAY" },
+    { Parameters::k_param_land_then_servos_neutral,0, AP_PARAM_INT8,  "LAND_THEN_NEUTRAL" },
+    { Parameters::k_param_land_abort_throttle_enable,0,AP_PARAM_INT8, "LAND_ABORT_THR" },
+    { Parameters::k_param_land_flap_percent,  0,      AP_PARAM_INT8,  "LAND_FLAP_PERCENT" },
 
 };
 
diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h
index 544c93918a..f8e4a8b61b 100644
--- a/ArduPlane/Parameters.h
+++ b/ArduPlane/Parameters.h
@@ -125,7 +125,7 @@ public:
         k_param_terrain_lookahead,
         k_param_fbwa_tdrag_chan,
         k_param_rangefinder_landing,
-        k_param_land_flap_percent,
+        k_param_land_flap_percent,  // unused - moved to AP_Landing
         k_param_takeoff_flap_percent,
         k_param_flap_slewrate,
         k_param_rtl_autoland,
@@ -135,13 +135,13 @@ public:
         k_param_cli_enabled,
         k_param_trim_rc_at_start,
         k_param_hil_mode,
-        k_param_land_disarm_delay,
+        k_param_land_disarm_delay,  // unused - moved to AP_Landing
         k_param_glide_slope_threshold,
         k_param_rudder_only,
         k_param_gcs3,            // 93
         k_param_gcs_pid_mask,
         k_param_crash_detection_enable,
-        k_param_land_abort_throttle_enable,
+        k_param_land_abort_throttle_enable, // unused - moved to AP_Landing
         k_param_rssi = 97,
         k_param_rpm_sensor,
         k_param_parachute,
@@ -149,7 +149,7 @@ public:
         k_param_parachute_channel,
         k_param_crash_accel_threshold,
         k_param_override_safety,
-        k_param_land_throttle_slewrate, // 104
+        k_param_land_throttle_slewrate, // 104 unused - moved to AP_Landing
 
         // 105: Extra parameters
         k_param_fence_retalt = 105,
@@ -288,7 +288,7 @@ public:
         k_param_scaling_speed,
         k_param_quadplane,
         k_param_rtl_radius,
-        k_param_land_then_servos_neutral,
+        k_param_land_then_servos_neutral,   // unused - moved to AP_Landing
         k_param_rc_15,
         k_param_rc_16,
 
@@ -473,9 +473,6 @@ public:
     AP_Int8 reset_switch_chan;
     AP_Int8 reset_mission_chan;
     AP_Int32 RTL_altitude_cm;
-    AP_Int8 land_disarm_delay;
-    AP_Int8 land_then_servos_neutral;
-    AP_Int8 land_abort_throttle_enable;
     AP_Int16 pitch_trim_cd;
     AP_Int16 FBWB_min_altitude_cm;
     AP_Int8  hil_servos;
@@ -488,7 +485,6 @@ public:
     AP_Int8 flap_1_speed;
     AP_Int8 flap_2_percent;
     AP_Int8 flap_2_speed;
-    AP_Int8 land_flap_percent;
     AP_Int8 takeoff_flap_percent;  
     AP_Int8 inverted_flight_ch;             // 0=disabled, 1-8 is channel for inverted flight trigger
     AP_Int8 stick_mixing;
@@ -500,7 +496,6 @@ public:
     AP_Float takeoff_rotate_speed;
     AP_Int8 takeoff_throttle_slewrate;
     AP_Float takeoff_pitch_limit_reduction_sec;
-    AP_Int8 land_throttle_slewrate;
     AP_Int8 level_roll_limit;
     AP_Int8 flapin_channel;
     AP_Int8 flaperon_output;