diff --git a/CMakeLists.txt b/CMakeLists.txt
index 550792c606679c44da9739081a78646c13b718c2..a2a0c55e2aba5fd80e9f8e94f2429ef1c779e1f6 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -51,8 +51,6 @@ add_message_files(
    FILES
    Monitoring.msg
    Metric.msg
-   States.msg
-   State.msg
 )
 
 ## Generate services in the 'srv' folder
@@ -166,7 +164,7 @@ catkin_install_python(PROGRAMS
    nodes/watchdog
    nodes/monitor_distance
    nodes/monitor_test2
-   nodes/monitor_test
+   nodes/monitor_test1
    DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
 )
 
diff --git a/launch/monitor_test.launch b/launch/monitor_test.launch
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/launch/monitor_test_1.launch b/launch/monitor_test_1.launch
new file mode 100644
index 0000000000000000000000000000000000000000..87792fbb135ccc9b09ecd40d55c686889633d2e7
--- /dev/null
+++ b/launch/monitor_test_1.launch
@@ -0,0 +1,3 @@
+<launch>
+    <node pkg="monitoring" type="monitor_test_1" name="monitor_test_1" />
+</launch>
\ No newline at end of file
diff --git a/launch/monitor_test_2.launch b/launch/monitor_test_2.launch
new file mode 100644
index 0000000000000000000000000000000000000000..0ad14251b87eb9fabcc114e3868e1716f1503027
--- /dev/null
+++ b/launch/monitor_test_2.launch
@@ -0,0 +1,3 @@
+<launch>
+    <node pkg="monitoring" type="monitor_test_2" name="monitor_test_2" />
+</launch>
\ No newline at end of file
diff --git a/launch/monitor_test_3.launch b/launch/monitor_test_3.launch
new file mode 100644
index 0000000000000000000000000000000000000000..a1f9d522cbcb69e92a72c6e52e250861770e4b81
--- /dev/null
+++ b/launch/monitor_test_3.launch
@@ -0,0 +1,3 @@
+<launch>
+    <node pkg="monitoring" type="monitor_test_3" name="monitor_test_3" />
+</launch>
\ No newline at end of file
diff --git a/launch/system.launch b/launch/system.launch
new file mode 100644
index 0000000000000000000000000000000000000000..57a9763b36b5b7c3d7aaf1856cdd6e04269d945d
--- /dev/null
+++ b/launch/system.launch
@@ -0,0 +1,9 @@
+<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/translator.launch b/launch/translator.launch
new file mode 100644
index 0000000000000000000000000000000000000000..578711ac339ed360d86abdb3098f01aeb3ef4eba
--- /dev/null
+++ b/launch/translator.launch
@@ -0,0 +1,3 @@
+<launch>
+    <node pkg="monitoring" type="translator" name="translator" />
+</launch>
\ No newline at end of file
diff --git a/launch/watchdog.launch b/launch/watchdog.launch
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..f42b74d7f87b9ffc5ad96688630d3a0f369cf9f6 100644
--- a/launch/watchdog.launch
+++ b/launch/watchdog.launch
@@ -0,0 +1,14 @@
+<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.py b/nodes/monitor_distance
similarity index 97%
rename from nodes/monitor_distance.py
rename to nodes/monitor_distance
index 63e2da420ad58fc38b49b1e70f315b383b231a34..31d25f7ecb22058573f72663a9dda2122e6e780b 100755
--- a/nodes/monitor_distance.py
+++ b/nodes/monitor_distance
@@ -1,4 +1,4 @@
-#!/usr/bin/env pyhton
+#!/usr/bin/env python
 
 import rospy
 from sensor_msgs.msg import LaserScan
diff --git a/nodes/monitor_test b/nodes/monitor_test_1
similarity index 56%
rename from nodes/monitor_test
rename to nodes/monitor_test_1
index 50119dd5c1fa36ab26436ebfea22b84d6af0ca20..764389552688b16d88a23cbe0d37197a29308c86 100755
--- a/nodes/monitor_test
+++ b/nodes/monitor_test_1
@@ -4,18 +4,18 @@ import rospy
 from monitoring.monitor import Monitor
 
 
-def monitor_test():
-    rospy.init_node("monitor_test")
-    monitor = Monitor(1, 1)
+def monitor_test_1():
+    rospy.init_node("monitor_test_1")
+    monitor = Monitor(1, 1.0)
 
     rate = rospy.Rate(10)
     while not rospy.is_shutdown():
