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