35 from actionlib
import SimpleActionClient
36 from actionlib_msgs.msg
import GoalStatus
37 from actionlib.msg
import TestRequestAction, TestRequestGoal
45 self.assert_(self.client.wait_for_server(self.
default_wait))
48 goal = TestRequestGoal(terminate_status=TestRequestGoal.TERMINATE_SUCCESS,
50 self.client.send_goal(goal)
53 self.assertEqual(GoalStatus.SUCCEEDED, self.client.get_state())
54 self.assertEqual(42, self.client.get_result().the_result)
57 goal = TestRequestGoal(terminate_status=TestRequestGoal.TERMINATE_ABORTED,
59 self.client.send_goal(goal)
62 self.assertEqual(GoalStatus.ABORTED, self.client.get_state())
63 self.assertEqual(42, self.client.get_result().the_result)
66 goal = TestRequestGoal(terminate_status=TestRequestGoal.TERMINATE_SUCCESS,
67 delay_terminate=rospy.Duration(100000),
69 self.client.send_goal(goal)
73 while rospy.Time.now() < timeout_time:
74 if (self.client.get_state() != GoalStatus.PENDING):
76 self.client.cancel_goal()
79 self.assertEqual(GoalStatus.PREEMPTED, self.client.get_state())
80 self.assertEqual(42, self.client.get_result().the_result)
84 goal = TestRequestGoal(terminate_status=TestRequestGoal.TERMINATE_DROP,
86 self.client.send_goal(goal)
89 self.assertEqual(GoalStatus.ABORTED, self.client.get_state())
90 self.assertEqual(0, self.client.get_result().the_result)
94 goal = TestRequestGoal(terminate_status=TestRequestGoal.TERMINATE_EXCEPTION,
96 self.client.send_goal(goal)
99 self.assertEqual(GoalStatus.ABORTED, self.client.get_state())
100 self.assertEqual(0, self.client.get_result().the_result)
103 goal = TestRequestGoal(terminate_status=TestRequestGoal.TERMINATE_SUCCESS,
104 delay_terminate=rospy.Duration(2.0),
107 self.client.send_goal(goal)
111 while rospy.Time.now() < timeout_time:
112 if (self.client.get_state() != GoalStatus.PENDING):
114 self.client.cancel_goal()
118 self.assertEqual(GoalStatus.SUCCEEDED, self.client.get_state())
119 self.assertEqual(42, self.client.get_result().the_result)
122 goal = TestRequestGoal(terminate_status=TestRequestGoal.TERMINATE_LOSE,
124 self.client.send_goal(goal)
127 self.assertEqual(GoalStatus.LOST, self.client.get_state())
143 if __name__ ==
'__main__':
144 rospy.init_node(
"exercise_simple_server")
145 rostest.run(PKG,
'exercise_simple_server', SimpleExerciser, sys.argv)
def test_just_succeed(self)
def test_just_abort(self)
A Simple client implementation of the ActionInterface which supports only one goal at a time...
def test_ignore_cancel_and_succeed(self)
def test_just_preempt(self)