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 import actionlib
00023 from std_srvs.srv import *
00024 from move_base_msgs.msg import *
00025 from control_msgs.msg import *
00026 from simple_script_server import *
00027 sss = simple_script_server()
00028
00029
00030 class TestTrigger(unittest.TestCase):
00031 def __init__(self, *args):
00032 super(TestTrigger, self).__init__(*args)
00033 rospy.init_node('test_trigger')
00034 self.cb_executed = False
00035 self.component_name = "arm"
00036 self.service_ns = "/" + self.component_name + "/driver"
00037 rospy.set_param("/script_server/"+ self.component_name + "/service_ns", self.service_ns)
00038 self.action_name = "/"+ self.component_name + "/joint_trajectory_controller/follow_joint_trajectory"
00039 rospy.set_param("/script_server/"+ self.component_name + "/action_name", self.action_name)
00040
00041 def test_init(self):
00042 rospy.Service(self.service_ns + "/init", Trigger, self.srv_cb)
00043 self.cb_executed = False
00044 handle = sss.init(self.component_name)
00045 if not self.cb_executed:
00046 self.fail('sss.init() failed. script server error_code: ' + str(handle.get_error_code()))
00047
00048 def test_stop(self):
00049 as_name = "/move_base"
00050 self.as_server = actionlib.SimpleActionServer(as_name, MoveBaseAction, execute_cb=self.action_cb)
00051 handle = sss.stop("base")
00052 if not handle.get_error_code() == 0:
00053 self.fail('sss.stop("base") failed. script server error_code: ' + str(handle.get_error_code()))
00054 handle = sss.stop("base", mode="omni")
00055 if not handle.get_error_code() == 0:
00056 self.fail('sss.stop("base", mode="omni") failed. script server error_code: ' + str(handle.get_error_code()))
00057
00058 as_name = "/move_base_diff"
00059 self.as_server = actionlib.SimpleActionServer(as_name, MoveBaseAction, execute_cb=self.action_cb)
00060 handle = sss.stop("base", mode="diff")
00061 if not handle.get_error_code() == 0:
00062 self.fail('sss.stop("base", mode="diff") failed. script server error_code: ' + str(handle.get_error_code()))
00063
00064 as_name = "/move_base_linear"
00065 self.as_server = actionlib.SimpleActionServer(as_name, MoveBaseAction, execute_cb=self.action_cb)
00066 handle = sss.stop("base", mode="linear")
00067 if not handle.get_error_code() == 0:
00068 self.fail('sss.stop("base", mode="linear") failed. script server error_code: ' + str(handle.get_error_code()))
00069
00070 self.as_server = actionlib.SimpleActionServer(self.action_name, FollowJointTrajectoryAction, execute_cb=self.action_cb)
00071 handle = sss.stop(self.component_name)
00072 if not handle.get_error_code() == 0:
00073 self.fail('sss.stop("arm") failed. script server error_code: ' + str(handle.get_error_code()))
00074
00075 def test_recover(self):
00076 rospy.Service(self.service_ns + "/recover", Trigger, self.srv_cb)
00077 self.cb_executed = False
00078 handle = sss.recover(self.component_name)
00079 if not self.cb_executed:
00080 self.fail('sss.recover() failed. script server error_code: ' + str(handle.get_error_code()))
00081
00082 def test_halt(self):
00083 rospy.Service(self.service_ns + "/halt", Trigger, self.srv_cb)
00084 self.cb_executed = False
00085 handle = sss.halt(self.component_name)
00086 if not self.cb_executed:
00087 self.fail('sss.halt() failed. script server error_code: ' + str(handle.get_error_code()))
00088
00089 def srv_cb(self,req):
00090 self.cb_executed = True
00091 res = TriggerResponse()
00092 res.success = True
00093 return res
00094
00095 def action_cb(self, goal):
00096 while not self.as_server.is_preempt_requested():
00097 rospy.Rate(1).sleep()
00098 self.as_server.set_preempted()
00099
00100 if __name__ == '__main__':
00101 import rostest
00102 rostest.rosrun('cob_script_server', 'trigger', TestTrigger)