exercise_simple_client.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 # Copyright (c) 2009, Willow Garage, Inc.
3 # All rights reserved.
4 #
5 # Redistribution and use in source and binary forms, with or without
6 # modification, are permitted provided that the following conditions are met:
7 #
8 # * Redistributions of source code must retain the above copyright
9 # notice, this list of conditions and the following disclaimer.
10 # * Redistributions in binary form must reproduce the above copyright
11 # notice, this list of conditions and the following disclaimer in the
12 # documentation and/or other materials provided with the distribution.
13 # * Neither the name of the Willow Garage, Inc. nor the names of its
14 # contributors may be used to endorse or promote products derived from
15 # this software without specific prior written permission.
16 #
17 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 # POSSIBILITY OF SUCH DAMAGE.
28 
29 PKG = 'actionlib'
30 
31 import sys
32 import unittest
33 import rospy
34 import rostest
35 from actionlib import SimpleActionClient
36 from actionlib_msgs.msg import GoalStatus
37 from actionlib.msg import TestRequestAction, TestRequestGoal
38 
39 
40 class SimpleExerciser(unittest.TestCase):
41 
42  def setUp(self):
43  self.default_wait = rospy.Duration(60.0)
44  self.client = SimpleActionClient('test_request_action', TestRequestAction)
45  self.assert_(self.client.wait_for_server(self.default_wait))
46 
47  def test_just_succeed(self):
48  goal = TestRequestGoal(terminate_status=TestRequestGoal.TERMINATE_SUCCESS,
49  the_result=42)
50  self.client.send_goal(goal)
51  self.client.wait_for_result(self.default_wait)
52 
53  self.assertEqual(GoalStatus.SUCCEEDED, self.client.get_state())
54  self.assertEqual(42, self.client.get_result().the_result)
55 
56  def test_just_abort(self):
57  goal = TestRequestGoal(terminate_status=TestRequestGoal.TERMINATE_ABORTED,
58  the_result=42)
59  self.client.send_goal(goal)
60  self.client.wait_for_result(self.default_wait)
61 
62  self.assertEqual(GoalStatus.ABORTED, self.client.get_state())
63  self.assertEqual(42, self.client.get_result().the_result)
64 
65  def test_just_preempt(self):
66  goal = TestRequestGoal(terminate_status=TestRequestGoal.TERMINATE_SUCCESS,
67  delay_terminate=rospy.Duration(100000),
68  the_result=42)
69  self.client.send_goal(goal)
70 
71  # Ensure that the action server got the goal, before continuing
72  timeout_time = rospy.Time.now() + self.default_wait
73  while rospy.Time.now() < timeout_time:
74  if (self.client.get_state() != GoalStatus.PENDING):
75  break
76  self.client.cancel_goal()
77 
78  self.client.wait_for_result(self.default_wait)
79  self.assertEqual(GoalStatus.PREEMPTED, self.client.get_state())
80  self.assertEqual(42, self.client.get_result().the_result)
81 
82  # Should print out errors about not setting a terminal status in the action server.
83  def test_drop(self):
84  goal = TestRequestGoal(terminate_status=TestRequestGoal.TERMINATE_DROP,
85  the_result=42)
86  self.client.send_goal(goal)
87  self.client.wait_for_result(self.default_wait)
88 
89  self.assertEqual(GoalStatus.ABORTED, self.client.get_state())
90  self.assertEqual(0, self.client.get_result().the_result)
91 
92  # Should print out errors about throwing an exception
93  def test_exception(self):
94  goal = TestRequestGoal(terminate_status=TestRequestGoal.TERMINATE_EXCEPTION,
95  the_result=42)
96  self.client.send_goal(goal)
97  self.client.wait_for_result(self.default_wait)
98 
99  self.assertEqual(GoalStatus.ABORTED, self.client.get_state())
100  self.assertEqual(0, self.client.get_result().the_result)
101 
103  goal = TestRequestGoal(terminate_status=TestRequestGoal.TERMINATE_SUCCESS,
104  delay_terminate=rospy.Duration(2.0),
105  ignore_cancel=True,
106  the_result=42)
107  self.client.send_goal(goal)
108 
109  # Ensure that the action server got the goal, before continuing
110  timeout_time = rospy.Time.now() + self.default_wait
111  while rospy.Time.now() < timeout_time:
112  if (self.client.get_state() != GoalStatus.PENDING):
113  break
114  self.client.cancel_goal()
115 
116  self.client.wait_for_result(self.default_wait)
117 
118  self.assertEqual(GoalStatus.SUCCEEDED, self.client.get_state())
119  self.assertEqual(42, self.client.get_result().the_result)
120 
121  def test_lose(self):
122  goal = TestRequestGoal(terminate_status=TestRequestGoal.TERMINATE_LOSE,
123  the_result=42)
124  self.client.send_goal(goal)
125  self.client.wait_for_result(self.default_wait)
126 
127  self.assertEqual(GoalStatus.LOST, self.client.get_state())
128 
129  # test_freeze_server has been removed, as it is undecided what should happen
130  # when the action server disappears.
131  #
132  # # def test_freeze_server(self):
133  # # goal = TestRequestGoal(terminate_status = TestRequestGoal.TERMINATE_SUCCESS,
134  # # the_result = 42,
135  # # pause_status = rospy.Duration(10.0))
136  # # self.client.send_goal(goal)
137  # # self.client.wait_for_result(rospy.Duration(13.0))
138  # #
139  # # self.assertEqual(GoalStatus.LOST, self.client.get_state())
140  #
141 
142 
143 if __name__ == '__main__':
144  rospy.init_node("exercise_simple_server")
145  rostest.run(PKG, 'exercise_simple_server', SimpleExerciser, sys.argv)
A Simple client implementation of the ActionInterface which supports only one goal at a time...


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Feb 18 2019 03:59:59