diff --git a/src/lib/CollisionPrevention/CollisionPrevention.cpp b/src/lib/CollisionPrevention/CollisionPrevention.cpp
index 38e49a41a10a3ca561502cec37bc0da5616bca3d..98cf2ec2f871f9e37ce3dfd954ba936e1864160c 100644
--- a/src/lib/CollisionPrevention/CollisionPrevention.cpp
+++ b/src/lib/CollisionPrevention/CollisionPrevention.cpp
@@ -106,18 +106,6 @@ void CollisionPrevention::publish_constraints(const Vector2f &original_setpoint,
 	} else {
 		_constraints_pub = orb_advertise(ORB_ID(collision_constraints), &constraints);
 	}
-
-}
-
-void CollisionPrevention::update()
-{
-	// activate/deactivate the collision prevention based on MPC_COL_PREV parameter
-	if (collision_prevention_enabled()) {
-		activate();
-
-	} else {
-		deactivate();
-	}
 }
 
 void CollisionPrevention::update_range_constraints()
@@ -155,7 +143,6 @@ void CollisionPrevention::update_range_constraints()
 
 void CollisionPrevention::modifySetpoint(Vector2f &original_setpoint, const float max_speed)
 {
-	update();
 	reset_constraints();
 
 	//calculate movement constraints based on range data
diff --git a/src/lib/CollisionPrevention/CollisionPrevention.hpp b/src/lib/CollisionPrevention/CollisionPrevention.hpp
index ec82401bd9545878bc37b4a8a7174f95e63032c6..11561c3bb502c5f2713ba0fa3489603328d7c144 100644
--- a/src/lib/CollisionPrevention/CollisionPrevention.hpp
+++ b/src/lib/CollisionPrevention/CollisionPrevention.hpp
@@ -71,13 +71,7 @@ public:
 	 */
 	bool initializeSubscriptions(SubscriptionArray &subscription_array);
 
-	void activate() {_is_active = true;}
-
-	void deactivate() {_is_active = false;}
-
-	bool is_active() {return _is_active;}
-
-	bool collision_prevention_enabled() { return MPC_COL_PREV.get(); }
+	bool is_active() {return MPC_COL_PREV.get();}
 
 	void update();
 
diff --git a/src/lib/CollisionPrevention/collisionprevention_params.c b/src/lib/CollisionPrevention/collisionprevention_params.c
new file mode 100644
index 0000000000000000000000000000000000000000..a518571f39275a6366fad3c04d8d1d59661390b7
--- /dev/null
+++ b/src/lib/CollisionPrevention/collisionprevention_params.c
@@ -0,0 +1,60 @@
+/****************************************************************************
+ *
+ *   Copyright (c) 2018 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file collisionprevention_params.c
+ *
+ * Parameters defined by the collisionprevention lib.
+ *
+ * @author Tanja Baumann <tanja@auterion.com>
+ */
+
+/**
+ * Flag to enable the use of a MAVLink range sensor for collision avoidance.
+ *
+ * @boolean
+ * @group Multicopter Position Control
+ */
+PARAM_DEFINE_INT32(MPC_COL_PREV, 0);
+
+/**
+ * Minimum distance the vehicle should keep to all obstacles
+ *
+ * Only used in Position mode when collision avoidance is active (see MPC_COL_AVOID).
+ *
+ * @min 0
+ * @max 15
+ * @unit meters
+ * @group Multicopter Position Control
+ */
+PARAM_DEFINE_FLOAT(MPC_COL_PREV_D, 4.0f);
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 f418ac540383581c293c868e0a1e5035ee411ab5..f86eb782061c5c60e82cef2ea1d0b498a57ab458 100644
--- a/src/modules/mc_pos_control/mc_pos_control_params.c
+++ b/src/modules/mc_pos_control/mc_pos_control_params.c
@@ -738,22 +738,3 @@ PARAM_DEFINE_INT32(MPC_OBS_AVOID, 0);
  */
 PARAM_DEFINE_INT32(MPC_YAW_MODE, 0);
 
-/**
- * Flag to enable the use of a MAVLink range sensor for collision avoidance.
- *
- * @boolean
- * @group Multicopter Position Control
- */
-PARAM_DEFINE_INT32(MPC_COL_PREV, 0);
-
-/**
- * Minimum distance the vehicle should keep to all obstacles
- *
- * Only used in Position mode when collision avoidance is active (see MPC_COL_AVOID).
- *
- * @min 0
- * @max 15
- * @unit meters
- * @group Multicopter Position Control
- */
-PARAM_DEFINE_FLOAT(MPC_COL_PREV_D, 4.0f);