Go to the documentation of this file.00001
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
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
00020 def test_move_base(self):
00021 self.move_base()
00022
00023
00024
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
00050 def test_move_traj(self):
00051 component_name = "arm"
00052
00053
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
00065 result = FollowJointTrajectoryResult()
00066 self.as_server.set_succeeded(result)
00067
00068
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084
00085
00086
00087
00088
00089
00090
00091
00092
00093
00094
00095
00096
00097
00098
00099
00100 if __name__ == '__main__':
00101 import rostest
00102 rostest.rosrun(PKG, 'move', TestMove)