diff --git a/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d
index b6ef969ed4504337c382121c8e3bb46ae99b80cc..0284bbaf5f2aed490ce3f3abe1e4e847a2a94864 100644
--- a/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d
+++ b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d
@@ -36,7 +36,6 @@ then
 	param set MC_YAWRATE_P 0.2
 	param set MC_YAWRATE_I 0.1
 	param set MC_YAWRATE_D 0.0
-	param set MC_YAW_FF 0.5
 
 	param set BAT_N_CELLS 4
 fi
diff --git a/ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik b/ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik
index 3db8e69db2faf8050ca762a03f9785588a75d957..2be4f390052dcd82f37ecc175d6e9690f308f778 100644
--- a/ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik
+++ b/ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik
@@ -37,7 +37,6 @@ then
 	param set MC_YAWRATE_P 0.2
 	param set MC_YAWRATE_I 0.1
 	param set MC_YAWRATE_D 0.0
-	param set MC_YAW_FF 0.5
 
 	param set MPC_HOLD_MAX_XY 0.25
 	param set MPC_THR_MIN 0.15
diff --git a/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol b/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol
index a5c516b24af6726eaaca0212187c36f2e2d6ee92..b266012481b915b26a20bdbdb0011b8d1353feec 100644
--- a/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol
+++ b/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol
@@ -28,7 +28,6 @@ then
 	param set MC_PITCHRATE_D 0.003
 	param set MC_PITCHRATE_FF 0.0
 	param set MC_YAW_P 3.8
-	param set MC_YAW_FF 0.5
 	param set MC_YAWRATE_P 0.22
 	param set MC_YAWRATE_I 0.02
 	param set MC_YAWRATE_D 0.0
diff --git a/ROMFS/px4fmu_common/init.d/13002_firefly6 b/ROMFS/px4fmu_common/init.d/13002_firefly6
index 504b9056a3cfcbd8f20d28d80b2ff4d6294c1550..bcaa78048c90431b8a096af84ac058fbe044cdb8 100644
--- a/ROMFS/px4fmu_common/init.d/13002_firefly6
+++ b/ROMFS/px4fmu_common/init.d/13002_firefly6
@@ -33,7 +33,6 @@ then
 	param set MC_PITCHRATE_D 0.004
 	param set MC_PITCHRATE_FF 0.0
 	param set MC_YAW_P 4.0
-	param set MC_YAW_FF 0.5
 	param set MC_YAWRATE_P 0.22
 	param set MC_YAWRATE_I 0.02
 	param set MC_YAWRATE_D 0.0
diff --git a/ROMFS/px4fmu_common/init.d/13005_vtol_AAERT_quad b/ROMFS/px4fmu_common/init.d/13005_vtol_AAERT_quad
index cca99f49dc9b423da06bc75e5ee334874aa1d5ed..1fc37ebd04a0276b817bbe2036bb96864a51bc9b 100644
--- a/ROMFS/px4fmu_common/init.d/13005_vtol_AAERT_quad
+++ b/ROMFS/px4fmu_common/init.d/13005_vtol_AAERT_quad
@@ -39,7 +39,6 @@ then
 	param set MC_PITCHRATE_D 0.004
 	param set MC_PITCHRATE_FF 0.0
 	param set MC_YAW_P 2.8
-	param set MC_YAW_FF 0.5
 	param set MC_YAWRATE_P 0.22
 	param set MC_YAWRATE_I 0.02
 	param set MC_YAWRATE_D 0.0
diff --git a/ROMFS/px4fmu_common/init.d/13006_vtol_standard_delta b/ROMFS/px4fmu_common/init.d/13006_vtol_standard_delta
index 9d5c85a086a4a6feaba48324ec766120fd488eaa..26d138b54c8473eebb6b2c31490bc45dc0b714e3 100644
--- a/ROMFS/px4fmu_common/init.d/13006_vtol_standard_delta
+++ b/ROMFS/px4fmu_common/init.d/13006_vtol_standard_delta
@@ -35,7 +35,6 @@ then
 	param set MC_PITCHRATE_D 0.003
 	param set MC_PITCHRATE_FF 0.0
 	param set MC_YAW_P 3.5
