diff --git a/CMakeLists.txt b/CMakeLists.txt
index 2780764e8082e36b350bd1c3985e1ce1e5034f5b..f4f4048577a4a8bfc892f305585be5848a72999d 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -46,11 +46,6 @@ LQHeadToPointData.msg
 LQPtuCommandData.msg
 LQPositionData.msg
 MPFlyingInfo.msg
-MPParams.msg
-MPRefinements.msg
-MPRoadmap.msg
-MPZone.msg
-MPForbiddenZone.msg
 OMPLInfo.msg
 PlatformParams.msg
 PMAVInfo.msg
@@ -63,12 +58,10 @@ RelayProblemSpec.msg
 Sticks.msg
 SticksValue.msg
 TDWNodeVisibilityInfo.msg
-ThreeDObject.msg
 VelExtData.msg
 VisDelete.msg
 VisFrustrum.msg
 VisTrackBallHome.msg
-MPOBBObject.msg
 PlatformHeartbeat.msg
 # ConfirmRequest.msg
 #   Message1.msg
diff --git a/msg/MPForbiddenZone.msg b/msg/MPForbiddenZone.msg
deleted file mode 100644
index 26523fc0f2c303aacfaa35856c54727bebc29431..0000000000000000000000000000000000000000
--- a/msg/MPForbiddenZone.msg
+++ /dev/null
@@ -1,2 +0,0 @@
-uint64 zone_id
-lrs_msgs/MPZone zone
\ No newline at end of file
diff --git a/msg/MPOBBObject.msg b/msg/MPOBBObject.msg
deleted file mode 100644
index fa5018d74cf23a4713c995d9fa2d2eefd75c2955..0000000000000000000000000000000000000000
--- a/msg/MPOBBObject.msg
+++ /dev/null
@@ -1,3 +0,0 @@
-ThreeDObject[] objects
-int32 level
-bool first
\ No newline at end of file
diff --git a/msg/MPParams.msg b/msg/MPParams.msg
deleted file mode 100644
index 409ca1b7a1123dce3631d6739a7ca69f541bc0cc..0000000000000000000000000000000000000000
--- a/msg/MPParams.msg
+++ /dev/null
@@ -1,36 +0,0 @@
-#
-# Used for parameters to the Motion Planner
-#
-
-int32 BASIC_PRM = 1
-int32 REPARATION_PRM = 2
-int32 RRT_CONNECT = 3
-int32 RRT_STAR = 4
-int32 OMPL_RRT = 5
-int32 OMPL_RRT_CONNECT = 6
-int32 OMPL_RRT_LAZY = 7
-int32 OMPL_RRT_STAR = 8
-int32 OMPL_PRM = 9
-int32 OMPL_PRM_STAR = 10
-int32 OMPL_PRM_LAZY = 11
-int32 OMPL_PRM_LAZY_STAR = 12
-int32 type                           # see above for values
-
-int32 POLYNOMIAL_CURVE_DEG_1 = 1
-int32 POLYNOMIAL_CURVE_DEG_3 = 2
-int32 curve_type                     # see above for values
-
-string datadir                       # Directory for the objects in the world file
-string worldfile
-bool buildroadmap                    # if true build the roadmap, otherwise build it if needed
-int32 roadmapnodes                   # Number of nodes in the roadmap
-int32 obb_tree_objects_max_depth
-int32 obb_tree_ground_max_depth
-float64 xmin                         # Specified the bounding box
-float64 xmax
-float64 ymin
-float64 ymax
-float64 zmin
-float64 zmax
-float64 margin                       # Safety margin
-
diff --git a/msg/MPRefinements.msg b/msg/MPRefinements.msg
deleted file mode 100644
index f9aab28c0d54c47ef779bd0a0d4e366c2c47eb7c..0000000000000000000000000000000000000000
--- a/msg/MPRefinements.msg
+++ /dev/null
@@ -1,9 +0,0 @@
-int32 GREEDY_NODE_REMOVAL=0
-int32 NODE_ALIGNMENT_HALF=1
-int32 NODE_ALIGNMENT_FULL=2
-int32 NODE_ALIGNMENT_HEIGHT=3
-int32 NODE_VELOCITIES_WITAS=4
-int32 SPLINE_INTERPOLATION=5
-
-int32[] ref
-float64[] args
diff --git a/msg/MPRoadmap.msg b/msg/MPRoadmap.msg
deleted file mode 100644
index 45c91d2387c49e5a0f849911451e8323ad7e9357..0000000000000000000000000000000000000000
--- a/msg/MPRoadmap.msg
+++ /dev/null
@@ -1,3 +0,0 @@
-geometry_msgs/Point[] p0
-geometry_msgs/Point[] p1
-
diff --git a/msg/MPZone.msg b/msg/MPZone.msg
deleted file mode 100644
index 1d949778987d7a09f27914a4dad413a4d5748517..0000000000000000000000000000000000000000
--- a/msg/MPZone.msg
+++ /dev/null
@@ -1,2 +0,0 @@
-string tag
-geometry_msgs/Point[] corners
\ No newline at end of file
diff --git a/msg/ThreeDObject.msg b/msg/ThreeDObject.msg
deleted file mode 100644
index d8744daa46b9f3089bf09761f063cc71573df800..0000000000000000000000000000000000000000
--- a/msg/ThreeDObject.msg
+++ /dev/null
@@ -1,2 +0,0 @@
-geometry_msgs/PoseStamped[] vertices
-int32[]			    faces
\ No newline at end of file