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

more cleanup

parent f04ca230
No related branches found
No related tags found
No related merge requests found
...@@ -161,10 +161,10 @@ include_directories( ...@@ -161,10 +161,10 @@ include_directories(
## Mark executable scripts (Python etc.) for installation ## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination ## in contrast to setup.py, you can choose the destination
catkin_install_python(PROGRAMS catkin_install_python(PROGRAMS
nodes/watchdog
nodes/monitor_distance nodes/monitor_distance
nodes/monitor_test2 nodes/monitor_test_1
nodes/monitor_test1 nodes/monitor_test_2
nodes/monitor_test_3
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
) )
......
<launch>
<node pkg="monitoring" type="monitor_distance" name="monitor_distance" />
</launch>
\ No newline at end of file
<launch> <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_1.launch" />
<include file="$(find monitoring)/launch/monitor_test_2.launch" /> <include file="$(find monitoring)/launch/monitor_test_2.launch" />
<include file="$(find monitoring)/launch/monitor_test_3.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> </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 python #!/usr/bin/env python
import rospy import rospy
from sensor_msgs.msg import LaserScan from sensor_msgs.msg import LaserScan
from monitoring.monitor import Monitor from monitoring.monitor import Monitor
...@@ -16,6 +17,7 @@ if __name__ == '__main__': ...@@ -16,6 +17,7 @@ if __name__ == '__main__':
rospy.init_node("monitor_distance") rospy.init_node("monitor_distance")
monitor = Monitor() monitor = Monitor()
distance = float("inf")
rate = rospy.Rate(10) rate = rospy.Rate(10)
while not rospy.is_shutdown(): while not rospy.is_shutdown():
......
#!/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
#!/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
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment