37 import roslib; roslib.load_manifest(
'kobuki_auto_docking')
41 from kobuki_msgs.msg
import AutoDockingAction, AutoDockingGoal
42 from actionlib_msgs.msg
import GoalStatus
46 elif status == GoalStatus.PENDING : state=
'PENDING' 47 elif status == GoalStatus.ACTIVE : state=
'ACTIVE' 48 elif status == GoalStatus.PREEMPTED : state=
'PREEMPTED' 49 elif status == GoalStatus.SUCCEEDED : state=
'SUCCEEDED' 50 elif status == GoalStatus.ABORTED : state=
'ABORTED' 51 elif status == GoalStatus.REJECTED : state=
'REJECTED' 52 elif status == GoalStatus.PREEMPTING: state=
'PREEMPTING' 53 elif status == GoalStatus.RECALLING : state=
'RECALLING' 54 elif status == GoalStatus.RECALLED : state=
'RECALLED' 55 elif status == GoalStatus.LOST : state=
'LOST' 57 print 'Result - [ActionServer: ' + state +
']: ' + result.text
60 if 0:
print 'Action server went active.' 64 print 'Feedback: [DockDrive: ' + feedback.state +
']: ' + feedback.text
69 while not client.wait_for_server(rospy.Duration(5.0)):
70 if rospy.is_shutdown():
return 71 print 'Action server is not connected yet. still waiting...' 73 goal = AutoDockingGoal();
74 client.send_goal(goal, doneCb, activeCb, feedbackCb)
76 rospy.on_shutdown(client.cancel_goal)
77 client.wait_for_result()
80 return client.get_result()
82 if __name__ ==
'__main__':
84 rospy.init_node(
'dock_drive_client_py', anonymous=
True)
88 except rospy.ROSInterruptException:
89 print "program interrupted before completion"
def doneCb(status, result)