-	param set MC_YAW_FF 0.5
 	param set MC_YAWRATE_P 0.2
 	param set MC_YAWRATE_I 0.1
 	param set MC_YAWRATE_D 0.0
diff --git a/ROMFS/px4fmu_common/init.d/13007_vtol_AAVVT_quad b/ROMFS/px4fmu_common/init.d/13007_vtol_AAVVT_quad
index 216dfd728d46cb4f01f8e5f1388990c58f093461..5efcf70fbcce30ce524a8721f4602e2c81c54654 100644
--- a/ROMFS/px4fmu_common/init.d/13007_vtol_AAVVT_quad
+++ b/ROMFS/px4fmu_common/init.d/13007_vtol_AAVVT_quad
@@ -27,7 +27,6 @@ then
 	param set MC_PITCHRATE_D 0.003
 	param set MC_PITCHRATE_FF 0.0
 	param set MC_YAW_P 2.8
-	param set MC_YAW_FF 0.5
 	param set MC_YAWRATE_P 0.22
 	param set MC_YAWRATE_I 0.02
 	param set MC_YAWRATE_D 0.0
diff --git a/ROMFS/px4fmu_common/init.d/13008_QuadRanger b/ROMFS/px4fmu_common/init.d/13008_QuadRanger
index c3fe1716b3cd9ffff13ec381922bd277448c6f56..23b2e5035878b30172f8ef74255cb7ef5710e1f0 100644
--- a/ROMFS/px4fmu_common/init.d/13008_QuadRanger
+++ b/ROMFS/px4fmu_common/init.d/13008_QuadRanger
@@ -30,7 +30,6 @@ then
 	param set MC_PITCHRATE_D 0.004
 	param set MC_PITCHRATE_FF 0.0
 	param set MC_YAW_P 3.5
-	param set MC_YAW_FF 0.7
 	param set MC_YAWRATE_P 0.6
 	param set MC_YAWRATE_I 0.04
 	param set MC_YAWRATE_D 0.0
diff --git a/ROMFS/px4fmu_common/init.d/13012_convergence b/ROMFS/px4fmu_common/init.d/13012_convergence
index 416ea45074c75c0a586fddffcc85d032986c1e18..9928af42e4ddadc7d2b4609644c28f6afbaba5cd 100644
--- a/ROMFS/px4fmu_common/init.d/13012_convergence
+++ b/ROMFS/px4fmu_common/init.d/13012_convergence
@@ -62,7 +62,6 @@ then
 	param set MC_ROLL_P   6.0
 	param set MC_YAWRATE_MAX  120
 	param set MC_YAWRATE_P    0.27
-	param set MC_YAW_FF   0.35
 	param set MC_YAW_P    2.5
 
 	param set MC_YAWRATE_P 0.3
diff --git a/ROMFS/px4fmu_common/init.d/13013_deltaquad b/ROMFS/px4fmu_common/init.d/13013_deltaquad
index 58c2eca715561e1203a586aec65ad4a78f30f8ed..01e49cefb88dd9d30fa6c5e1dc1b9fbc58e22efe 100644
--- a/ROMFS/px4fmu_common/init.d/13013_deltaquad
+++ b/ROMFS/px4fmu_common/init.d/13013_deltaquad
@@ -93,7 +93,6 @@ then
 	param set MC_PITCHRATE_FF 0.0
 	param set MC_PITCHRATE_MAX 80
 	param set MC_YAW_P 3.5
-	param set MC_YAW_FF 0.5
 	param set MC_YAWRATE_P 0.2
 	param set MC_YAWRATE_I 0.1
 	param set MC_YAWRATE_D 0.0
diff --git a/ROMFS/px4fmu_common/init.d/15001_coax_heli b/ROMFS/px4fmu_common/init.d/15001_coax_heli
index 853bc4823aaab0467934b91e70bfda1057222492..1e2db92f227264569ca79052082bbc9e9f82c132 100644
--- a/ROMFS/px4fmu_common/init.d/15001_coax_heli
+++ b/ROMFS/px4fmu_common/init.d/15001_coax_heli
@@ -37,7 +37,6 @@ then
 	param set MC_PITCHRATE_D 0.005
 	param set MC_PITCHRATE_FF 0
 	param set MC_YAW_P 2
