Skip to content

Commit 9eff3e4

Browse files
Merge pull request #150 from floweisshardt/fix/user_result
rework groundtruth handling
2 parents e34457c + 6a02908 commit 9eff3e4

25 files changed

+945
-1229
lines changed

atf_core/scripts/analyser.py

Lines changed: 13 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -8,19 +8,19 @@
88
import rostest
99
import sys
1010
import time
11+
import traceback
1112
import unittest
1213
import yaml
1314

1415
from atf_core import ATFConfigurationParser
15-
from atf_msgs.msg import AtfResult, TestResult, TestblockResult, MetricResult, TestblockStatus, KeyValue, DataStamped
16+
from atf_msgs.msg import AtfResult, TestResult, TestblockResult, MetricResult, TestblockStatus, KeyValue, DataStamped, Groundtruth
1617
from atf_metrics import metrics_helper
1718

1819
class Analyser:
1920
def __init__(self, package_name, test_generation_config_file = "atf/test_generation_config.yaml"):
2021
print "ATF analyser: started!"
2122
start_time = time.time()
2223
self.ns = "/atf/"
23-
self.error = False
2424
self.package_name = package_name
2525

2626
# parse configuration
@@ -78,11 +78,13 @@ def __init__(self, package_name, test_generation_config_file = "atf/test_generat
7878
break
7979
except Exception as e:
8080
print "general Exception in ATF analyser", type(e), e
81+
print traceback.format_exc()
8182
count_error += 1
8283
continue
8384
bar.update(j)
8485
except Exception as e:
8586
print "FATAL exception in bag file", type(e), e
87+
print traceback.format_exc()
8688
continue
8789
bar.finish()
8890

@@ -178,18 +180,15 @@ def aggregate_results(self, atf_result):
178180
for tl_test in tl_tests.keys():
179181
#print " tl_test=", tl_test
180182
metric_result = MetricResult()
181-
started = True
182-
finished = True
183-
groundtruth_result = True
183+
status = TestblockStatus.SUCCEEDED
184+
groundtruth_result = Groundtruth.SUCCEEDED
184185
groundtruth_error_message = ""
185186
details = []
186187
for test in mbt[metric][testblock].keys():
187188
if test.startswith(tl_test):
188-
# aggregate started/stopped from every metric_result
189-
if not mbt[metric][testblock][test].started:
190-
started = False
191-
if not mbt[metric][testblock][test].finished:
192-
finished = False
189+
# aggregate status SUCCEEDED from every metric_result
190+
if mbt[metric][testblock][test].status != TestblockStatus.SUCCEEDED:
191+
status = TestblockStatus.ERROR
193192

194193
# aggregate data from every metric_result
195194
data = mbt[metric][testblock][test].data
@@ -201,8 +200,8 @@ def aggregate_results(self, atf_result):
201200

202201
# aggregate groundtruth from every metric_result
203202
groundtruth = mbt[metric][testblock][test].groundtruth
204-
if groundtruth.result == False:
205-
groundtruth_result = False
203+
if groundtruth.result != Groundtruth.SUCCEEDED:
204+
groundtruth_result = Groundtruth.FAILED
206205
if groundtruth_error_message != "":
207206
groundtruth_error_message += "\n"
208207
groundtruth_error_message += "groundtruth missmatch in subtest %s"%(test)
@@ -219,8 +218,7 @@ def aggregate_results(self, atf_result):
219218

220219
metric_result.name = mbt[metric][testblock][test].name
221220
metric_result.mode = MetricResult.SPAN_MEAN # aggregated metrics are always SPAN_MEAN
222-
metric_result.started = started
223-
metric_result.finished = finished
221+
metric_result.status = status
224222
# metric_result.series is set above
225223
metric_result.data.stamp = stamp
226224
metric_result.data.data = metrics_helper.get_mean(metric_result.series)
@@ -273,7 +271,7 @@ def aggregate_results(self, atf_result):
273271
metric_result = tbm[test][testblock][metric]
274272
testblock_result.results.append(metric_result)
275273
# aggregate metric result
276-
if metric_result.groundtruth.result == False:
274+
if metric_result.groundtruth.result != Groundtruth.SUCCEEDED:
277275
testblock_result.result = False
278276
testblock_result.error_message += "\n - metric '%s': %s"%(metric_result.name, metric_result.groundtruth.error_message)
279277

atf_core/src/atf_core/atf.py

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ def stop(self, testblock, metric_result = None):
5555
error_msg = "testblock \'%s\' not in list of testblocks"%testblock
5656
self._send_error(error_msg)
5757
raise atf_core.ATFError(error_msg)
58-
58+
5959
if metric_result != None:
6060

6161
#TODO check if metric_result is of type atf_msgs/MetricResult
@@ -91,22 +91,25 @@ def stop(self, testblock, metric_result = None):
9191

9292
else:
9393
rospy.loginfo("no user result set for testblock \'%s\'"%testblock)
94+
metric_result = MetricResult()
9495

9596
rospy.loginfo("stopping testblock \'%s\'"%testblock)
9697
trigger = TestblockTrigger()
9798
trigger.stamp = rospy.Time.now()
9899
trigger.name = testblock
99100
trigger.trigger = TestblockTrigger.STOP
100-
if metric_result != None:
101-
trigger.user_result = metric_result
101+
trigger.user_result = metric_result
102102
self.publisher_trigger.publish(trigger)
103103

104104
def shutdown(self):
105105
rospy.loginfo("shutting down atf application")
106106

107107
# call stop for all testblocks
108108
for testblock in self.test.testblocks:
109-
self.stop(testblock.name)
109+
rospy.sleep(1) # TODO remove sleep and wait until all states have finished their transitions
110+
if testblock.name in self.sm_container_status.active_states:
111+
rospy.logwarn("shutdown called but testblock %s is still active: calling stop automatically"%testblock.name)
112+
self.stop(testblock.name)
110113

111114
# check if any testblock is still running
112115
rospy.loginfo("waiting for all states to be in a terminal state")

atf_core/src/atf_core/configuration_parser.py

Lines changed: 12 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -208,15 +208,20 @@ def validate_metric_parameters(self, metric_type, params):
208208
print "params not a dict"
209209
return False
210210

211-
if "groundtruth" in params and "groundtruth_epsilon" in params: # groundtruth specified
212-
pass
213-
elif "groundtruth" not in params and "groundtruth_epsilon" not in params: # no groundtruth specified
214-
pass
215-
else: # invalid configuration
216-
# e.g. (params["groundtruth"] == None and params["groundtruth_epsilon"] != None) or (params["groundtruth"] != None and params["groundtruth_epsilon"] == None)
211+
try:
212+
params["groundtruth"]
213+
except (TypeError, KeyError):
214+
return True # no groundtruth specified
215+
216+
try:
217+
params["groundtruth"]["data"]
218+
params["groundtruth"]["epsilon"]
219+
return True # groundtruth specified
220+
except (TypeError, KeyError):
221+
# e.g. (params["groundtruth"]["data"] == None and params["groundtruth"]["epsilon"] != None) or (params["groundtruth"]["data"] != None and params["groundtruth"]["epsilon"] == None)
217222
print "invalid groundtruth specified:", params
218223
return False
219-
224+
220225
return True # all checks successfull
221226

222227
def load_data(self, filename):

atf_core/src/atf_core/testblock.py

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
#!/usr/bin/env python
22

33
from atf_core import ATFAnalyserError
4-
from atf_msgs.msg import TestblockResult, TestblockStatus
4+
from atf_msgs.msg import TestblockResult, TestblockStatus, Groundtruth
55

66
class Testblock:
77
def __init__(self, name, metric_handles, recorder_handle):
@@ -12,8 +12,7 @@ def __init__(self, name, metric_handles, recorder_handle):
1212
self.trigger = None
1313
self.timestamp = None
1414
self.exception = None
15-
self.atf_started = False
16-
self.status = None
15+
self.status = TestblockStatus.INACTIVE
1716

1817
def get_result(self):
1918

@@ -35,11 +34,11 @@ def get_result(self):
3534
testblock_result.results.append(metric_result)
3635

3736
# aggregate result
38-
if metric_result.groundtruth.result != None and not metric_result.groundtruth.result:
37+
if metric_result.groundtruth.result != Groundtruth.SUCCEEDED:
3938
testblock_result.result = False
4039
testblock_result.error_message += "\n - metric '%s': %s"%(metric_result.name, metric_result.groundtruth.error_message)
4140
#print testblock_result.groundtruth_error_message
42-
if testblock_result.result == None and metric_result.groundtruth.result:
41+
if testblock_result.result == None and metric_result.groundtruth.result == Groundtruth.SUCCEEDED:
4342
testblock_result.result = True
4443

4544
if testblock_result.result == None:

0 commit comments

Comments
 (0)