Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 import roslib; roslib.load_manifest('kobuki_auto_docking')
00038 import rospy
00039
00040 import actionlib
00041 from kobuki_msgs.msg import AutoDockingAction, AutoDockingGoal
00042 from actionlib_msgs.msg import GoalStatus
00043
00044 def doneCb(status, result):
00045 if 0: print ''
00046 elif status == GoalStatus.PENDING : state='PENDING'
00047 elif status == GoalStatus.ACTIVE : state='ACTIVE'
00048 elif status == GoalStatus.PREEMPTED : state='PREEMPTED'
00049 elif status == GoalStatus.SUCCEEDED : state='SUCCEEDED'
00050 elif status == GoalStatus.ABORTED : state='ABORTED'
00051 elif status == GoalStatus.REJECTED : state='REJECTED'
00052 elif status == GoalStatus.PREEMPTING: state='PREEMPTING'
00053 elif status == GoalStatus.RECALLING : state='RECALLING'
00054 elif status == GoalStatus.RECALLED : state='RECALLED'
00055 elif status == GoalStatus.LOST : state='LOST'
00056
00057 print 'Result - [ActionServer: ' + state + ']: ' + result.text
00058
00059 def activeCb():
00060 if 0: print 'Action server went active.'
00061
00062 def feedbackCb(feedback):
00063
00064 print 'Feedback: [DockDrive: ' + feedback.state + ']: ' + feedback.text
00065
00066 def dock_drive_client():
00067
00068 client = actionlib.SimpleActionClient('dock_drive_action', AutoDockingAction)
00069 while not client.wait_for_server(rospy.Duration(5.0)):
00070 if rospy.is_shutdown(): return
00071 print 'Action server is not connected yet. still waiting...'
00072
00073 goal = AutoDockingGoal();
00074 client.send_goal(goal, doneCb, activeCb, feedbackCb)
00075 print 'Goal: Sent.'
00076 rospy.on_shutdown(client.cancel_goal)
00077 client.wait_for_result()
00078
00079
00080 return client.get_result()
00081
00082 if __name__ == '__main__':
00083 try:
00084 rospy.init_node('dock_drive_client_py', anonymous=True)
00085 dock_drive_client()
00086
00087
00088 except rospy.ROSInterruptException:
00089 print "program interrupted before completion"