Go to the documentation of this file.00001
00002
00003
00004 import sys
00005 import unittest
00006 import rospy
00007 import rostest
00008 import simplejson
00009 from o3d3xx.srv import Dump, Config
00010
00011 class TestServices(unittest.TestCase):
00012
00013 def __init__(self, *args):
00014 super(TestServices, self).__init__(*args)
00015
00016 def test_services(self):
00017 rospy.init_node('test_services')
00018 rospy.wait_for_service("/Dump")
00019 rospy.wait_for_service("/Config")
00020
00021 self.dump_srv = rospy.ServiceProxy("/Dump", Dump)
00022 self.config_srv = rospy.ServiceProxy("/Config", Config)
00023
00024 dump_resp = self.dump_srv()
00025 json = simplejson.loads(dump_resp.config)
00026 idx = int(json["o3d3xx"]["Device"]["ActiveApplication"])
00027 self.assertTrue(idx > 0)
00028
00029 params = [(idx, 5, "upto30m_moderate"),
00030 (idx, 10, "under5m_low"),
00031 (idx, 5, "upto30m_moderate")]
00032 for param_set in params:
00033 self._dump_config(*param_set)
00034
00035 def _dump_config(self, idx, frame_rate, im_type):
00036 dump_resp = self.dump_srv()
00037 json = simplejson.loads(dump_resp.config)
00038
00039 real_idx = 0
00040 for app in json["o3d3xx"]["Apps"]:
00041 if int(app["Index"]) == idx:
00042 break
00043 else:
00044 real_idx += 1
00045
00046 json["o3d3xx"]["Apps"][real_idx]["Imager"]["FrameRate"] = \
00047 str(frame_rate)
00048 json["o3d3xx"]["Apps"][real_idx]["Imager"]["Type"] = str(im_type)
00049
00050 config_resp = self.config_srv(simplejson.dumps(json))
00051 self.assertTrue(config_resp.status == 0)
00052
00053 dump_resp = self.dump_srv()
00054 json = simplejson.loads(dump_resp.config)
00055
00056 fr = int(json["o3d3xx"]["Apps"][real_idx]["Imager"]["FrameRate"])
00057 it = json["o3d3xx"]["Apps"][real_idx]["Imager"]["Type"]
00058 self.assertTrue(fr == frame_rate)
00059 self.assertTrue(it == im_type)
00060
00061 def main():
00062 rostest.rosrun('o3d3xx', 'test_services', TestServices, sys.argv)
00063 return 0
00064
00065 if __name__ == '__main__':
00066 sys.exit(main())