test_move.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 
18 import sys
19 import unittest
20 
21 import rospy
22 import actionlib
23 from control_msgs.msg import FollowJointTrajectoryAction, FollowJointTrajectoryResult
24 from move_base_msgs.msg import MoveBaseAction, MoveBaseResult
25 from simple_script_server import *
27 
28 ## 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).
29 class TestMove(unittest.TestCase):
30  def __init__(self, *args):
31  super(TestMove, self).__init__(*args)
32  rospy.init_node('test_move')
33  self.cb_executed = False
34 
35  # test move base commands
36  def test_move_base(self):
37  self.move_base()
38 
40  self.move_base(mode="omni")
41 
43  self.move_base(mode="diff")
44 
46  self.move_base(mode="linear")
47 
48  def move_base(self,mode=None):
49  if mode == None or mode == "" or mode == "omni":
50  as_name = "/move_base"
51  else:
52  as_name = "/move_base_" + mode
53  self.as_server = actionlib.SimpleActionServer(as_name, MoveBaseAction, execute_cb=self.base_cb, auto_start=False)
54  self.as_server.start()
55  self.cb_executed = False
56  handle = sss.move("base",[0,0,0],mode=mode)
57  if not self.cb_executed:
58  self.fail('Action Server not called. script server error_code: ' + str(handle.get_error_code()))
59 
60  def base_cb(self, goal):
61  self.cb_executed = True
62  result = MoveBaseResult()
63  self.as_server.set_succeeded(result)
64 
65  # test move trajectory commands
66  def test_move_traj(self):
67  component_name = "arm" # testing for component arm
68  as_name = "/" + component_name + "/joint_trajectory_controller/follow_joint_trajectory"
69  self.as_server = actionlib.SimpleActionServer(as_name, FollowJointTrajectoryAction, execute_cb=self.traj_cb, auto_start=False)
70  self.as_server.start()
71  self.cb_executed = False
72  handle = sss.move(component_name,[[0,0,0,0,0,0,0]])
73  if not self.cb_executed:
74  self.fail('Action Server not called. script server error_code: ' + str(handle.get_error_code()))
75 
76  def traj_cb(self, goal):
77  self.cb_executed = True
78  result = FollowJointTrajectoryResult()
79  self.as_server.set_succeeded(result)
80 
81 if __name__ == '__main__':
82  import rostest
83  rostest.rosrun('cob_script_server', 'move', TestMove)
def test_move_base_omni(self)
Definition: test_move.py:39
def test_move_traj(self)
Definition: test_move.py:66
def traj_cb(self, goal)
Definition: test_move.py:76
def base_cb(self, goal)
Definition: test_move.py:60
This test checks the correct call to commands from the cob_script_server.
Definition: test_move.py:29
def move_base(self, mode=None)
Definition: test_move.py:48
def __init__(self, args)
Definition: test_move.py:30
def test_move_base(self)
Definition: test_move.py:36
def test_move_base_diff(self)
Definition: test_move.py:42
def test_move_base_linear(self)
Definition: test_move.py:45


cob_script_server
Author(s): Florian Weisshardt
autogenerated on Wed Apr 7 2021 03:03:06