Skip to content
Snippets Groups Projects
Commit f04ca230 authored by bav6096's avatar bav6096
Browse files

cleanup

parent 5afd431d
No related branches found
No related tags found
No related merge requests found
...@@ -51,8 +51,6 @@ add_message_files( ...@@ -51,8 +51,6 @@ add_message_files(
FILES FILES
Monitoring.msg Monitoring.msg
Metric.msg Metric.msg
States.msg
State.msg
) )
## Generate services in the 'srv' folder ## Generate services in the 'srv' folder
...@@ -166,7 +164,7 @@ catkin_install_python(PROGRAMS ...@@ -166,7 +164,7 @@ catkin_install_python(PROGRAMS
nodes/watchdog nodes/watchdog
nodes/monitor_distance nodes/monitor_distance
nodes/monitor_test2 nodes/monitor_test2
nodes/monitor_test nodes/monitor_test1
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
) )
......
<launch>
<node pkg="monitoring" type="monitor_test_1" name="monitor_test_1" />
</launch>
\ No newline at end of file
<launch>
<node pkg="monitoring" type="monitor_test_2" name="monitor_test_2" />
</launch>
\ No newline at end of file
<launch>
<node pkg="monitoring" type="monitor_test_3" name="monitor_test_3" />
</launch>
\ No newline at end of file
<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
<launch>
<node pkg="monitoring" type="translator" name="translator" />
</launch>
\ No newline at end of file
<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
#!/usr/bin/env pyhton #!/usr/bin/env python
import rospy import rospy
from sensor_msgs.msg import LaserScan from sensor_msgs.msg import LaserScan
......
...@@ -4,18 +4,18 @@ import rospy ...@@ -4,18 +4,18 @@ import rospy
from monitoring.monitor import Monitor from monitoring.monitor import Monitor
def monitor_test(): def monitor_test_1():
rospy.init_node("monitor_test") rospy.init_node("monitor_test_1")
monitor = Monitor(1, 1) monitor = Monitor(1, 1.0)
rate = rospy.Rate(10) rate = rospy.Rate(10)
while not rospy.is_shutdown(): 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() rate.sleep()
if __name__ == '__main__': if __name__ == '__main__':
try: try:
monitor_test() monitor_test_1()
except rospy.ROSInterruptException: except rospy.ROSInterruptException:
pass pass
...@@ -4,14 +4,14 @@ import rospy ...@@ -4,14 +4,14 @@ import rospy
from monitoring.monitor import Monitor from monitoring.monitor import Monitor
def monitor_test(): def monitor_test_2():
rospy.init_node("monitor_test2") rospy.init_node("monitor_test_2")
monitor = Monitor(1, 1) monitor = Monitor(1, 1.0)
rate = rospy.Rate(10) rate = rospy.Rate(10)
value = 0 value = 0
while not rospy.is_shutdown(): 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 value = value + 0.1
if value > 1.0: if value > 1.0:
value = 0 value = 0
...@@ -20,6 +20,6 @@ def monitor_test(): ...@@ -20,6 +20,6 @@ def monitor_test():
if __name__ == '__main__': if __name__ == '__main__':
try: try:
monitor_test() monitor_test_2()
except rospy.ROSInterruptException: except rospy.ROSInterruptException:
pass pass
#!/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
#!/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
...@@ -4,17 +4,10 @@ import rospy ...@@ -4,17 +4,10 @@ import rospy
from monitoring.watchdog import Watchdog 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__': if __name__ == '__main__':
try: try:
watchdog() rospy.init_node("watchdog")
watchdog = Watchdog()
rospy.spin()
except rospy.ROSInterruptException: except rospy.ROSInterruptException:
pass pass
...@@ -23,7 +23,7 @@ class Monitor: ...@@ -23,7 +23,7 @@ class Monitor:
""" """
def __init__(self, mon_mode=1, mon_freq=1.0): def __init__(self, mon_mode=1, mon_freq=1.0):
self.log = {} # Logging dictionary. Is used to accomplish different publishing modes. 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 self.mon_mode = mon_mode
if not mon_freq > 0.0: if not mon_freq > 0.0:
...@@ -52,7 +52,7 @@ class Monitor: ...@@ -52,7 +52,7 @@ class Monitor:
self.monitoring.metric = metric self.monitoring.metric = metric
def rst_key(): # Reset the value of a key in the logging dictionary. 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! if " " in label: # A label cannot contain whitespace!
rospy.logwarn("Whitespaces are not allowed in metric labels!") rospy.logwarn("Whitespaces are not allowed in metric labels!")
...@@ -67,32 +67,32 @@ class Monitor: ...@@ -67,32 +67,32 @@ class Monitor:
# Mode 2: Remember and set the minimum value, # Mode 2: Remember and set the minimum value,
# obtained after mode selection. # obtained after mode selection.
elif self.mon_mode == 2: elif self.mon_mode == 2:
if value < self.log[label]['val']: if value < self.log[label]["val"]:
self.log[label]['val'] = value self.log[label]["val"] = value
else: else:
value = self.log[label]['val'] value = self.log[label]["val"]
set_metric() set_metric()
# Mode 3: Remember and set the maximum value, # Mode 3: Remember and set the maximum value,
# obtained after mode selection. # obtained after mode selection.
elif self.mon_mode == 3: elif self.mon_mode == 3:
if value > self.log[label]['val']: if value > self.log[label]["val"]:
self.log[label]['val'] = value self.log[label]["val"] = value
else: else:
value = self.log[label]['val'] value = self.log[label]["val"]
set_metric() set_metric()
# Mode 4: Set the average obtained value over five # Mode 4: Set the average obtained value over five
# or more seconds. # or more seconds.
elif self.mon_mode == 4: 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): if duration < rospy.Duration(5):
self.log[label]['num'] += 1 self.log[label]["num"] += 1
self.log[label]['sum'] += value self.log[label]["sum"] += value
else: 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() set_metric()
rst_key() rst_key()
else: else:
......
#!/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)
...@@ -14,17 +14,17 @@ class Watchdog: ...@@ -14,17 +14,17 @@ class Watchdog:
# Strategies that specify how the critical level of each metric should be aggregated in a domain. # 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. # 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. # Dictionary that stores the aggregated critical levels of the metrics of a domain.
self.aggregated_metrics = {} self.aggregated_metrics = {}
# Strategy that specifies how the critical levels of all domains should be aggregated. # 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. # Variable that stores the aggregated critical level of all domains.
self.aggregated_domains = None self.aggregated_domains = None
# Frequency at which the metrics in the log are aggregated. # 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: if not wdg_freq > 0.0:
rospy.logwarn( rospy.logwarn(
...@@ -78,7 +78,7 @@ class Watchdog: ...@@ -78,7 +78,7 @@ class Watchdog:
self.aggregated_metrics.update({domain: highest_error}) self.aggregated_metrics.update({domain: highest_error})
# Strategy 2: Take the lowest error level of any metric in a domain. # 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 lowest_error = 1.0
for origin in self.log[domain]: for origin in self.log[domain]:
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment