38 NAME =
'test_param_api' 51 param_names = rospy.get_param_names()
52 for n
in [
'/param1',
'param1',
'~param1',
'param_int',
'param_float']:
53 self.assert_(rospy.resolve_name(n)
in param_names)
56 self.assert_(rospy.has_param(
'/run_id'))
57 self.assert_(rospy.has_param(
'/param1'))
58 self.assert_(rospy.has_param(
'param1'))
59 self.assert_(rospy.has_param(
'~param1'))
62 self.assertEquals(
None, rospy.search_param(
'not_param1'))
63 self.assertEquals(rospy.resolve_name(
'~param1'), rospy.search_param(
'param1'))
64 self.assertEquals(rospy.resolve_name(
'parent_param'), rospy.search_param(
'parent_param'))
65 self.assertEquals(
"/global_param", rospy.search_param(
'global_param'))
68 self.assertEquals(
'global_param1', rospy.get_param(
'/param1'))
69 self.assertEquals(
'parent_param1', rospy.get_param(
'param1'))
70 self.assertEquals(
'private_param1', rospy.get_param(
'~param1'))
72 self.assertEquals(1, rospy.get_param(
'param_int'))
73 self.assertAlmostEquals(2., rospy.get_param(
'param_float'))
74 self.assertEquals(
True, rospy.get_param(
'param_bool'))
75 self.assertEquals(
"hello world", rospy.get_param(
'param_str'))
79 rospy.get_param(
'not_param1')
80 self.fail(
"should have raised KeyError")
82 self.assertEquals(
'parent_param1', rospy.get_param(
'param1',
'foo'))
83 self.assertEquals(
'private_param1', rospy.get_param(
'~param1',
'foo'))
84 self.assertEquals(
'myval', rospy.get_param(
'not_param1',
'myval'))
85 self.assertEquals(
'myval', rospy.get_param(
'~not_param1',
'myval'))
86 self.assertEquals(
None, rospy.get_param(
'not_param1',
None))
87 self.assertEquals(
None, rospy.get_param(
'~not_param1',
None))
90 vals = [
'1', 1, 1., [1, 2, 3, 4], {
'a': 1,
'b': 2}]
92 self.failIf(rospy.has_param(
"cp_param"))
94 rospy.get_param(
'cp_param1')
95 self.fail(
"should have thrown KeyError")
97 self.assertEquals(
None, rospy.get_param(
'cp_param',
None))
98 self.assertEquals(
"default", rospy.get_param(
'cp_param',
"default"))
99 rospy.set_param(
"cp_param", v)
100 self.assert_(rospy.has_param(
"cp_param"))
101 self.assertEquals(v, rospy.get_param(
"cp_param"))
102 self.assertEquals(rospy.resolve_name(
'cp_param'), rospy.search_param(
'cp_param'))
104 rospy.delete_param(
'cp_param')
105 self.failIf(rospy.has_param(
"cp_param"))
106 self.assertEquals(
None, rospy.get_param(
'cp_param',
None))
107 self.assertEquals(
"default", rospy.get_param(
'cp_param',
"default"))
108 self.assertEquals(
None, rospy.search_param(
'cp_param'))
110 if __name__ ==
'__main__':
111 rospy.init_node(NAME)
112 rostest.run(PKG, NAME, TestClientParamApi, sys.argv)