$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2009, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of the Willow Garage nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 00034 import roslib 00035 roslib.load_manifest('pr2_plugs_actions') 00036 00037 import rospy 00038 00039 from actionlib import * 00040 from pr2_plugs_msgs.msg import * 00041 from pr2_plugs_msgs.srv import * 00042 00043 class RechargeActionWebAdapter: 00044 def __init__(self): 00045 # Construct action client 00046 self.recharge_client = SimpleActionClient('recharge',RechargeAction) 00047 if self.recharge_client.wait_for_server(rospy.Duration(120.0)): 00048 rospy.loginfo("Recharge action web adapter connected to recharge action server.") 00049 else: 00050 rospy.logerr("Recharge action web adapter timed out while waiting for recharge action server.") 00051 raise Exception() 00052 00053 # Construct publisher for recharge state, and broadcast initial state 00054 self.recharge_state = RechargeState() 00055 self.recharge_state.state = RechargeState.UNPLUGGED 00056 00057 self.recharge_state_pub = rospy.Publisher('recharge_state', RechargeState, None, False, True) 00058 self.recharge_state_pub.publish(self.recharge_state) 00059 00060 # Construct subscriber for recharge commands 00061 self.recharge_command_sub = rospy.Subscriber("recharge_command", RechargeCommand, self.recharge_command_cb) 00062 self.recharge_request_srv = rospy.Service('recharge_request', RechargeRequest, self.recharge_request_cb) 00063 00064 00065 def recharge_request_cb(self, req): 00066 self.recharge_command_cb(req.command) 00067 00068 def recharge_command_cb(self,msg): 00069 if self.recharge_state.state == RechargeState.WAITING_FOR_STATE: 00070 rospy.logerr("Recharge action web adapter can't execute commands while still waiting for state.") 00071 return 00072 00073 # There are only two valid things to do 00074 valid_plug_in_cmd = (self.recharge_state.state == RechargeState.UNPLUGGED and msg.command == RechargeCommand.PLUG_IN) 00075 valid_unplug_cmd = (self.recharge_state.state == RechargeState.PLUGGED_IN and msg.command == RechargeCommand.UNPLUG) 00076 00077 if valid_plug_in_cmd or valid_unplug_cmd: 00078 # Publish ack to web 00079 rospy.loginfo("Recharge action web adapter sending command to action server...") 00080 self.recharge_state.state = RechargeState.WAITING_FOR_STATE 00081 self.recharge_state_pub.publish(self.recharge_state) 00082 00083 # Send action to action server 00084 self.recharge_client.send_goal( 00085 RechargeGoal(command = msg), 00086 done_cb = self.action_done_cb) 00087 00088 # Store recharge command 00089 self.recharge_command = msg.command 00090 else: 00091 rospy.logerr("Invalid command for the current recharge state.") 00092 00093 def action_done_cb(self,result_state,result): 00094 rospy.loginfo("Recharge action completed with state: %d and result: %s" % (result_state, str(result))) 00095 00096 # Store result 00097 self.recharge_state.state = result.state.state 00098 00099 # Publish result to the web 00100 self.recharge_state_pub.publish(self.recharge_state) 00101 00102 00103 00104 def main(): 00105 rospy.init_node("recharge_action_web_adapter") 00106 adapter = RechargeActionWebAdapter() 00107 rospy.spin() 00108 00109 if __name__ == "__main__": 00110 main() 00111