diff --git a/CMakeLists.txt b/CMakeLists.txt
index 7bd6a6af37b30ee1e022961eb316edcf6efb3d83..8ec28b319e13635268427408aaa1084a8813f62a 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -51,6 +51,8 @@ add_message_files(
    FILES
    Monitoring.msg
    Metric.msg
+   States.msg
+   State.msg
 )
 
 ## Generate services in the 'srv' folder
@@ -161,6 +163,8 @@ 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_test2
    nodes/monitor_test
    DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
 )
diff --git a/msg/Metric.msg b/msg/Metric.msg
index 26728b16295ff91c0abd7f28d1ce2721f36f0bad..08f38888fbc42add8b521e2a666e4c7f21fa00a6 100644
--- a/msg/Metric.msg
+++ b/msg/Metric.msg
@@ -1,4 +1,5 @@
-string  label    # Label of the metric.
-string  value    # Value of the metric.
-string  unit     # Unit of the metric.
-float32 critical # Critical level of the metric.
\ No newline at end of file
+string  component # A metric is affiliated with a roboter component.
+string  label     # Label of the metric.
+string  value     # Value of the metric.
+string  unit      # Unit of the metric.
+float32 critical  # Critical level of the metric.
\ No newline at end of file
diff --git a/msg/Monitoring.msg b/msg/Monitoring.msg
index 4274d629d1d80b950e6489396e654c3e1be821dc..dd121ac03fa7c1399581b3e2bacd5794954d7673 100644
--- a/msg/Monitoring.msg
+++ b/msg/Monitoring.msg
@@ -1,3 +1,2 @@
-string family # Affiliation of the monitored metric.
 string origin # Origin of the monitored metric.
 Metric metric # Monitored metric.
\ No newline at end of file
diff --git a/msg/State.msg b/msg/State.msg
new file mode 100644
index 0000000000000000000000000000000000000000..0d2c235a8af317a531ffa9be244984e49e194967
--- /dev/null
+++ b/msg/State.msg
@@ -0,0 +1,3 @@
+string  component # Name of the component, whose
+                  # critical level is monitored.
+float32 critical  # Critical level of the family.
\ No newline at end of file
diff --git a/msg/States.msg b/msg/States.msg
new file mode 100644
index 0000000000000000000000000000000000000000..d6705831806ee8d3908995353186638fe8aa46c5
--- /dev/null
+++ b/msg/States.msg
@@ -0,0 +1 @@
+State[] states # Array of states.
diff --git a/nodes/monitor_test b/nodes/monitor_test
index 01d669c6a008b9492c9d9abab4df56161604dcfe..50119dd5c1fa36ab26436ebfea22b84d6af0ca20 100755
--- a/nodes/monitor_test
+++ b/nodes/monitor_test
@@ -6,11 +6,11 @@ from monitoring.monitor import Monitor
 
 def monitor_test():
     rospy.init_node("monitor_test")
-    monitor = Monitor(1, 1, "test")
+    monitor = Monitor(1, 1)
 
     rate = rospy.Rate(10)
     while not rospy.is_shutdown():
-        monitor.update_metric("test", 10, "test", 0.5)
+        monitor.update_metric("family", "label1", 10, "unit", 0.5)
         rate.sleep()
 
 
diff --git a/nodes/monitor_test2 b/nodes/monitor_test2
new file mode 100755
index 0000000000000000000000000000000000000000..663b1975c281c663a7db91fa7132a1d06a606902
--- /dev/null
+++ b/nodes/monitor_test2
@@ -0,0 +1,25 @@
+#!/usr/bin/env python
+
+import rospy
+from monitoring.monitor import Monitor
+
+
+def monitor_test():
+    rospy.init_node("monitor_test2")
+    monitor = Monitor(1, 1)
+
+    rate = rospy.Rate(10)
+    value = 0
+    while not rospy.is_shutdown():
+        monitor.update_metric("family", "label2", 10, "unit", value)
+        value = value + 0.1
+        if value > 1.0:
+            value = 0
+        rate.sleep()
+
+
+if __name__ == '__main__':
+    try:
+        monitor_test()
+    except rospy.ROSInterruptException:
+        pass
diff --git a/nodes/watchdog b/nodes/watchdog
index 24ef85bdc4a3b780ab1663b6b9567ca1f708e985..dc202143e59e3eaad87ea80eaaae29391820fd28 100755
--- a/nodes/watchdog
+++ b/nodes/watchdog
@@ -6,11 +6,10 @@ from monitoring.watchdog import Watchdog
 
 def watchdog():
     rospy.init_node("watchdog")
-    watching = Watchdog(1.0)
+    watching = Watchdog(1, 1.0)
 
     rate = rospy.Rate(10)
     while not rospy.is_shutdown():
-        print(watching.states)
         rate.sleep()
 
 