-	param set MC_YAW_FF 0.5
 	param set MC_YAWRATE_P 0.1
 	param set MC_YAWRATE_I 0.1
 	param set MC_YAWRATE_D 0.0
diff --git a/ROMFS/px4fmu_common/init.d/16001_helicopter b/ROMFS/px4fmu_common/init.d/16001_helicopter
index a91a60fb5f5713dee24d898d72d34c38904dd209..a4e4d768b3355ee67b6a450017dd475d7656c768 100644
--- a/ROMFS/px4fmu_common/init.d/16001_helicopter
+++ b/ROMFS/px4fmu_common/init.d/16001_helicopter
@@ -39,7 +39,6 @@ then
 	param set MC_YAWRATE_P 0.1
 	param set MC_YAWRATE_I 0.0
 	param set MC_YAWRATE_D 0.0
-	param set MC_YAW_FF 0.0
 	param set MC_ROLLRATE_MAX 720.0
 	param set MC_PITCHRATE_MAX 720.0
 	param set MC_YAWRATE_MAX 400.0
diff --git a/ROMFS/px4fmu_common/init.d/4003_qavr5 b/ROMFS/px4fmu_common/init.d/4003_qavr5
index 4e5f64133263f15a597d71bd0bd57e4950333e13..932480278f112bbad4bd613c8b58ac7ae294c6c9 100644
--- a/ROMFS/px4fmu_common/init.d/4003_qavr5
+++ b/ROMFS/px4fmu_common/init.d/4003_qavr5
@@ -26,7 +26,6 @@ then
 	param set MC_YAWRATE_P 0.15
 	param set MC_YAWRATE_I 0.1
 	param set MC_YAWRATE_D 0.0
-	param set MC_YAW_FF 0.5
 	param set MC_TPA_BREAK_P 0.7
 	param set MC_TPA_RATE_P 0.3
 	param set PWM_MIN 1075
diff --git a/ROMFS/px4fmu_common/init.d/4009_qav250 b/ROMFS/px4fmu_common/init.d/4009_qav250
index dc92f5eb5afa728fab89b13a3aa966d7bf0f7ba8..6b4127da756da7a7ef31472a287e91bf5c02415b 100644
--- a/ROMFS/px4fmu_common/init.d/4009_qav250
+++ b/ROMFS/px4fmu_common/init.d/4009_qav250
@@ -24,7 +24,6 @@ then
 	param set MC_YAWRATE_P 0.3
 	param set MC_YAWRATE_I 0.2
 	param set MC_YAWRATE_D 0.0
-	param set MC_YAW_FF 0.5
 	param set PWM_MIN 1075
 	param set MPC_THR_MIN 0.06
 	param set MPC_MANTHR_MIN 0.06
diff --git a/ROMFS/px4fmu_common/init.d/4013_bebop b/ROMFS/px4fmu_common/init.d/4013_bebop
index 8b23184307c63b6b63385a587304c02afc950b8d..0459a45280aceafb67b5dd55db2759ed2fb5ab89 100644
--- a/ROMFS/px4fmu_common/init.d/4013_bebop
+++ b/ROMFS/px4fmu_common/init.d/4013_bebop
@@ -35,7 +35,6 @@ then
 	param set MC_YAWRATE_P 0.05
 	param set MC_YAWRATE_I 0.001
 	param set MC_YAWRATE_D 0.0
-	param set MC_YAW_FF 0.7
 fi
 
 set OUTPUT_MODE bebop
diff --git a/ROMFS/px4fmu_common/init.d/4050_generic_250 b/ROMFS/px4fmu_common/init.d/4050_generic_250
index 7c5af498a5cd8ec0b4339a147a59836a242f0e08..333ffbf37b8d9fd67301aa84d5d7b04b25e8e89d 100644
--- a/ROMFS/px4fmu_common/init.d/4050_generic_250
+++ b/ROMFS/px4fmu_common/init.d/4050_generic_250
@@ -24,7 +24,6 @@ then
 	param set MC_YAWRATE_P 0.2
 	param set MC_YAWRATE_I 0.1
 	param set MC_YAWRATE_D 0.0
