33 from actionlib_msgs.msg
import GoalStatus
36 from actionlib
import ActionClient
37 from actionlib.msg
import TestAction, TestGoal
45 self.assertTrue(client.wait_for_action_server_to_start(rospy.Duration(2.0)),
46 'Could not connect to the action server')
49 client.send_goal(goal)
50 self.assertTrue(client.wait_for_goal_to_finish(rospy.Duration(2.0)),
52 self.assertEqual(GoalStatus.SUCCEEDED, client.get_terminal_state())
53 self.assertEqual(GoalStatus.SUCCEEDED, client.get_state())
56 client.send_goal(goal)
57 self.assertTrue(client.wait_for_goal_to_finish(rospy.Duration(10.0)),
59 self.assertEqual(GoalStatus.ABORTED, client.get_terminal_state())
60 self.assertEqual(GoalStatus.ABORTED, client.get_state())
64 self.assertTrue(client.wait_for_server(rospy.Duration(2.0)),
65 'Could not connect to the action server')
67 goal_work = TestGoal(4)
68 goal_abort = TestGoal(6)
69 goal_feedback = TestGoal(8)
71 g1 = client.send_goal(goal_work)
72 g2 = client.send_goal(goal_work)
73 g3 = client.send_goal(goal_work)
74 g4 = client.send_goal(goal_work)
77 self.assertEqual(g1.get_goal_status(), GoalStatus.ACTIVE)
78 self.assertEqual(g2.get_goal_status(), GoalStatus.ACTIVE,
"Should be active")
79 self.assertEqual(g3.get_goal_status(), GoalStatus.ACTIVE,
"Should be active")
80 self.assertEqual(g4.get_goal_status(), GoalStatus.ACTIVE,
"Should be active")
82 g5 = client.send_goal(goal_abort)
84 self.assertEqual(g5.get_goal_status(), GoalStatus.SUCCEEDED,
"Should be done")
86 self.assertEqual(g1.get_goal_status(), GoalStatus.ABORTED,
"Should be aborted")
87 self.assertEqual(g2.get_goal_status(), GoalStatus.ABORTED,
"Should be aborted")
88 self.assertEqual(g3.get_goal_status(), GoalStatus.ABORTED,
"Should be aborted")
89 self.assertEqual(g4.get_goal_status(), GoalStatus.ABORTED,
"Should be aborted")
93 self.assertTrue(client.wait_for_server(rospy.Duration(2.0)),
94 'Could not connect to the action server')
96 goal_work = TestGoal(4)
97 goal_abort = TestGoal(6)
98 goal_feedback = TestGoal(7)
100 rospy.logwarn(
"This is a hacky way to associate goals with feedback")
103 def update_feedback(id, g, f):
106 g1 = client.send_goal(goal_work, feedback_cb=
lambda g, f: update_feedback(0, g, f))
107 g2 = client.send_goal(goal_work, feedback_cb=
lambda g, f: update_feedback(1, g, f))
108 g3 = client.send_goal(goal_work, feedback_cb=
lambda g, f: update_feedback(2, g, f))
109 g4 = client.send_goal(goal_work, feedback_cb=
lambda g, f: update_feedback(3, g, f))
112 self.assertEqual(g1.get_goal_status(), GoalStatus.ACTIVE,
"Should be active")
113 self.assertEqual(g2.get_goal_status(), GoalStatus.ACTIVE,
"Should be active")
114 self.assertEqual(g3.get_goal_status(), GoalStatus.ACTIVE,
"Should be active")
115 self.assertEqual(g4.get_goal_status(), GoalStatus.ACTIVE,
"Should be active")
117 g5 = client.send_goal(goal_feedback)
119 self.assertEqual(g5.get_goal_status(), GoalStatus.SUCCEEDED,
"Should be done")
121 self.assertEqual(g1.get_goal_status(), GoalStatus.ACTIVE)
122 self.assertEqual(feedback[0].feedback, 4)
123 self.assertEqual(g2.get_goal_status(), GoalStatus.ACTIVE)
124 self.assertEqual(feedback[1].feedback, 3)
125 self.assertEqual(g3.get_goal_status(), GoalStatus.ACTIVE)
126 self.assertEqual(feedback[2].feedback, 2)
127 self.assertEqual(g4.get_goal_status(), GoalStatus.ACTIVE)
128 self.assertEqual(feedback[3].feedback, 1)
130 g6 = client.send_goal(goal_abort)
135 self.assertTrue(client.wait_for_server(rospy.Duration(2.0)),
136 'Could not connect to the action server')
138 goal_work = TestGoal(4)
139 goal_abort = TestGoal(6)
140 goal_result = TestGoal(8)
142 rospy.logwarn(
"This is a hacky way to associate goals with feedback")
144 g1 = client.send_goal(goal_work)
145 g2 = client.send_goal(goal_work)
146 g3 = client.send_goal(goal_work)
147 g4 = client.send_goal(goal_work)
150 self.assertEqual(g1.get_goal_status(), GoalStatus.ACTIVE,
"Should be active")
151 self.assertEqual(g2.get_goal_status(), GoalStatus.ACTIVE,
"Should be active")
152 self.assertEqual(g3.get_goal_status(), GoalStatus.ACTIVE,
"Should be active")
153 self.assertEqual(g4.get_goal_status(), GoalStatus.ACTIVE,
"Should be active")
155 g5 = client.send_goal(goal_result)
157 self.assertEqual(g5.get_goal_status(), GoalStatus.SUCCEEDED,
"Should be done")
159 self.assertEqual(g1.get_goal_status(), GoalStatus.SUCCEEDED)
160 self.assertEqual(g1.get_result().result, 4)
161 self.assertEqual(g2.get_goal_status(), GoalStatus.ABORTED)
162 self.assertEqual(g2.get_result().result, 3)
163 self.assertEqual(g3.get_goal_status(), GoalStatus.SUCCEEDED)
164 self.assertEqual(g3.get_result().result, 2)
165 self.assertEqual(g4.get_goal_status(), GoalStatus.ABORTED)
166 self.assertEqual(g4.get_result().result, 1)
167 g6 = client.send_goal(goal_abort)
171 if __name__ ==
'__main__':
173 rospy.init_node(
'test_ref_simple_action_server')
174 rostest.rosrun(
'actionlib',
'test_simple_action_client_python', TestRefSimpleActionServer)