diff --git a/CMakeLists.txt b/CMakeLists.txt
index a2a0c55e2aba5fd80e9f8e94f2429ef1c779e1f6..58853a9df189090e46cd59f8ddd1956db6df7e55 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -161,10 +161,10 @@ include_directories(
 ## Mark executable scripts (Python etc.) for installation
 ## in contrast to setup.py, you can choose the destination
 catkin_install_python(PROGRAMS
-   nodes/watchdog
    nodes/monitor_distance
-   nodes/monitor_test2
-   nodes/monitor_test1
+   nodes/monitor_test_1
+   nodes/monitor_test_2
+   nodes/monitor_test_3
    DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
 )
 
diff --git a/launch/monitor_distance.launch b/launch/monitor_distance.launch
new file mode 100644
index 0000000000000000000000000000000000000000..8824fb3b5c1199c3e4d1772d812c04db8c8fab22
--- /dev/null
+++ b/launch/monitor_distance.launch
@@ -0,0 +1,3 @@
+<launch>
+    <node pkg="monitoring" type="monitor_distance" name="monitor_distance" />
+</launch>
\ No newline at end of file
diff --git a/launch/system.launch b/launch/monitoring.launch
similarity index 76%
rename from launch/system.launch
rename to launch/monitoring.launch
index 57a9763b36b5b7c3d7aaf1856cdd6e04269d945d..05491baa777fdbc218c310649e7ea4dffca1261d 100644
--- a/launch/system.launch
+++ b/launch/monitoring.launch
@@ -1,9 +1,11 @@
 <launch>
+    <!--
+    <include file="$(find monitoring)/launch/translator.launch" />
+    -->
 
+    <include file="$(find monitoring)/launch/monitor_distance.launch" />
 
     <include file="$(find monitoring)/launch/monitor_test_1.launch" />
     <include file="$(find monitoring)/launch/monitor_test_2.launch" />
     <include file="$(find monitoring)/launch/monitor_test_3.launch" />
-    <include file="$(find monitoring)/launch/translator.launch" />
-    <include file="$(find monitoring)/launch/watchdog.launch" />
 </launch>
\ No newline at end of file
diff --git a/launch/watchdog.launch b/launch/watchdog.launch
deleted file mode 100644
index f42b74d7f87b9ffc5ad96688630d3a0f369cf9f6..0000000000000000000000000000000000000000
--- a/launch/watchdog.launch
+++ /dev/null
@@ -1,14 +0,0 @@
-<launch>
-    <node pkg="monitoring" type="watchdog" name="watchdog">
-        <!-- example of how to set an aggregation strategy for a metric -->
-        <rosparam param="aggregation_strategy_metrics">
-            example_1: 10
-            example_2: 10
-            test_domain_1: 1
-            test_domain_2: 2
-        </rosparam>
-        <!-- set the default aggregation strategy for domains -->
-        <param name="aggregation_strategy_domains" value="1" type="int" />
-        <param name="wdg_freq" value="2.0" type="double" />
-    </node>
-</launch>
\ No newline at end of file
diff --git a/nodes/monitor_distance b/nodes/monitor_distance
index 31d25f7ecb22058573f72663a9dda2122e6e780b..deeb3016f9700c0d708665e4445306e1df7895e9 100755
--- a/nodes/monitor_distance
+++ b/nodes/monitor_distance
@@ -1,6 +1,7 @@
 #!/usr/bin/env python
 
 import rospy
+
 from sensor_msgs.msg import LaserScan
 from monitoring.monitor import Monitor
 
@@ -16,6 +17,7 @@ if __name__ == '__main__':
         rospy.init_node("monitor_distance")
 
         monitor = Monitor()
+        distance = float("inf")
 
         rate = rospy.Rate(10)
         while not rospy.is_shutdown():
diff --git a/nodes/watchdog b/nodes/watchdog
deleted file mode 100755
index c30f22c877ab9b400dbb7a2520b682e0d4590074..0000000000000000000000000000000000000000
--- a/nodes/watchdog
+++ /dev/null
@@ -1,13 +0,0 @@
-#!/usr/bin/env python
-
-import rospy
-from monitoring.watchdog import Watchdog
-
-
-if __name__ == '__main__':
-    try:
-        rospy.init_node("watchdog")
-        watchdog = Watchdog()
-        rospy.spin()
-    except rospy.ROSInterruptException:
-        pass
diff --git a/src/monitoring/watchdog.py b/src/monitoring/watchdog.py
deleted file mode 100755
index 31250ae3e1c7ed055d3ac8d03f849a8e08aa3fbb..0000000000000000000000000000000000000000
--- a/src/monitoring/watchdog.py
+++ /dev/null
@@ -1,142 +0,0 @@
-#!/usr/bin/env python
-
-import rospy
-
-from monitoring.msg import Monitoring
-
-
-class Watchdog:
-    def __init__(self):
-        self.sub = rospy.Subscriber("/monitoring", Monitoring, self.update_log)
-
-        # Stores the most current values of each metric.
-        self.log = {}
-
-        # Strategies that specify how the critical level of each metric should be aggregated in a domain.
-        # It is possible to specify a different aggregation strategy for every single domain.
-        self.aggregation_strategy_metrics = rospy.get_param("/watchdog/aggregation_strategy_metrics")
-        # Dictionary that stores the aggregated critical levels of the metrics of a domain.
-        self.aggregated_metrics = {}
-
-        # Strategy that specifies how the critical levels of all domains should be aggregated.
-        self.aggregation_strategy_domains = rospy.get_param("/watchdog/aggregation_strategy_domains")
-        # Variable that stores the aggregated critical level of all domains.
-        self.aggregated_domains = None
-
-        # Frequency at which the metrics in the log are aggregated.
-        wdg_freq = rospy.get_param("/watchdog/wdg_freq", 1.0)
-
-        if not wdg_freq > 0.0:
-            rospy.logwarn(
-                "Watchdog: The frequency at which the metrics of the robot are aggregated must be greater then 0! "
-                "Using 1 as frequency!")
-            wdg_freq = 1.0
-
-        self.timer = rospy.Timer(rospy.Duration(1.0 / wdg_freq), self.update_condition)
-
-    # TODO: Think about efficiency!
-    def update_log(self, monitoring):
-        origin = monitoring.origin
-        metric = monitoring.metric
-
-        domain = metric.domain
-        label = metric.label
-        value = metric.value
-        unit = metric.unit
-        error = metric.error
-
-        if domain in self.log:
-            if origin in self.log[domain]:
-                self.log[domain][origin].update({label: {"value": value, "unit": unit, "error": error}})
-            else:
-                self.log[domain][origin] = {}
-                self.log[domain][origin][label] = {"value": value, "unit": unit, "error": error}
-        else:
-            self.log[domain] = {}
-            self.log[domain][origin] = {}
-            self.log[domain][origin][label] = {"value": value, "unit": unit, "error": error}
-
-    def update_condition(self, event):
-        self.aggregate_metrics()
-        self.aggregate_domains()
-
-    # TODO: Add more modes!
-    def aggregate_metrics(self):
-        for domain in self.log:
-            if domain in self.aggregation_strategy_metrics:
-
-                # Strategy 1: Take the highest error level of any metric in a domain.
-                if self.aggregation_strategy_metrics[domain] == 1:
-                    highest_error = 0.0
-
-                    for origin in self.log[domain]:
-                        for label in self.log[domain][origin]:
-                            local_error = self.log[domain][origin][label]["error"]
-                            if local_error > highest_error:
-                                highest_error = local_error
-
-                    self.aggregated_metrics.update({domain: highest_error})
-
-                # Strategy 2: Take the lowest error level of any metric in a domain.
-                elif self.aggregation_strategy_metrics[domain] == 2:
-                    lowest_error = 1.0
-
-                    for origin in self.log[domain]:
-                        for label in self.log[domain][origin]:
-                            local_error = self.log[domain][origin][label]["error"]
-                            if local_error < lowest_error:
-                                lowest_error = local_error
-
-                    self.aggregated_metrics.update({domain: lowest_error})
-
-                else:
-                    rospy.logwarn("Watchdog: The specified method for aggregating metrics is not recognised!")
-
-            # Default strategy: Take the average error level of every metric in a domain.
-            else:
-                count = 0.001
-                aggregated_error = 0.0
-
-                for origin in self.log[domain]:
-                    for label in self.log[domain][origin]:
-                        count = count + 1
-                        aggregated_error = aggregated_error + self.log[domain][origin][label]["error"]
-
-                quotient = aggregated_error / count
-                self.aggregated_metrics.update({domain: quotient})
-
-    # TODO: Add more modes!
-    def aggregate_domains(self):
-        # Strategy 1: Take the highest error level of any domain.
-        if self.aggregation_strategy_domains == 1:
-            highest_error = 0.0
-
-            for domain in self.aggregated_metrics:
-                local_error = self.aggregated_metrics[domain]
-                if local_error > highest_error:
-                    highest_error = local_error
-
-            self.aggregated_domains = highest_error
-
-        # Strategy 2: Take the lowes error level of any domain.
-        elif self.aggregation_strategy_domains == 2:
-            lowest_error = 1.0
-
-            for domain in self.aggregated_metrics:
-                local_error = self.aggregated_metrics[domain]
-                if local_error < lowest_error:
-                    lowest_error = local_error
-
-            self.aggregated_domains = lowest_error
-
-        # Default strategy: Take the average error level of every domain.
-        else:
-            count = 0.001
-            aggregated_error = 0.0
-
-            for domain in self.aggregated_metrics:
-                count = count + 1
-                aggregated_error = aggregated_error + self.aggregated_metrics[domain]
-
-            quotient = aggregated_error / count
-            self.aggregated_domains = quotient