diff --git a/src/modules/vtol_att_control/tailsitter.cpp b/src/modules/vtol_att_control/tailsitter.cpp
index f765c424fb1ce6c2c8e65b82bdbc2f6559d4db48..73fee6f092dd5cf54168ae1cc118090e75a8d320 100644
--- a/src/modules/vtol_att_control/tailsitter.cpp
+++ b/src/modules/vtol_att_control/tailsitter.cpp
@@ -198,8 +198,6 @@ void Tailsitter::update_transition_state()
 		_v_att_sp->pitch_body = math::constrain(_v_att_sp->pitch_body, PITCH_TRANSITION_FRONT_P1 - 0.2f,
 							_pitch_transition_start);
 
-		_v_att_sp->thrust = _mc_virtual_att_sp->thrust;
-
 		// disable mc yaw control once the plane has picked up speed
 		if (_airspeed->indicated_airspeed_m_s > ARSP_YAW_CTRL_DISABLE) {
 			_mc_yaw_weight = 0.0f;
@@ -222,9 +220,6 @@ void Tailsitter::update_transition_state()
 					time_since_trans_start / _params->back_trans_duration;
 		_v_att_sp->pitch_body = math::constrain(_v_att_sp->pitch_body, -2.0f, PITCH_TRANSITION_BACK + 0.2f);
 
-
-		_v_att_sp->thrust = _mc_virtual_att_sp->thrust;
-
 		// keep yaw disabled
 		_mc_yaw_weight = 0.0f;
 
@@ -233,6 +228,13 @@ void Tailsitter::update_transition_state()
 
 	}
 
+	if (_v_control_mode->flag_control_climb_rate_enabled) {
+		_v_att_sp->thrust = _params->front_trans_throttle;
+
+	} else {
+		_v_att_sp->thrust = _mc_virtual_att_sp->thrust;
+	}
+
 	_mc_roll_weight = math::constrain(_mc_roll_weight, 0.0f, 1.0f);
 	_mc_yaw_weight = math::constrain(_mc_yaw_weight, 0.0f, 1.0f);
 	_mc_pitch_weight = math::constrain(_mc_pitch_weight, 0.0f, 1.0f);