diff --git a/boards/stm/32f4discovery/default.cmake b/boards/stm/32f4discovery/default.cmake
index 28c213bd6429d444cf779daf773b39833cdb95ac..46c950680c8d7fa96cb4d0792e4ffd0ffa8a15f0 100644
--- a/boards/stm/32f4discovery/default.cmake
+++ b/boards/stm/32f4discovery/default.cmake
@@ -55,8 +55,8 @@ px4_add_board(
 		logger
 		mavlink
 		#mc_att_control
-		mc_pos_control
-		navigator
+		#mc_pos_control
+		#navigator
 		position_estimator_inav
 		#sensors
 		#vmount
diff --git a/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.cpp b/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.cpp
index 96a2204e0e41006c1d02c0a60e3c3485c41b3997..c669bd71025b597296e4d404cc2f43563ed54a94 100644
--- a/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.cpp
+++ b/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.cpp
@@ -227,7 +227,7 @@ bool FlightTaskAuto::_evaluateTriplets()
 		_mission_gear = _sub_triplet_setpoint->get().current.landing_gear;
 	}
 
-	if (MPC_OBS_AVOID.get() && _sub_vehicle_status->get().is_rotary_wing) {
+	if (COM_OBS_AVOID.get() && _sub_vehicle_status->get().is_rotary_wing) {
 		_checkAvoidanceProgress();
 	}
 
diff --git a/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.hpp b/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.hpp
index 7521acc2c0cb735300100b824384b465024983b0..cb1eeb3b242c1e6fe7d6f46b6c3ccee4b6ea360f 100644
--- a/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.hpp
+++ b/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.hpp
@@ -109,7 +109,7 @@ protected:
 					(ParamFloat<px4::params::MPC_CRUISE_90>) MPC_CRUISE_90, // speed at corner when angle is 90 degrees move to line
 					(ParamFloat<px4::params::NAV_MC_ALT_RAD>) NAV_MC_ALT_RAD, //vertical acceptance radius at which waypoints are updated
 					(ParamInt<px4::params::MPC_YAW_MODE>) MPC_YAW_MODE, // defines how heading is executed,
-					(ParamInt<px4::params::MPC_OBS_AVOID>) MPC_OBS_AVOID // obstacle avoidance active
+					(ParamInt<px4::params::COM_OBS_AVOID>) COM_OBS_AVOID // obstacle avoidance active
 				       );
 
 private:
diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp
index 345f739d06f2bc765400e7d9d05e2b811814cc20..6d52e1ccf67946543350a16b2ca587283f6793c8 100644
--- a/src/modules/commander/Commander.hpp
+++ b/src/modules/commander/Commander.hpp
@@ -118,7 +118,7 @@ private:
 		(ParamInt<px4::params::COM_LOW_BAT_ACT>) _low_bat_action,
 		(ParamFloat<px4::params::COM_DISARM_LAND>) _disarm_when_landed_timeout,
 
-		(ParamInt<px4::params::MPC_OBS_AVOID>) _obs_avoid
+		(ParamInt<px4::params::COM_OBS_AVOID>) _obs_avoid
 	)
 
 	const int64_t POSVEL_PROBATION_MIN = 1_s;	/**< minimum probation duration (usec) */
diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c
index cda46920ba2252afec8bd62ac4aa34dcd8ca1f54..14eb645e0b224478cb9e43f49ebd2e6eb04e5870 100644
--- a/src/modules/commander/commander_params.c
+++ b/src/modules/commander/commander_params.c
@@ -811,3 +811,12 @@ PARAM_DEFINE_INT32(NAV_DLL_ACT, 0);
  * @group Mission
  */
 PARAM_DEFINE_INT32(NAV_RCL_ACT, 2);
+
+/**
+ * Flag to enable obstacle avoidance
+ * Temporary Parameter to enable interface testing
+ *
+ * @boolean
+ * @group Mission
+ */
+PARAM_DEFINE_INT32(COM_OBS_AVOID, 0);
diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp
index 62941487293a823efce1b2917b2d37332bdbe7c6..74417afc5b572d06be23b927c1c0ec5d23778779 100644
--- a/src/modules/mc_pos_control/mc_pos_control_main.cpp
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -160,7 +160,7 @@ private:
 		(ParamInt<px4::params::MPC_AUTO_MODE>) MPC_AUTO_MODE,
 		(ParamInt<px4::params::MPC_ALT_MODE>) MPC_ALT_MODE,
 		(ParamFloat<px4::params::MPC_SPOOLUP_TIME>) MPC_SPOOLUP_TIME, /**< time to let motors spool up after arming */
-		(ParamInt<px4::params::MPC_OBS_AVOID>) MPC_OBS_AVOID, /**< enable obstacle avoidance */
+		(ParamInt<px4::params::COM_OBS_AVOID>) COM_OBS_AVOID, /**< enable obstacle avoidance */
 		(ParamFloat<px4::params::MPC_TILTMAX_LND>) MPC_TILTMAX_LND /**< maximum tilt for landing and smooth takeoff */
 	);
 
@@ -1141,7 +1141,7 @@ void
 MulticopterPositionControl::update_avoidance_waypoint_desired(PositionControlStates &states,
 		vehicle_local_position_setpoint_s &setpoint)
 {
-	if (MPC_OBS_AVOID.get()) {
+	if (COM_OBS_AVOID.get()) {
 		_traj_wp_avoidance_desired = _flight_tasks.getAvoidanceWaypoint();
 		_traj_wp_avoidance_desired.timestamp = hrt_absolute_time();
 		_traj_wp_avoidance_desired.type = vehicle_trajectory_waypoint_s::MAV_TRAJECTORY_REPRESENTATION_WAYPOINTS;
@@ -1193,7 +1193,7 @@ MulticopterPositionControl::reset_setpoint_to_nan(vehicle_local_position_setpoin
 bool
 MulticopterPositionControl::use_obstacle_avoidance()
 {
-	if (MPC_OBS_AVOID.get()) {
+	if (COM_OBS_AVOID.get()) {
 		const bool avoidance_data_timeout = hrt_elapsed_time((hrt_abstime *)&_traj_wp_avoidance.timestamp) > TRAJECTORY_STREAM_TIMEOUT_US;
 		const bool avoidance_point_valid = _traj_wp_avoidance.waypoints[vehicle_trajectory_waypoint_s::POINT_0].point_valid == true;
 		const bool in_mission = _vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION;
diff --git a/src/modules/mc_pos_control/mc_pos_control_params.c b/src/modules/mc_pos_control/mc_pos_control_params.c
index 2d5b80a410c2a54c7db4df5ca73e839d24948cef..f357304e46d9105759d845af67418eeb38a5145d 100644
--- a/src/modules/mc_pos_control/mc_pos_control_params.c
+++ b/src/modules/mc_pos_control/mc_pos_control_params.c
@@ -705,16 +705,7 @@ PARAM_DEFINE_INT32(MPC_AUTO_MODE, 1);
 PARAM_DEFINE_FLOAT(MPC_SPOOLUP_TIME, 0.0f);
 
 /**
- * Flag to enable obstacle avoidance
- * Temporary Parameter to enable interface testing
- *
- * @boolean
- * @group Multicopter Position Control
- */
-PARAM_DEFINE_INT32(MPC_OBS_AVOID, 0);
-
-/**
- * Yaw mode
+ * Yaw mode.
  *
  * Specifies the heading in Auto.
  *
@@ -727,4 +718,3 @@ PARAM_DEFINE_INT32(MPC_OBS_AVOID, 0);
  * @group Mission
  */
 PARAM_DEFINE_INT32(MPC_YAW_MODE, 0);
-