$search
00001 #!/usr/bin/env python 00002 00003 PKG="cob_script_server" 00004 import roslib; roslib.load_manifest(PKG) 00005 00006 import sys 00007 import unittest 00008 00009 from simple_script_server import * 00010 sss = simple_script_server() 00011 00012 ## This test checks the correct call to commands from the cob_script_server. This does not cover the execution of the commands (this shoud be checked in the package where the calls refer to). 00013 class TestMove(unittest.TestCase): 00014 def __init__(self, *args): 00015 super(TestMove, self).__init__(*args) 00016 rospy.init_node('test_move') 00017 self.cb_executed = False 00018 00019 # test move base commands 00020 def test_move_base(self): 00021 self.move_base() 00022 00023 # def test_move_base_omni(self): #FIXME fails because client is already in DONE state (mode="" and mode="omni" is the same) 00024 # self.move_base(mode="omni") 00025 00026 def test_move_base_diff(self): 00027 self.move_base(mode="diff") 00028 00029 def test_move_base_linear(self): 00030 self.move_base(mode="linear") 00031 00032 def move_base(self,mode=None): 00033 if mode == None or mode == "" or mode == "omni": 00034 as_name = "/move_base" 00035 else: 00036 as_name = "/move_base_" + mode 00037 self.as_server = actionlib.SimpleActionServer(as_name, MoveBaseAction, execute_cb=self.base_cb, auto_start=False) 00038 self.as_server.start() 00039 self.cb_executed = False 00040 handle = sss.move("base",[0,0,0],mode=mode) 00041 if not self.cb_executed: 00042 self.fail('Action Server not called. script server error_code: ' + str(handle.get_error_code())) 00043 00044 def base_cb(self, goal): 00045 self.cb_executed = True 00046 result = MoveBaseResult() 00047 self.as_server.set_succeeded(result) 00048 00049 # test move trajectory commands 00050 def test_move_traj(self): 00051 component_name = "arm" # testing for component arm 00052 #as_name = "/" + component_name + "_controller/joint_trajectory_action" 00053 #self.as_server = actionlib.SimpleActionServer(as_name, JointTrajectoryAction, execute_cb=self.traj_cb, auto_start=False) 00054 as_name = "/" + component_name + "_controller/follow_joint_trajectory" 00055 self.as_server = actionlib.SimpleActionServer(as_name, FollowJointTrajectoryAction, execute_cb=self.traj_cb, auto_start=False) 00056 self.as_server.start() 00057 self.cb_executed = False 00058 handle = sss.move(component_name,[[0,0,0,0,0,0,0]]) 00059 if not self.cb_executed: 00060 self.fail('Action Server not called. script server error_code: ' + str(handle.get_error_code())) 00061 00062 def traj_cb(self, goal): 00063 self.cb_executed = True 00064 #result = JointTrajectoryResult() 00065 result = FollowJointTrajectoryResult() 00066 self.as_server.set_succeeded(result) 00067 00068 # move cartesian 00069 # def test_move_cart(self): 00070 # component_name = "arm" # testing for component arm 00071 # as_name = "/" + component_name + "_controller/move_cart" 00072 # self.as_server = actionlib.SimpleActionServer(as_name, MoveCartAction, execute_cb=self.cart_cb, auto_start=False) 00073 # self.as_server.start() 00074 # self.cb_executed = False 00075 # sss.move(component_name,["base_link",[0,0,0],[0,0,0]]) 00076 # if not self.cb_executed: 00077 # self.fail('Action Server not called') 00078 00079 # def cart_cb(self, goal): 00080 # self.cb_executed = True 00081 # result = MoveCartResult() 00082 # self.as_server.set_succeeded(result) 00083 00084 # move planned 00085 # def test_move_planned(self): 00086 # component_name = "arm" # testing for component arm 00087 # as_name = "/" + component_name + "_controller/move_cart" 00088 # self.as_server = actionlib.SimpleActionServer(as_name, MoveCartAction, execute_cb=self.planned_cb, auto_start=False) 00089 # self.as_server.start() 00090 # self.cb_executed = False 00091 # sss.move(component_name,["base_link",[0,0,0],[0,0,0]]) 00092 # if not self.cb_executed: 00093 # self.fail('Action Server not called') 00094 00095 # def planned_cb(self, goal): 00096 # self.cb_executed = True 00097 # result = MoveCartResult() 00098 # self.as_server.set_succeeded(result) 00099 00100 if __name__ == '__main__': 00101 import rostest 00102 rostest.rosrun(PKG, 'move', TestMove)