00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 PKG = 'test_rospy'
00037 NAME = 'test_rospy_client_param_server'
00038
00039 import sys, time
00040 import math
00041 import unittest
00042
00043 import rospy
00044 import rostest
00045 from test_rospy.srv import *
00046
00047 def test_param_filter(params):
00048 return [p for p in params if not p.startswith('/roslaunch') and p not in ['/run_id', '/rosdistro', '/rosversion']]
00049
00050
00051
00052
00053
00054
00055
00056 class TestClientParamServer(unittest.TestCase):
00057
00058
00059 def test_get_has_param(self):
00060
00061 try: rospy.get_param(None); self.fail("get_param(None) succeeded")
00062 except: pass
00063 try: rospy.get_param(''); self.fail("get_param('') succeeded")
00064 except: pass
00065
00066 try: rospy.get_param('non-existent'); self.fail("get_param('non-existent') succeeded")
00067 except: pass
00068 try: rospy.has_param(None, 'foo'); self.fail("has_param(None) succeeded")
00069 except: pass
00070 try: rospy.has_param(''); self.fail("has_param('') succeeded")
00071 except: pass
00072
00073 self.failIf(rospy.has_param('non-existent'), "has_param('non-existent') succeeded")
00074
00075
00076 rostest_tests = {
00077 'string': "string",
00078 'int0': 0,
00079 'int10': 10,
00080 'float0': 0.0,
00081 'float10': 10.0,
00082 "namespace/string": "namespaced string",
00083 }
00084 param_names = [rospy.resolve_name(k) for k in rostest_tests.keys()]
00085
00086
00087 diff = set(param_names) ^ set(test_param_filter(rospy.get_param_names()))
00088 self.failIf(diff, diff)
00089
00090
00091 for k, v in rostest_tests.items():
00092 self.assert_(rospy.has_param(k))
00093 self.assert_(rospy.has_param(rospy.resolve_name(k)))
00094 if not type(v) == float:
00095 self.assertEqual(v, rospy.get_param(k))
00096 self.assertEqual(v, rospy.get_param(rospy.resolve_name(k)))
00097 else:
00098 self.assertAlmostEqual(v, rospy.get_param(k), 1)
00099 self.assertAlmostEqual(v, rospy.get_param(rospy.resolve_name(k)), 1)
00100
00101 def test_search_param(self):
00102 try:
00103 orig_caller_id = rospy.names.get_caller_id()
00104
00105 rospy.names._set_caller_id('/global_node')
00106
00107 self.assertEquals(None, rospy.search_param('search_param'))
00108 rospy.set_param('/search_param', 1)
00109 self.assertEquals('/search_param', rospy.search_param('search_param'))
00110
00111 rospy.names._set_caller_id('/level1/level2/relative_node')
00112 self.assertEquals('/search_param', rospy.search_param('search_param'))
00113 rospy.set_param('/level1/search_param', 2)
00114 self.assertEquals('/level1/search_param', rospy.search_param('search_param'))
00115 rospy.set_param('~search_param', 3)
00116
00117 self.assertEquals('/level1/level2/relative_node/search_param', rospy.search_param('search_param'))
00118
00119 finally:
00120 rospy.names._set_caller_id(orig_caller_id)
00121
00122 def test_delete_param(self):
00123 try: rospy.delete_param(None); self.fail("delete_param(None) succeeded")
00124 except: pass
00125 try: rospy.delete_param(''); self.fail("delete_param('') succeeded")
00126 except: pass
00127
00128 rostest_tests = {
00129 'dpstring': "string",
00130 'dpint0': 0,
00131 'dpint10': 10,
00132 'dpfloat0': 0.0,
00133 'dpfloat10': 10.0,
00134 "dpnamespace/string": "namespaced string",
00135 }
00136 initial_params = rospy.get_param_names()
00137
00138 for k, v in rostest_tests.items():
00139 rospy.set_param(k, v)
00140
00141
00142 for k, v in rostest_tests.items():
00143 self.assert_(rospy.has_param(k))
00144 rospy.delete_param(k)
00145 self.failIf(rospy.has_param(k))
00146 self.failIf(rospy.has_param(rospy.resolve_name(k)))
00147 try:
00148 rospy.get_param(k)
00149 self.fail("get_param should fail on deleted key")
00150 except KeyError: pass
00151
00152
00153 self.failIf(set(initial_params) ^ set(rospy.get_param_names()))
00154
00155
00156 def test_set_param(self):
00157 try: rospy.set_param(None, 'foo'); self.fail("set_param(None) succeeded")
00158 except: pass
00159 try: rospy.set_param('', 'foo'); self.fail("set_param('') succeeded")
00160 except: pass
00161
00162 rostest_tests = {
00163 'spstring': "string",
00164 'spint0': 0,
00165 'spint10': 10,
00166 'spfloat0': 0.0,
00167 'spfloat10': 10.0,
00168 "spnamespace/string": "namespaced string",
00169 }
00170 initial_param_names = rospy.get_param_names()
00171 param_names = [rospy.resolve_name(k) for k in rostest_tests.keys()]
00172 for k, v in rostest_tests.items():
00173 self.failIf(rospy.has_param(k))
00174 self.failIf(rospy.has_param(rospy.resolve_name(k)))
00175 rospy.set_param(k, v)
00176 self.assert_(rospy.has_param(k))
00177 self.assert_(rospy.has_param(rospy.resolve_name(k)))
00178 self.assertEquals(v, rospy.get_param(k))
00179 self.assertEquals(v, rospy.get_param(rospy.resolve_name(k)))
00180 correct_state = set(initial_param_names + param_names)
00181 self.failIf(correct_state ^ set(rospy.get_param_names()))
00182
00183 if __name__ == '__main__':
00184 rospy.init_node(NAME)
00185 rostest.run(PKG, NAME, TestClientParamServer, sys.argv)