-        monitor.update_metric("family", "label1", 10, "unit", 0.5)
+        monitor.update_metric("test_domain_1", "test_label_1", 10, "unit", 0.5)
         rate.sleep()
 
 
 if __name__ == '__main__':
     try:
-        monitor_test()
+        monitor_test_1()
     except rospy.ROSInterruptException:
         pass
diff --git a/nodes/monitor_test2 b/nodes/monitor_test_2
similarity index 63%
rename from nodes/monitor_test2
rename to nodes/monitor_test_2
index 663b1975c281c663a7db91fa7132a1d06a606902..aea6a3a5d054441d953ebd529b07d3ec81735cca 100755
--- a/nodes/monitor_test2
+++ b/nodes/monitor_test_2
@@ -4,14 +4,14 @@ import rospy
 from monitoring.monitor import Monitor
 
 
-def monitor_test():
-    rospy.init_node("monitor_test2")
-    monitor = Monitor(1, 1)
+def monitor_test_2():
+    rospy.init_node("monitor_test_2")
+    monitor = Monitor(1, 1.0)
 
     rate = rospy.Rate(10)
     value = 0
     while not rospy.is_shutdown():
-        monitor.update_metric("family", "label2", 10, "unit", value)
+        monitor.update_metric("test_domain_1", "test_label_2", 10, "unit", value)
         value = value + 0.1
         if value > 1.0:
             value = 0
@@ -20,6 +20,6 @@ def monitor_test():
 
 if __name__ == '__main__':
     try:
-        monitor_test()
+        monitor_test_2()
     except rospy.ROSInterruptException:
         pass
diff --git a/nodes/monitor_test_3 b/nodes/monitor_test_3
new file mode 100755
index 0000000000000000000000000000000000000000..f24cb767fbde865afee2036f8c23b2861e8aae38
--- /dev/null
+++ b/nodes/monitor_test_3
@@ -0,0 +1,21 @@
+#!/usr/bin/env python
+
+import rospy
+from monitoring.monitor import Monitor
+
+
+def monitor_test_3():
+    rospy.init_node("monitor_test_3")
+    monitor = Monitor(1, 1.0)
+
+    rate = rospy.Rate(10)
+    while not rospy.is_shutdown():
+        monitor.update_metric("test_domain_2", "test_label_3", 10, "unit", 1.0)
+        rate.sleep()
+
+
+if __name__ == '__main__':
+    try:
+        monitor_test_3()
+    except rospy.ROSInterruptException:
+        pass
diff --git a/nodes/translator b/nodes/translator
new file mode 100755
index 0000000000000000000000000000000000000000..04f9899c9e5d2c658dc142eb3009e166d57c3b3a
--- /dev/null
+++ b/nodes/translator
@@ -0,0 +1,14 @@
+#!/usr/bin/env python
+
+import rospy
+
+from monitoring.translator import Translator
+
+
+if __name__ == '__main__':
+    try:
+        rospy.init_node("translator")
+        Translator()
+        rospy.spin()
+    except rospy.ROSInterruptException:
+        pass
diff --git a/nodes/watchdog b/nodes/watchdog
index dc202143e59e3eaad87ea80eaaae29391820fd28..c30f22c877ab9b400dbb7a2520b682e0d4590074 100755
--- a/nodes/watchdog
+++ b/nodes/watchdog
@@ -4,17 +4,10 @@ import rospy
 from monitoring.watchdog import Watchdog
 
 
-def watchdog():
-    rospy.init_node("watchdog")
-    watching = Watchdog(1, 1.0)
-
-    rate = rospy.Rate(10)
-    while not rospy.is_shutdown():
-        rate.sleep()
-
-
 if __name__ == '__main__':
     try:
-        watchdog()
+        rospy.init_node("watchdog")
+        watchdog = Watchdog()
+        rospy.spin()
     except rospy.ROSInterruptException:
         pass
