32 from actionlib_msgs.msg
import GoalStatus
33 from actionlib
import SimpleActionClient
34 from actionlib
import ActionClient
35 from actionlib.msg
import TestAction, TestGoal
42 self.assert_(client.wait_for_server(rospy.Duration(2.0)),
43 'Could not connect to the action server')
46 client.send_goal(goal)
47 self.assert_(client.wait_for_result(rospy.Duration(2.0)),
49 self.assertEqual(GoalStatus.SUCCEEDED, client.get_state())
52 client.send_goal(goal)
53 self.assert_(client.wait_for_result(rospy.Duration(10.0)),
55 self.assertEqual(GoalStatus.ABORTED, client.get_state())
58 client.send_goal(goal)
59 self.assert_(client.wait_for_result(rospy.Duration(10.0)),
63 self.assertEqual(GoalStatus.ABORTED, client.get_state())
69 rospy.loginfo(
"Got feedback")
70 saved_feedback[0] = fb
72 client.send_goal(goal, feedback_cb=on_feedback)
73 self.assert_(client.wait_for_result(rospy.Duration(10.0)),
75 self.assertEqual(GoalStatus.SUCCEEDED, client.get_state())
77 self.assertEqual(saved_feedback[0].feedback, 9)
80 if __name__ ==
'__main__':
82 rospy.init_node(
'test_ref_simple_action_server')
83 rostest.rosrun(
'actionlib',
'test_simple_action_client_python', TestRefSimpleActionServer)
A Simple client implementation of the ActionInterface which supports only one goal at a time...