Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Feature/resources #42

Open
wants to merge 28 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,13 @@ qtcreator-*
/planning/src

*~
*.orig

# Emacs
.#*

# Catkin custom files
CATKIN_IGNORE
test_generated

.idea/*
4 changes: 3 additions & 1 deletion atf_core/src/atf_core/recorder.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import os
import atf_recorder_plugins
import atf_core
import time

from threading import Lock
from atf_msgs.msg import TestblockTrigger
Expand Down Expand Up @@ -128,8 +129,9 @@ def create_subscriber_callback(self, event):
if topic not in self.subscriber:
try:
msg_class, _, _ = rostopic.get_topic_class(topic)
rospy.Subscriber(topic, msg_class, self.global_topic_callback, callback_args=topic)
rospy.Subscriber(topic, msg_class, self.global_topic_callback, callback_args=topic, queue_size=10)
self.subscriber.append(topic)
print "new subscriber for: ", topic, "message class:", msg_class, " subscribers: ", self.subscriber
except Exception:
pass

Expand Down
16 changes: 13 additions & 3 deletions atf_metrics/config/metrics.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,23 @@ time:
handler: CalculateTimeParamHandler
path_length:
handler: CalculatePathLengthParamHandler
resources:
handler: CalculateResourcesParamHandler
distance:
handler: CalculateDistanceParamHandler
resource_cpu:
handler: CalculateResourcesCpuParamHandler
resource_mem:
handler: CalculateResourcesMemParamHandler
resource_io:
handler: CalculateResourcesIOParamHandler
resource_network:
handler: CalculateResourcesNetworkParamHandler
obstacle_distance:
handler: CalculateDistanceToObstaclesParamHandler
publish_rate:
handler: CalculatePublishRateParamHandler
interface:
handler: CalculateInterfaceParamHandler
handler: CalculateInterfaceParamHandler
localization:
handler: CheckLocalizationParamHandler
# example:
# handler: ExampleParamHandler
5 changes: 4 additions & 1 deletion atf_metrics/src/atf_metrics/__init__.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
from atf_metrics.calculate_path_length import CalculatePathLength, CalculatePathLengthParamHandler
from atf_metrics.calculate_time import CalculateTime, CalculateTimeParamHandler
from atf_metrics.calculate_resources import CalculateResources, CalculateResourcesParamHandler
from atf_metrics.calculate_resources_cpu import CalculateResourcesCpu, CalculateResourcesCpuParamHandler
from atf_metrics.calculate_resources_mem import CalculateResourcesMem, CalculateResourcesMemParamHandler
from atf_metrics.calculate_resources_io import CalculateResourcesIO, CalculateResourcesIOParamHandler
from atf_metrics.calculate_resources_network import CalculateResourcesNetwork, CalculateResourcesNetworkParamHandler
from atf_metrics.calculate_distance_to_obstacles import CalculateDistanceToObstacles, CalculateDistanceToObstaclesParamHandler
from atf_metrics.calculate_publish_rate import CalculatePublishRate, CalculatePublishRateParamHandler
from atf_metrics.calculate_interface import CalculateInterface, CalculateInterfaceParamHandler
Expand Down
123 changes: 0 additions & 123 deletions atf_metrics/src/atf_metrics/calculate_resources.py

This file was deleted.

139 changes: 139 additions & 0 deletions atf_metrics/src/atf_metrics/calculate_resources_cpu.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,139 @@
#!/usr/bin/env python
import numpy
import rospy
import math

from atf_msgs.msg import Resources, IO, Network


class CalculateResourcesCpuParamHandler:
def __init__(self):
"""
Class for returning the corresponding metric class with the given parameter.
"""
self.params = []

def parse_parameter(self, testblock_name, params):
"""
Method that returns the metric method with the given parameter.
:param params: Parameter
"""
if not isinstance(params, list):
rospy.logerr("metric config not a list")
return False
metrics = []
print "params:", params
for metric in params:
# check for optional parameters
try:
groundtruth = metric["groundtruth"]
groundtruth_epsilon = metric["groundtruth_epsilon"]
print "groundtruth", groundtruth, "groundtruth_epsilon", groundtruth_epsilon
if 'groundtruth' in metric:
del metric['groundtruth']
if 'groundtruth_epsilon' in metric:
del metric['groundtruth_epsilon']
except (TypeError, KeyError):
rospy.logwarn(
"No groundtruth parameters given, skipping groundtruth evaluation for metric 'resources' in testblock '%s'",
testblock_name)
groundtruth = None
groundtruth_epsilon = None
print "metric:", metric
metrics.append(CalculateResourcesCpu(metric["nodes"], groundtruth, groundtruth_epsilon))
return metrics


class CalculateResourcesCpu:
def __init__(self, nodes, groundtruth, groundtruth_epsilon):
"""
Class for calculating the average resource workload and writing the current resource data.
The resource data is sent over the topic "/testing/Resources".
:param resources: a dictionary containing the names of the resources and a list with the names of the nodes.
Example: {"cpu":[move_group], "mem": [move_group]}
:type resources: dict
"""

self.active = False
self.resource = "cpu"
self.groundtruth = groundtruth
self.groundtruth_epsilon = groundtruth_epsilon
self.node_data = {}
self.size_io = len(IO.__slots__)
self.size_network = len(Network.__slots__)
self.finished = False

# Sort resources after nodes
print "node data:", self.node_data
for node in nodes:
if node not in self.node_data:
print "node : ", node
self.node_data[node] = {self.resource: {"data": [], "average": [], "min": [], "max": []}}
# elif resource not in self.node_data[node]:
# self.node_data[node].update({resource: {"data": [], "average": [], "min": [], "max": []}})
rospy.Subscriber("/atf/resources", Resources, self.process_resource_data, queue_size=1)

def start(self, timestamp):
self.active = True

def stop(self, timestamp):
self.active = False
self.finished = True

def pause(self, timestamp):
self.active = False

def purge(self, timestamp):
pass

def process_resource_data(self, msg):
#print "--------------------------------------\nprocess data \n msg:", msg, "\n active", self.active
if self.active:
for node in msg.nodes:
try:
for resource in self.node_data[node.node_name]:
#print "nodes:", msg.nodes, "\n node data:", self.node_data, "\n resource", resource
if resource == "cpu":
self.node_data[node.node_name][resource]["data"].append(round(node.cpu, 2))
except KeyError:
pass

def get_result(self):
groundtruth_result = None
details = {"sum of nodes":[]}
average_sum = 0.0

if self.finished:
#print "----------------------------- \n node data:", self.node_data
for node in self.node_data:
#print " node:", node
for res in self.node_data[node]:
#print "res", res
if len(self.node_data[node][res]["data"]) != 0:
self.node_data[node][res]["average"] = float(round(numpy.mean(self.node_data[node][res]
["data"]), 2))
self.node_data[node][res]["min"] = float(round(min(self.node_data[node][res]["data"]), 2))
self.node_data[node][res]["max"] = float(round(max(self.node_data[node][res]["data"]), 2))
average_sum += float(round(numpy.mean(self.node_data[node][res]["data"]), 2))
print "average sum:", average_sum
del self.node_data[node][res]["data"]

details["sum of nodes"].append(node)
# details["nodes"][node].append({"max":self.node_data[node][res]["max"]})
# details["nodes"][node].append({"average":self.node_data[node][res]["average"]})
# details["nodes"][node].append({"min":self.node_data[node][res]["min"]})

#print "groundtruthes:", self.groundtruth, self.groundtruth_epsilon, "\n average:", self.node_data[node][res]["average"]
if self.groundtruth != None and self.groundtruth_epsilon != None:
for node in self.node_data:

#print "average sum:check", average_sum
if math.fabs(self.groundtruth - average_sum) <= self.groundtruth_epsilon:
groundtruth_result = True
else:
groundtruth_result = False

print "resources cpu data: ", average_sum, "\n groundthruth result", groundtruth_result, "details:", details, " \n .................................."
return "resources_cpu", round(average_sum, 3), groundtruth_result, self.groundtruth, self.groundtruth_epsilon, details
else:
return False
Loading