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
00039 PKG = 'test_rospy'
00040 NAME = 'test_param_api'
00041 import roslib; roslib.load_manifest(PKG)
00042
00043 import sys
00044 import time
00045 import unittest
00046
00047 import rospy
00048 import rostest
00049
00050 class TestClientParamApi(unittest.TestCase):
00051
00052 def test_param_api(self):
00053
00054 param_names = rospy.get_param_names()
00055 for n in ['/param1', 'param1', '~param1', 'param_int', 'param_float']:
00056 self.assert_(rospy.resolve_name(n) in param_names)
00057
00058
00059 self.assert_(rospy.has_param('/run_id'))
00060 self.assert_(rospy.has_param('/param1'))
00061 self.assert_(rospy.has_param('param1'))
00062 self.assert_(rospy.has_param('~param1'))
00063
00064
00065 self.assertEquals(None, rospy.search_param('not_param1'))
00066 self.assertEquals(rospy.resolve_name('~param1'), rospy.search_param('param1'))
00067 self.assertEquals(rospy.resolve_name('parent_param'), rospy.search_param('parent_param'))
00068 self.assertEquals("/global_param", rospy.search_param('global_param'))
00069
00070
00071 self.assertEquals('global_param1', rospy.get_param('/param1'))
00072 self.assertEquals('parent_param1', rospy.get_param('param1'))
00073 self.assertEquals('private_param1', rospy.get_param('~param1'))
00074
00075 self.assertEquals(1, rospy.get_param('param_int'))
00076 self.assertAlmostEquals(2., rospy.get_param('param_float'))
00077 self.assertEquals(True, rospy.get_param('param_bool'))
00078 self.assertEquals("hello world", rospy.get_param('param_str'))
00079
00080
00081 try:
00082 rospy.get_param('not_param1')
00083 self.fail("should have raised KeyError")
00084 except KeyError: pass
00085 self.assertEquals('parent_param1', rospy.get_param('param1', 'foo'))
00086 self.assertEquals('private_param1', rospy.get_param('~param1', 'foo'))
00087 self.assertEquals('myval', rospy.get_param('not_param1', 'myval'))
00088 self.assertEquals('myval', rospy.get_param('~not_param1', 'myval'))
00089 self.assertEquals(None, rospy.get_param('not_param1', None))
00090 self.assertEquals(None, rospy.get_param('~not_param1', None))
00091
00092
00093 vals = [ '1', 1, 1., [1, 2, 3, 4], {'a': 1, 'b': 2}]
00094 for v in vals:
00095 self.failIf(rospy.has_param("cp_param"))
00096 try:
00097 rospy.get_param('cp_param1')
00098 self.fail("should have thrown KeyError")
00099 except KeyError: pass
00100 self.assertEquals(None, rospy.get_param('cp_param', None))
00101 self.assertEquals("default", rospy.get_param('cp_param', "default"))
00102 rospy.set_param("cp_param", v)
00103 self.assert_(rospy.has_param("cp_param"))
00104 self.assertEquals(v, rospy.get_param("cp_param"))
00105 self.assertEquals(rospy.resolve_name('cp_param'), rospy.search_param('cp_param'))
00106
00107 rospy.delete_param('cp_param')
00108 self.failIf(rospy.has_param("cp_param"))
00109 self.assertEquals(None, rospy.get_param('cp_param', None))
00110 self.assertEquals("default", rospy.get_param('cp_param', "default"))
00111 self.assertEquals(None, rospy.search_param('cp_param'))
00112
00113 if __name__ == '__main__':
00114 rospy.init_node(NAME)
00115 rostest.run(PKG, NAME, TestClientParamApi, sys.argv)