-	param set MC_YAW_FF 0.5
 
 	param set MC_ROLLRATE_MAX 1600.0
 	param set MC_PITCHRATE_MAX 1600.0
diff --git a/ROMFS/px4fmu_common/init.d/4051_s250aq b/ROMFS/px4fmu_common/init.d/4051_s250aq
index 473c11e647d66ac38ea6c23de750d3503b580816..facc965fbc1e868de584fca89947cebbadf2317d 100644
--- a/ROMFS/px4fmu_common/init.d/4051_s250aq
+++ b/ROMFS/px4fmu_common/init.d/4051_s250aq
@@ -40,7 +40,6 @@ then
 	param set MC_YAWRATE_P 0.2
 	param set MC_YAWRATE_I 0.1
 	param set MC_YAWRATE_D 0.0
-	param set MC_YAW_FF 0.5
 	param set MC_ROLLRATE_MAX 720.0
 	param set MC_PITCHRATE_MAX 720.0
 	param set MC_YAWRATE_MAX 400.0
diff --git a/ROMFS/px4fmu_common/init.d/4070_aerofc b/ROMFS/px4fmu_common/init.d/4070_aerofc
index 0eb2d773ba1753a6909f11a23af5e26cb95243cf..506bd361fa49b15f1cd90d6065edddf1c525986a 100644
--- a/ROMFS/px4fmu_common/init.d/4070_aerofc
+++ b/ROMFS/px4fmu_common/init.d/4070_aerofc
@@ -41,7 +41,6 @@ then
 	param set MC_YAWRATE_P 0.119999997317790985
 	param set MC_YAWRATE_I 0.050000000745058060
 	param set MC_YAWRATE_D 0.0
-	param set MC_YAW_FF 0.5
 
 	param set MPC_LAND_SPEED 0.7000
 	param set MPC_MANTHR_MIN 0.0400
diff --git a/ROMFS/px4fmu_common/init.d/4080_zmr250 b/ROMFS/px4fmu_common/init.d/4080_zmr250
index 0c01e4f75b81558c8c5654faa16a289be44c7a94..e39a987796703562223e3657da27aedad38e6b9e 100644
--- a/ROMFS/px4fmu_common/init.d/4080_zmr250
+++ b/ROMFS/px4fmu_common/init.d/4080_zmr250
@@ -31,7 +31,6 @@ then
 	param set MC_YAWRATE_P 0.15
 	param set MC_YAWRATE_I 0.2
 	param set MC_YAWRATE_D 0.0
-	param set MC_YAW_FF 0.5
 
 	param set MC_ACRO_R_MAX 1000.0
 	param set MC_ACRO_P_MAX 1000.0
diff --git a/ROMFS/px4fmu_common/init.d/4090_nanomind b/ROMFS/px4fmu_common/init.d/4090_nanomind
index 0d16f79c5ba759b5347bd1e234532a733cfe6881..b629038eacbdebf6232d494a5ebfedb2c23bc1d9 100644
--- a/ROMFS/px4fmu_common/init.d/4090_nanomind
+++ b/ROMFS/px4fmu_common/init.d/4090_nanomind
@@ -31,7 +31,6 @@ then
 	param set MC_YAWRATE_P 0.2
 	param set MC_YAWRATE_I 0.1
 	param set MC_YAWRATE_D 0.0
-	param set MC_YAW_FF 0.5
 
 	param set BAT_N_CELLS 1
 
diff --git a/posix-configs/bebop/px4.config b/posix-configs/bebop/px4.config
index 5b35caf9e530b300d06ecd400108dd2e0b44bd83..9e20c39ad20effb0013db08c44f65f07c3467341 100644
--- a/posix-configs/bebop/px4.config
+++ b/posix-configs/bebop/px4.config
@@ -15,7 +15,6 @@ param set MPC_XY_VEL_MAX 2
 
 param set MC_YAW_P 4.0
 param set MC_YAWRATE_P 0.08
