37 NAME =
'test_rospy_client_param_server' 48 return [p
for p
in params
if not p.startswith(
'/roslaunch')
and p
not in [
'/run_id',
'/rosdistro',
'/rosversion']]
61 try: rospy.get_param(
None); self.fail(
"get_param(None) succeeded")
63 try: rospy.get_param(
''); self.fail(
"get_param('') succeeded")
66 try: rospy.get_param(
'non-existent'); self.fail(
"get_param('non-existent') succeeded")
68 try: rospy.has_param(
None,
'foo'); self.fail(
"has_param(None) succeeded")
70 try: rospy.has_param(
''); self.fail(
"has_param('') succeeded")
73 self.failIf(rospy.has_param(
'non-existent'),
"has_param('non-existent') succeeded")
82 "namespace/string":
"namespaced string",
84 param_names = [rospy.resolve_name(k)
for k
in rostest_tests.keys()]
88 self.failIf(diff, diff)
91 for k, v
in rostest_tests.items():
92 self.assert_(rospy.has_param(k))
93 self.assert_(rospy.has_param(rospy.resolve_name(k)))
94 if not type(v) == float:
95 self.assertEqual(v, rospy.get_param(k))
96 self.assertEqual(v, rospy.get_param(rospy.resolve_name(k)))
98 self.assertAlmostEqual(v, rospy.get_param(k), 1)
99 self.assertAlmostEqual(v, rospy.get_param(rospy.resolve_name(k)), 1)
103 orig_caller_id = rospy.names.get_caller_id()
105 rospy.names._set_caller_id(
'/global_node')
107 self.assertEquals(
None, rospy.search_param(
'search_param'))
108 rospy.set_param(
'/search_param', 1)
109 self.assertEquals(
'/search_param', rospy.search_param(
'search_param'))
111 rospy.names._set_caller_id(
'/level1/level2/relative_node')
112 self.assertEquals(
'/search_param', rospy.search_param(
'search_param'))
113 rospy.set_param(
'/level1/search_param', 2)
114 self.assertEquals(
'/level1/search_param', rospy.search_param(
'search_param'))
115 rospy.set_param(
'~search_param', 3)
117 self.assertEquals(
'/level1/level2/relative_node/search_param', rospy.search_param(
'search_param'))
120 rospy.names._set_caller_id(orig_caller_id)
123 try: rospy.delete_param(
None); self.fail(
"delete_param(None) succeeded")
125 try: rospy.delete_param(
''); self.fail(
"delete_param('') succeeded")
129 'dpstring':
"string",
134 "dpnamespace/string":
"namespaced string",
136 initial_params = rospy.get_param_names()
138 for k, v
in rostest_tests.items():
139 rospy.set_param(k, v)
142 for k, v
in rostest_tests.items():
143 self.assert_(rospy.has_param(k))
144 rospy.delete_param(k)
145 self.failIf(rospy.has_param(k))
146 self.failIf(rospy.has_param(rospy.resolve_name(k)))
149 self.fail(
"get_param should fail on deleted key")
150 except KeyError:
pass 153 self.failIf(set(initial_params) ^ set(rospy.get_param_names()))
157 try: rospy.set_param(
None,
'foo'); self.fail(
"set_param(None) succeeded")
159 try: rospy.set_param(
'',
'foo'); self.fail(
"set_param('') succeeded")
163 'spstring':
"string",
168 "spnamespace/string":
"namespaced string",
170 initial_param_names = rospy.get_param_names()
171 param_names = [rospy.resolve_name(k)
for k
in rostest_tests.keys()]
172 for k, v
in rostest_tests.items():
173 self.failIf(rospy.has_param(k))
174 self.failIf(rospy.has_param(rospy.resolve_name(k)))
175 rospy.set_param(k, v)
176 self.assert_(rospy.has_param(k))
177 self.assert_(rospy.has_param(rospy.resolve_name(k)))
178 self.assertEquals(v, rospy.get_param(k))
179 self.assertEquals(v, rospy.get_param(rospy.resolve_name(k)))
180 correct_state = set(initial_param_names + param_names)
181 self.failIf(correct_state ^ set(rospy.get_param_names()))
183 if __name__ ==
'__main__':
184 rospy.init_node(NAME)
185 rostest.run(PKG, NAME, TestClientParamServer, sys.argv)
def test_set_param(self)
test set_param separately
def test_delete_param(self)
def test_search_param(self)
def test_param_filter(params)
def test_get_has_param(self)
test get/has param against state initialized from rostest script
Test the rospy.client parameter server API: