test_action_interface.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #   http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 
00017 
00018 import sys
00019 import unittest
00020 
00021 import rospy
00022 import actionlib
00023 from simple_script_server import *
00024 
00025 ## 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).
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" # testing for component arm
00033 
00034         # test trigger commands
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         # test move base commands
00075 #       def test_move_base(self):
00076 #               goal = ScriptGoal()
00077 #               goal.function_name = "move"
00078 #               goal.component_name = "base"
00079 #               goal.parameter_name = [0,0,0]
00080 #               self.script_action_move_base(goal)
00081 
00082 #       def test_move_base_omni(self): #FIXME fails because client is already in DONE state (mode="" and mode="omni" is the same)
00083 #               goal = ScriptGoal()
00084 #               goal.function_name = "move"
00085 #               goal.component_name = "base"
00086 #               goal.parameter_name = "home"
00087 #               goal.mode = "omni"
00088 #               self.script_action_move_base(goal)
00089 
00090 #       def test_move_base_diff(self):
00091 #               goal = ScriptGoal()
00092 #               goal.function_name = "move"
00093 #               goal.component_name = "base"
00094 #               goal.parameter_name = [0,0,0]
00095 #               goal.mode = "diff"
00096 #               self.script_action_move_base(goal)
00097 
00098 #       def test_move_base_linear(self):
00099 #               goal = ScriptGoal()
00100 #               goal.function_name = "move"
00101 #               goal.component_name = "base"
00102 #               goal.parameter_name = [0,0,0]
00103 #               goal.mode = "linear"
00104 #               self.script_action_move_base(goal)
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                 #if not client.wait_for_result(rospy.Duration(10)):
00122                 #       self.fail('Action didnt give a result before timeout')
00123 
00124                 #if not self.cb_executed:
00125                 #       self.fail('Action Server not called. script server error_code: ' + str(client.get_result().error_code))
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         # test move trajectory commands
00133         #TODO
00134 
00135 if __name__ == '__main__':
00136         import rostest
00137         rostest.rosrun('cob_script_server', 'action_interface', TestActionInterface)


cob_script_server
Author(s): Florian Weisshardt
autogenerated on Sun Jun 9 2019 20:20:12