diff --git a/src/monitoring/monitor.py b/src/monitoring/monitor.py
index 54c986a82822b97ea997a44dabd69509a5ed4ddd..307b26a2f0fbe5f5ab5d0c47651f5412ddfc51f7 100755
--- a/src/monitoring/monitor.py
+++ b/src/monitoring/monitor.py
@@ -7,7 +7,7 @@ from monitoring.msg import Metric
 
 
 class Monitor:
-    def __init__(self, mode=1, freq=1.0, family="generic"):
+    def __init__(self, mode=1, freq=1.0):
         self.log = {}  # Logging dictionary. Is used to accomplish different publishing modes.
         self.pub = rospy.Publisher('monitoring', Monitoring, queue_size=1)
         self.mode = mode
@@ -19,16 +19,16 @@ class Monitor:
         self.timer = rospy.Timer(rospy.Duration(1.0 / freq), self.publish_monitoring)
 
         self.monitoring = Monitoring()
-        self.monitoring.family = family
         self.monitoring.origin = socket.gethostname() + rospy.get_name()
 
     # At the moment the last metric update ist published over and over.
     def publish_monitoring(self, event):
         self.pub.publish(self.monitoring)
 
-    def update_metric(self, label, value, unit, critical):
+    def update_metric(self, component, label, value, unit, critical):
         def set_metric():
             metric = Metric()
+            metric.component = str(component)
             metric.label = str(label)
             metric.value = str(value)
             metric.unit = str(unit)
diff --git a/src/monitoring/watchdog.py b/src/monitoring/watchdog.py
index 829d0849a602d2b1a8d7253f1ae20f735e6a6fc3..3529bfdccb4ec1b4d7cca94f089b407451b1741f 100755
--- a/src/monitoring/watchdog.py
+++ b/src/monitoring/watchdog.py
@@ -2,54 +2,70 @@
 
 import rospy
 from monitoring.msg import Monitoring
+from monitoring.msg import State
+from monitoring.msg import States
 
 
 class Watchdog:
-    def __init__(self, freq):
-        self.states = {}
+    def __init__(self, mode=1, freq=1.0):
+        self.mode = mode
+        self.pub = rospy.Publisher('states', States, queue_size=1)
+        self.component_states = {}
         self.observing = {}
 
         if not freq > 0.0:
             rospy.logwarn("Frequency must be greater then 0! Using 1 as frequency!")
             freq = 1.0
 
-        self.timer = rospy.Timer(rospy.Duration(1.0 / freq), self.update_state)
+        self.timer = rospy.Timer(rospy.Duration(1.0 / freq), self.update_states)
 
         rospy.Subscriber("monitoring", Monitoring, self.logging)
 
     def logging(self, monitoring):
-        family = monitoring.family
         origin = monitoring.origin
         metric = monitoring.metric
 
+        component = metric.component
         label = metric.label
         value = metric.value
         unit = metric.unit
         critical = metric.critical
 
-        if family in self.observing:
-            if origin in self.observing[family]:
-                self.observing[family][origin].update({label: {"value": value, "unit": unit, "critical": critical}})
+        if component in self.observing:
+            if origin in self.observing[component]:
+                self.observing[component][origin].update({label: {"value": value, "unit": unit, "critical": critical}})
             else:
-                self.observing[family][origin] = {}
-                self.observing[family][origin][label] = {"value": value, "unit": unit, "critical": critical}
+                self.observing[component][origin] = {}
+                self.observing[component][origin][label] = {"value": value, "unit": unit, "critical": critical}
         else:
-            self.observing[family] = {}
-            self.observing[family][origin] = {}
-            self.observing[family][origin][label] = {"value": value, "unit": unit, "critical": critical}
+            self.observing[component] = {}
+            self.observing[component][origin] = {}
+            self.observing[component][origin][label] = {"value": value, "unit": unit, "critical": critical}
 
-    def update_state(self, event):
-        for family in self.observing:
-            aggregation = 0
-            number = 0
+    def update_states(self, event):
+        for component in self.observing:
+            # Mode 1: Take the average critical level for a component
+            if self.mode == 1:
+                aggregation = 0
+                number = 0
 
-            for origin in self.observing[family]:
-                for label in self.observing[family][origin]:
-                    number = number + 1
-                    aggregation = aggregation + self.observing[family][origin][label]["critical"]
+                for origin in self.observing[component]:
+                    for label in self.observing[component][origin]:
+                        number = number + 1
+                        aggregation = aggregation + self.observing[component][origin][label]["critical"]
 
-            quotient = aggregation / number
-            self.states.update({family: quotient})
+                quotient = aggregation / number
+                self.component_states.update({component: quotient})
 
+        self.publish_states()
 
+    def publish_states(self):
+        topic = States()
+        for component in self.component_states:
+            state = State()
+            state.component = component
+            state.critical = self.component_states[component]
 
+            topic.states.append(state)
+
+        self.pub.publish(topic)