Rlt code in ac 3.3 and ac 3.5.5

i ned that the copter not disarms after landing,
i have that in ac 3.3 with this modification in tthe controlrtl.cpp

// rtl_returnhome_run - return home
// called by rtl_run at 100hz or more
void Copter::rtl_land_run()
{
int16_t roll_control = 0, pitch_control = 0;
float target_yaw_rate = 0;
// if not auto armed or landing completed or motor interlock not enabled set throttle to zero and exit immediately
if(!ap.auto_armed || ap.land_complete || !motors.get_interlock()) {
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
// call attitude controller
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
attitude_control.set_throttle_out(0,false,g.throttle_filt);
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
#endif
// set target to current position
wp_nav.init_loiter_target();

///esto lo comento yo///

/// #if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED
/// // disarm when the landing detector says we’ve landed and throttle is at minimum
/// if (ap.land_complete && (ap.throttle_zero || failsafe.radio)) {
/// init_disarm_motors();
/// }
/// #else
/// // disarm when the landing detector says we’ve landed
/// if (ap.land_complete) {
/// init_disarm_motors();
/// }
/// #endif

    // check if we've completed this stage of RTL
    rtl_state_complete = ap.land_complete;
    return;
}

i just comented a few lines…
how can i have the same thing in ac 3.5.5, i try a lot of things but nathingg…:
// rtl_returnhome_run - return home
// called by rtl_run at 100hz or more
void Copter::rtl_land_run()
{
// if not auto armed or landing completed or motor interlock not enabled set throttle to zero and exit immediately
if (!motors->armed() || !ap.auto_armed || ap.land_complete || !motors->get_interlock()) {
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
// call attitude controller
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0, 0, 0, get_smoothing_gain());
attitude_control->set_throttle_out(0,false,g.throttle_filt);
#else
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
// multicopters do not stabilize roll/pitch/yaw when disarmed
attitude_control->set_throttle_out_unstabilized(0,true,g.throttle_filt);
#endif
// set target to current position
wp_nav->init_loiter_target();

    // disarm when the landing detector says we've landed

/// if (ap.land_complete) {
/// init_disarm_motors();
/// }

    // check if we've completed this stage of RTL
    rtl_state_complete = ap.land_complete;
    return;
}

thank you very much