test_move.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 from simple_script_server import *
00023 sss = simple_script_server()
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 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         # test move base commands
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         # test move trajectory commands
00063         def test_move_traj(self):
00064                 component_name = "arm" # testing for component 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)


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