diff --git a/src/monitoring/monitor.py b/src/monitoring/monitor.py
index 5d4f21688ef88746af8fbacc85d25ad963281325..e6f71214e245052fa997280fdcff76c28842ee01 100755
--- a/src/monitoring/monitor.py
+++ b/src/monitoring/monitor.py
@@ -23,7 +23,7 @@ class Monitor:
     """
     def __init__(self, mon_mode=1, mon_freq=1.0):
         self.log = {}  # Logging dictionary. Is used to accomplish different publishing modes.
-        self.pub = rospy.Publisher('/monitoring', Monitoring, queue_size=1)
+        self.pub = rospy.Publisher("/monitoring", Monitoring, queue_size=1)
         self.mon_mode = mon_mode
 
         if not mon_freq > 0.0:
@@ -52,7 +52,7 @@ class Monitor:
             self.monitoring.metric = metric
 
         def rst_key():  # Reset the value of a key in the logging dictionary.
-            self.log[label] = {'num': 0, 'val': 0, 'sum': 0, 'dur': rospy.get_rostime()}
+            self.log[label] = {"num": 0, "val": 0, "sum": 0, "dur": rospy.get_rostime()}
 
         if " " in label:  # A label cannot contain whitespace!
             rospy.logwarn("Whitespaces are not allowed in metric labels!")
@@ -67,32 +67,32 @@ class Monitor:
                 # Mode 2: Remember and set the minimum value,
                 #         obtained after mode selection.
                 elif self.mon_mode == 2:
-                    if value < self.log[label]['val']:
-                        self.log[label]['val'] = value
+                    if value < self.log[label]["val"]:
+                        self.log[label]["val"] = value
                     else:
-                        value = self.log[label]['val']
+                        value = self.log[label]["val"]
 
                     set_metric()
 
                 # Mode 3: Remember and set the maximum value,
                 #         obtained after mode selection.
                 elif self.mon_mode == 3:
-                    if value > self.log[label]['val']:
-                        self.log[label]['val'] = value
+                    if value > self.log[label]["val"]:
+                        self.log[label]["val"] = value
                     else:
-                        value = self.log[label]['val']
+                        value = self.log[label]["val"]
 
                     set_metric()
 
                 # Mode 4: Set the average obtained value over five
                 #         or more seconds.
                 elif self.mon_mode == 4:
-                    duration = rospy.get_rostime() - self.log[label]['dur']
+                    duration = rospy.get_rostime() - self.log[label]["dur"]
                     if duration < rospy.Duration(5):
-                        self.log[label]['num'] += 1
-                        self.log[label]['sum'] += value
+                        self.log[label]["num"] += 1
+                        self.log[label]["sum"] += value
                     else:
-                        value = self.log[label]['sum'] / (self.log[label]['num'] + 0.001)
+                        value = self.log[label]["sum"] / (self.log[label]["num"] + 0.001)
                         set_metric()
                         rst_key()
             else:
diff --git a/src/monitoring/translator.py b/src/monitoring/translator.py
new file mode 100644
index 0000000000000000000000000000000000000000..5010d28dc91fb1729709b92c4b241c65cae81659
--- /dev/null
+++ b/src/monitoring/translator.py
@@ -0,0 +1,29 @@
+#!/usr/bin/env python
+
+import rospy
+
+from monitoring.msg import Metric
+from monitoring.msg import Monitoring
+from monitoring_msgs.msg import MonitoringArray
+from monitoring_msgs.msg import MonitoringInfo
+from monitoring_msgs.msg import KeyValue
+
+
+class Translator:
+    def __init__(self):
+        self.sub = rospy.Subscriber("/luhrts_monitoring", MonitoringArray, self.translate)
+        self.pub = rospy.Publisher("/monitoring", Monitoring, queue_size=1)
+
+    def translate(self, event):
+        metric = Metric()
+        metric.domain = event.info[0].description
+        metric.label = event.info[0].values.key
+        metric.value = event.info[0].values.value
+        metric.unit = event.info[0].values.unit
+        metric.error = event.info[0].values.errorlevel
+
+        monitoring = Monitoring()
+        monitoring.origin = event.info[0].name
+        monitoring.metric = metric
+
+        self.pub.publish(monitoring)
diff --git a/src/monitoring/watchdog.py b/src/monitoring/watchdog.py
index 7ac2a86a9c85ca9ba9738d792c325d37a608b878..31250ae3e1c7ed055d3ac8d03f849a8e08aa3fbb 100755
--- a/src/monitoring/watchdog.py
+++ b/src/monitoring/watchdog.py
@@ -14,17 +14,17 @@ class Watchdog:
 
         # 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("/aggregation_strategy_metrics")
+        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("/aggregation_strategy_domains")
+        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("/wdg_freq", 1.0)
+        wdg_freq = rospy.get_param("/watchdog/wdg_freq", 1.0)
 
         if not wdg_freq > 0.0:
             rospy.logwarn(
@@ -78,7 +78,7 @@ class Watchdog:
                     self.aggregated_metrics.update({domain: highest_error})
 
                 # Strategy 2: Take the lowest error level of any metric in a domain.
-                if self.aggregation_strategy_metrics[domain] == 2:
+                elif self.aggregation_strategy_metrics[domain] == 2:
                     lowest_error = 1.0
 
                     for origin in self.log[domain]: