interface_backend.py
Go to the documentation of this file.
00001 import roslib
00002 roslib.load_manifest("hrl_ellipsoidal_control")
00003 import rospy
00004 from std_msgs.msg import String
00005 from std_srvs.srv import Empty
00006 from arm_cart_control_interface import MOVE_BUTTONS, TEXT_BUTTONS
00007 
00008 class ControllerInterfaceBackend(object):
00009     def __init__(self, name, hidden_buttons=[], use_service=True):
00010         self.ctrl_name = name
00011         self.hidden_buttons = hidden_buttons
00012         self.shown_buttons = MOVE_BUTTONS + TEXT_BUTTONS
00013         for button in hidden_buttons:
00014             if button in self.shown_buttons:
00015                 self.shown_buttons.remove(button)
00016         self.set_ctrl_name_pub = rospy.Publisher("/arm_ctrl_gui/set_controller_name", String)
00017         self.set_status_pub = rospy.Publisher("/arm_ctrl_gui/set_status", String)
00018         self.hide_button_pub = rospy.Publisher("/arm_ctrl_gui/hide_button", String)
00019         self.show_button_pub = rospy.Publisher("/arm_ctrl_gui/show_button", String)
00020         if use_service:
00021             self.buttons_enable_srv = rospy.ServiceProxy("/arm_ctrl_gui/buttons_enable", Empty)
00022             self.buttons_disable_srv = rospy.ServiceProxy("/arm_ctrl_gui/buttons_disable", Empty)
00023             self.buttons_enable_srv.wait_for_service()
00024             self.buttons_disable_srv.wait_for_service()
00025         else:
00026             self.buttons_enable_pub = rospy.Publisher("/arm_ctrl_gui/buttons_enable", String)
00027             self.buttons_disable_pub = rospy.Publisher("/arm_ctrl_gui/buttons_disable", String)
00028             self.buttons_enable_srv = self._buttons_enable_srv
00029             self.buttons_disable_srv = self._buttons_disable_srv
00030 
00031         self.button_clk_sub = rospy.Subscriber("/arm_ctrl_gui/button_clk", String,
00032                                                self._button_clk_cb)
00033 
00034         rospy.sleep(0.1)
00035         self.set_ctrl_name_pub.publish(self.ctrl_name)
00036         self.buttons_enable_srv()
00037 
00038     def _buttons_enable_srv():
00039         self.buttons_enable_pub.publish("")
00040 
00041     def _buttons_disable_srv():
00042         self.buttons_disable_pub.publish("")
00043 
00044     def set_arm(self, cart_arm):
00045         rospy.logerr("set_arm not implemented!")
00046         
00047     def _button_clk_cb(self, msg):
00048         self.set_ctrl_name_pub.publish(self.ctrl_name)
00049         self.set_status_pub.publish("Moving arm.")
00050         self.buttons_disable_srv()
00051         self.run_controller(msg.data)
00052         self.set_status_pub.publish("Finished moving arm.")
00053         rospy.sleep(0.1)
00054         self.buttons_enable_srv()
00055 
00056     def run_controller(self, button_press):
00057         rospy.logerr("run_controller not implemented!")
00058 
00059     def disable_interface(self, status_message):
00060         self.buttons_disable_srv()
00061         self.set_status_pub.publish(status_message)
00062 
00063     def enable_interface(self, status_message):
00064         for button in self.hidden_buttons:
00065             self.hide_button_pub.publish(button)
00066         for button in self.shown_buttons:
00067             self.show_button_pub.publish(button)
00068         self.buttons_enable_srv()
00069         self.set_status_pub.publish(status_message)
00070 


hrl_ellipsoidal_control
Author(s): Kelsey Hawkins
autogenerated on Wed Nov 27 2013 11:41:49