Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 import sys
00019 import unittest
00020
00021 import rospy
00022 from simple_script_server import *
00023 sss = simple_script_server()
00024
00025
00026 class TestMove(unittest.TestCase):
00027 def __init__(self, *args):
00028 super(TestMove, self).__init__(*args)
00029 rospy.init_node('test_move')
00030 self.cb_executed = False
00031
00032
00033 def test_move_base(self):
00034 self.move_base()
00035
00036 def test_move_base_omni(self):
00037 self.move_base(mode="omni")
00038
00039 def test_move_base_diff(self):
00040 self.move_base(mode="diff")
00041
00042 def test_move_base_linear(self):
00043 self.move_base(mode="linear")
00044
00045 def move_base(self,mode=None):
00046 if mode == None or mode == "" or mode == "omni":
00047 as_name = "/move_base"
00048 else:
00049 as_name = "/move_base_" + mode
00050 self.as_server = actionlib.SimpleActionServer(as_name, MoveBaseAction, execute_cb=self.base_cb, auto_start=False)
00051 self.as_server.start()
00052 self.cb_executed = False
00053 handle = sss.move("base",[0,0,0],mode=mode)
00054 if not self.cb_executed:
00055 self.fail('Action Server not called. script server error_code: ' + str(handle.get_error_code()))
00056
00057 def base_cb(self, goal):
00058 self.cb_executed = True
00059 result = MoveBaseResult()
00060 self.as_server.set_succeeded(result)
00061
00062
00063 def test_move_traj(self):
00064 component_name = "arm"
00065 as_name = "/" + component_name + "/joint_trajectory_controller/follow_joint_trajectory"
00066 self.as_server = actionlib.SimpleActionServer(as_name, FollowJointTrajectoryAction, execute_cb=self.traj_cb, auto_start=False)
00067 self.as_server.start()
00068 self.cb_executed = False
00069 handle = sss.move(component_name,[[0,0,0,0,0,0,0]])
00070 if not self.cb_executed:
00071 self.fail('Action Server not called. script server error_code: ' + str(handle.get_error_code()))
00072
00073 def traj_cb(self, goal):
00074 self.cb_executed = True
00075 result = FollowJointTrajectoryResult()
00076 self.as_server.set_succeeded(result)
00077
00078 if __name__ == '__main__':
00079 import rostest
00080 rostest.rosrun('cob_script_server', 'move', TestMove)