Go to the documentation of this file.00001 import roslib; roslib.load_manifest('rcommander_interface')
00002 import actionlib
00003 import rospy
00004 from rcommander_web.msg import RunScriptAction, RunScriptGoal
00005
00006 BEHAVIOR_PATH = '/u/lazewatskyd/robot_behaviors'
00007 import os
00008
00009 class Behaviors:
00010 def __init__(self):
00011 ns = '/run_rcommander_action_web'
00012 self.action_client = actionlib.SimpleActionClient(ns, RunScriptAction)
00013 self.action_client.wait_for_server()
00014 self.rocker_on_goal = RunScriptGoal(os.path.join(BEHAVIOR_PATH, 'Behaviors/rcommander_behaviors/rocker_switch/rocker_on'))
00015 self.rocker_off_goal = RunScriptGoal(os.path.join(BEHAVIOR_PATH, 'Behaviors/rcommander_behaviors/rocker_switch/rocker_off'))
00016
00017 def rocker_on(self, wait=True):
00018 self.action_client.send_goal(self.rocker_on_goal)
00019 if wait:
00020 return self.action_client.wait_for_result()
00021
00022 def rocker_off(self, wait=True):
00023 self.action_client.send_goal(self.rocker_off_goal)
00024 if wait:
00025 return self.action_client.wait_for_result()
00026
00027
00028
00029
00030
00031
00032
00033