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 simple_script_server import *
00024
00025
00026 class TestActionInterface(unittest.TestCase):
00027 def __init__(self, *args):
00028 super(TestActionInterface, self).__init__(*args)
00029 rospy.init_node('test_action_interface')
00030 self.cb_executed = False
00031 self.cb_move_executed = False
00032 self.component_name = "arm"
00033
00034
00035 def test_init(self):
00036 goal = ScriptGoal()
00037 goal.function_name = "init"
00038 goal.component_name = "arm"
00039 self.script_action_trigger(goal)
00040
00041 def test_stop(self):
00042 goal = ScriptGoal()
00043 goal.function_name = "stop"
00044 goal.component_name = "arm"
00045 self.script_action_trigger(goal)
00046
00047 def test_recover(self):
00048 goal = ScriptGoal()
00049 goal.function_name = "recover"
00050 goal.component_name = "arm"
00051 self.script_action_trigger(goal)
00052
00053 def script_action_trigger(self,goal):
00054 rospy.Service("/" + goal.component_name + "_controller/" + goal.function_name, Trigger, self.cb)
00055 self.cb_executed = False
00056
00057 client = actionlib.SimpleActionClient('/script_server', ScriptAction)
00058
00059 if not client.wait_for_server(rospy.Duration(10)):
00060 self.fail('Action server not ready')
00061 client.send_goal(goal)
00062 if not client.wait_for_result(rospy.Duration(10)):
00063 self.fail('Action didnt give a result before timeout')
00064
00065 if not self.cb_executed:
00066 self.fail('Service Server not called. script server error_code: ' + str(client.get_result().error_code))
00067
00068 def cb(self,req):
00069 self.cb_executed = True
00070 res = TriggerResponse()
00071 res.success = True
00072 return res
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
00101
00102
00103
00104
00105
00106 def script_action_move_base(self,goal):
00107 if goal.mode == None or goal.mode == "" or goal.mode == "omni":
00108 as_name = "/move_base"
00109 else:
00110 as_name = "/move_base_" + goal.mode
00111 self.as_server = actionlib.SimpleActionServer(as_name, MoveBaseAction, execute_cb=self.base_cb, auto_start=False)
00112 self.as_server.start()
00113
00114 client = actionlib.SimpleActionClient('/script_server', ScriptAction)
00115
00116 self.cb_move_executed = False
00117 if not client.wait_for_server(rospy.Duration(10)):
00118 self.fail('Action server not ready')
00119 client.send_goal(goal)
00120 client.wait_for_result(rospy.Duration(10))
00121
00122
00123
00124
00125
00126
00127 def base_cb(self, goal):
00128 self.cb_move_executed = True
00129 result = MoveBaseResult()
00130 self.as_server.set_succeeded(result)
00131
00132
00133
00134
00135 if __name__ == '__main__':
00136 import rostest
00137 rostest.rosrun('cob_script_server', 'action_interface', TestActionInterface)