Go to the documentation of this file.00001
00002
00003 import roslib; roslib.load_manifest('flexbe_input')
00004 import rospy
00005 import pickle
00006 import actionlib
00007 import threading
00008
00009 from flexbe_msgs.msg import BehaviorInputAction, BehaviorInputFeedback, BehaviorInputResult, BehaviorInputGoal
00010 from complex_action_server import ComplexActionServer
00011 '''
00012 Created on 02/13/2015
00013
00014 @author: Philipp Schillinger, Brian Wright
00015 '''
00016
00017 class BehaviorInput(object):
00018
00019 def __init__(self):
00020 '''
00021 Constructor
00022 '''
00023
00024 self._as = ComplexActionServer('flexbe/behavior_input', BehaviorInputAction, execute_cb=self.execute_cb, auto_start = False)
00025 self._as.start()
00026
00027 rospy.loginfo("Ready for data requests...")
00028
00029 def execute_cb(self, goal , goal_handle):
00030 rospy.loginfo("--> Got a request!")
00031 rospy.loginfo('"%s"' % goal.msg)
00032
00033 relay_ocs_client_ = actionlib.SimpleActionClient('flexbe/operator_input', BehaviorInputAction)
00034
00035
00036 print "waiting"
00037 relay_ocs_client_.wait_for_server()
00038 print "done"
00039
00040
00041 relay_ocs_client_.send_goal(goal)
00042 print "waiting for result"
00043 relay_ocs_client_.wait_for_result()
00044 print "got result"
00045
00046 result = BehaviorInputResult()
00047 result = relay_ocs_client_.get_result()
00048
00049 data_str = result.data
00050 print data_str
00051
00052 if(result.result_code == BehaviorInputResult.RESULT_OK):
00053 self._as.set_succeeded(BehaviorInputResult(result_code=BehaviorInputResult.RESULT_OK, data=data_str), "ok",goal_handle)
00054
00055 elif(result.result_code == BehaviorInputResult.RESULT_FAILED):
00056
00057 self._as.set_succeeded(BehaviorInputResult(result_code=BehaviorInputResult.RESULT_FAILED, data=data_str),"failed",goal_handle)
00058 rospy.loginfo("<-- Replied with FAILED")
00059
00060 elif(result.result_code == BehaviorInputResult.RESULT_ABORTED ):
00061 self._as.set_succeeded(BehaviorInputResult(result_code=BehaviorInputResult.RESULT_ABORTED, data=data_str),"Aborted",goal_handle)
00062 rospy.loginfo("<-- Replied with ABORT")
00063
00064
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080