From 0eee791a3800a964c51a7f22b607461a41f13860 Mon Sep 17 00:00:00 2001 From: strdn Date: Mon, 24 Sep 2018 11:28:34 +0300 Subject: [PATCH] tests improvement: automate test_executor --- .../test/test_executor.py | 65 ++++++++++++++++++- robonomics_liability/tests/liability.test | 2 + 2 files changed, 65 insertions(+), 2 deletions(-) diff --git a/robonomics_liability/src/robonomics_liability/test/test_executor.py b/robonomics_liability/src/robonomics_liability/test/test_executor.py index 313e73a..634d37e 100755 --- a/robonomics_liability/src/robonomics_liability/test/test_executor.py +++ b/robonomics_liability/src/robonomics_liability/test/test_executor.py @@ -1,10 +1,12 @@ #!/usr/bin/env python import unittest, rostest, os, time, rospy, rosbag -from robonomics_lighthouse.msg import Result + +from robonomics_lighthouse.msg import Result, Bid, Ask from robonomics_liability.msg import Liability from urllib.parse import urlparse import ipfsapi +import std_srvs.srv from tempfile import TemporaryDirectory from std_msgs.msg import * @@ -20,6 +22,11 @@ def __init__(self, *args): ipfs_provider = urlparse(rospy.get_param('~ipfs_http_provider')).netloc.split(':') self.ipfs = ipfsapi.connect(ipfs_provider[0], int(ipfs_provider[1])) + + self.test_token = rospy.get_param('~test_token') + self.test_bid_publisher = rospy.Publisher('/liability/infochan/signing/bid', Bid, queue_size=10) + self.test_ask_publisher = rospy.Publisher('/liability/infochan/signing/ask', Ask, queue_size=10) + self.test_start_time = time.time() self.success = False @@ -46,14 +53,68 @@ def check_rosbag_is_new_and_has_messages(self, result): rospy.loginfo("ROSBAG: result has start time %s", bag.get_start_time()) return bag.get_message_count() != 0 and bag.get_start_time() > self.test_start_time + def test_executor(self): rospy.Subscriber('liability/incoming', Liability, self.incoming_liability_handler) rospy.Subscriber('liability/result', Result, self.result_handler) - timeout_t = time.time() + 60.0 + + time.sleep(15) + self.test_bid_publisher.publish(self.get_test_bid()) + self.test_ask_publisher.publish(self.get_test_ask()) + + timeout_t = time.time() + 30.0 + while self.incoming_liability is None and time.time() < timeout_t: + time.sleep(0.1) + + time.sleep(5) + finish_service_proxy = rospy.ServiceProxy('/liability/finish', std_srvs.srv.Empty) + finish_service_proxy() + + timeout_t = time.time() + 30.0 while not rospy.is_shutdown() and not self.success and time.time() < timeout_t: time.sleep(0.1) self.assert_(self.success) + def get_test_bid(self): + bidDict = { + "model": "QmaRmbJtyfMDBfkDETTPAxKUUcSqZKXWwFKKoZ318nrPku", + "objective": "Qmb3H3tHZ1QutcrLq7WEtQWbEWjA11aPqVmeatMSrmFXvE", + "token": self.test_token, + "cost": 1, + "lighthouseFee": 0, + "deadline": 9999999 + } + bid = Bid() + bid.model = bidDict['model'] + bid.objective = bidDict['objective'] + bid.token = bidDict['token'] + bid.cost = bidDict['cost'] + bid.lighthouseFee = bidDict['lighthouseFee'] + bid.deadline = bidDict['deadline'] + return bid + + + def get_test_ask(self): + askDict = { + "model": "QmaRmbJtyfMDBfkDETTPAxKUUcSqZKXWwFKKoZ318nrPku", + "objective": "Qmb3H3tHZ1QutcrLq7WEtQWbEWjA11aPqVmeatMSrmFXvE", + "token": self.test_token, + "cost": 1, + "validator": "0x0000000000000000000000000000000000000000", + "validatorFee": 0, + "deadline": 9999999 + } + ask = Ask() + ask.model = askDict['model'] + ask.objective = askDict['objective'] + ask.token = askDict['token'] + ask.cost = askDict['cost'] + ask.validator = askDict['validator'] + ask.validatorFee = askDict['validatorFee'] + ask.deadline = askDict['deadline'] + return ask + + if __name__ == '__main__': rostest.rosrun(PKG, NAME, TestExecutor, sys.argv) diff --git a/robonomics_liability/tests/liability.test b/robonomics_liability/tests/liability.test index fac0aa5..3052564 100644 --- a/robonomics_liability/tests/liability.test +++ b/robonomics_liability/tests/liability.test @@ -9,6 +9,7 @@ + @@ -41,6 +42,7 @@ +