-param set MC_YAW_FF 0.5
 
 param set MC_ROLLRATE_P 0.08
 param set MC_ROLLRATE_D 0.001
diff --git a/src/modules/mc_att_control/mc_att_control.hpp b/src/modules/mc_att_control/mc_att_control.hpp
index 5f2f032b1fed75b97a7c8ae55b391d3db3ade4de..50a3b1b3aec8ec25894e6125075b2bb8c6ad1b3f 100644
--- a/src/modules/mc_att_control/mc_att_control.hpp
+++ b/src/modules/mc_att_control/mc_att_control.hpp
@@ -204,8 +204,6 @@ private:
 		(ParamFloat<px4::params::MC_YAWRATE_D>) _yaw_rate_d,
 		(ParamFloat<px4::params::MC_YAWRATE_FF>) _yaw_rate_ff,
 
-		(ParamFloat<px4::params::MC_YAW_FF>) _yaw_ff,					/**< yaw control feed-forward */
-
 		(ParamFloat<px4::params::MC_DTERM_CUTOFF>) _d_term_cutoff_freq,			/**< Cutoff frequency for the D-term filter */
 
 		(ParamFloat<px4::params::MC_TPA_BREAK_P>) _tpa_breakpoint_p,			/**< Throttle PID Attenuation breakpoint */
diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp
index 5626f96e021da807adef7b61566f1cbb212209ee..16479dbf83e69137115816aa844e17b0a7dc0a8c 100644
--- a/src/modules/mc_att_control/mc_att_control_main.cpp
+++ b/src/modules/mc_att_control/mc_att_control_main.cpp
@@ -430,16 +430,14 @@ MulticopterAttitudeControl::control_attitude(float dt)
 	_rates_sp = eq.emult(attitude_gain);
 
 	/* Feed forward the yaw setpoint rate.
-	 * The yaw_feedforward_rate is a commanded rotation around the world z-axis,
+	 * yaw_sp_move_rate is the feed forward commanded rotation around the world z-axis,
 	 * but we need to apply it in the body frame (because _rates_sp is expressed in the body frame).
 	 * Therefore we infer the world z-axis (expressed in the body frame) by taking the last column of R.transposed (== q.inversed)
-	 * and multiply it by the yaw setpoint rate (yaw_sp_move_rate) and gain (_yaw_ff).
+	 * and multiply it by the yaw setpoint rate (yaw_sp_move_rate).
 	 * This yields a vector representing the commanded rotatation around the world z-axis expressed in the body frame
 	 * such that it can be added to the rates setpoint.
 	 */
-	Vector3f yaw_feedforward_rate = q.inversed().dcm_z();
-	yaw_feedforward_rate *= _v_att_sp.yaw_sp_move_rate * _yaw_ff.get();
-	_rates_sp += yaw_feedforward_rate;
+	_rates_sp += q.inversed().dcm_z() * _v_att_sp.yaw_sp_move_rate;
 
 
 	/* limit rates */
diff --git a/src/modules/mc_att_control/mc_att_control_params.c b/src/modules/mc_att_control/mc_att_control_params.c
index a8182c7e988a5297ea9a0c3e807b9fa1a6129512..5da8bae0098b8c4b061d1e21226d59a80c7bf96e 100644
--- a/src/modules/mc_att_control/mc_att_control_params.c
+++ b/src/modules/mc_att_control/mc_att_control_params.c
@@ -263,19 +263,6 @@ PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f);
  */
 PARAM_DEFINE_FLOAT(MC_YAWRATE_FF, 0.0f);
 
-/**
- * Yaw feed forward
- *
- * Feed forward weight for manual yaw control. 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
- *
- * @min 0.0
- * @max 1.0
- * @decimal 2
- * @increment 0.01
- * @group Multicopter Attitude Control
- */
-PARAM_DEFINE_FLOAT(MC_YAW_FF, 0.5f);
-
 /**
  * Max roll rate
  *