joy.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import math
00004 import numpy
00005 
00006 import rospy
00007 import os
00008 import sys
00009 
00010 import imp
00011 try:
00012   imp.find_module("sensor_msgs")
00013 except:
00014   import roslib; roslib.load_manifest('jsk_teleop_joy')
00015 
00016 
00017 from sensor_msgs.msg import Joy
00018 from diagnostic_msgs.msg import DiagnosticStatus, DiagnosticArray
00019 import tf.transformations
00020 from joy_status import XBoxStatus, PS3Status, PS3WiredStatus
00021 from jsk_rviz_plugins.msg import OverlayMenu
00022 from plugin_manager import PluginManager
00023 from status_history import StatusHistory
00024 from diagnostic_updater import Updater as DiagnosticUpdater
00025 
00026 AUTO_DETECTED_CLASS = None
00027 
00028 def autoJoyDetect(msg):
00029   global AUTO_DETECTED_CLASS
00030   if AUTO_DETECTED_CLASS:
00031     return
00032   if len(msg.axes) == 27 and len(msg.buttons) == 19:
00033     rospy.loginfo("auto detected as ps3wired")
00034     AUTO_DETECTED_CLASS = PS3WiredStatus
00035   elif len(msg.axes) == 8 and len(msg.buttons) == 11:
00036     rospy.loginfo("auto detected as xbox")
00037     AUTO_DETECTED_CLASS = XBoxStatus
00038   elif len(msg.axes) == 20 and len(msg.buttons) == 17:
00039     rospy.loginfo("auto detected as ps3")
00040     AUTO_DETECTED_CLASS = PS3Status
00041   else:
00042     AUTO_DETECTED_CLASS = "UNKNOWN"
00043     
00044 class JoyManager():
00045   STATE_INITIALIZATION = 1
00046   STATE_RUNNING = 2
00047   STATE_WAIT_FOR_JOY = 3
00048 
00049   MODE_PLUGIN = 0
00050   MODE_MENU = 1
00051   mode = 0
00052   
00053   plugin_instances = []
00054   def stateDiagnostic(self, stat):
00055     if self.state == self.STATE_INITIALIZATION:
00056       stat.summary(DiagnosticStatus.WARN,
00057                    "initializing JoyManager")
00058     elif self.state == self.STATE_RUNNING:
00059       stat.summary(DiagnosticStatus.OK,
00060                    "running")
00061       stat.add("Joy stick type", str(self.JoyStatus))
00062     elif self.state == self.STATE_WAIT_FOR_JOY:
00063       stat.summary(DiagnosticStatus.WARN,
00064                    "waiting for joy message to detect joy stick type")
00065     return stat
00066   def pluginStatusDiagnostic(self, stat):
00067     if len(self.plugin_instances) == 0:
00068         stat.summary(DiagnosticStatus.ERROR, "no plugin is loaded")
00069     else:
00070         stat.summary(DiagnosticStatus.OK, 
00071                      "%d plugins are loaded" % (len(self.plugin_instances)))
00072         stat.add("instances", ", ".join([p.name for p in self.plugin_instances]))
00073     return stat
00074   def __init__(self):
00075     self.state = self.STATE_INITIALIZATION
00076     self.pre_status = None
00077     self.history = StatusHistory(max_length=10)
00078     self.menu_pub = rospy.Publisher("/overlay_menu", OverlayMenu)
00079     self.controller_type = rospy.get_param('~controller_type', 'auto')
00080     self.plugins = rospy.get_param('~plugins', {})
00081     self.current_plugin_index = 0
00082     #you can specify the limit of the rate via ~diagnostic_period
00083     self.diagnostic_updater = DiagnosticUpdater()
00084     self.diagnostic_updater.setHardwareID("teleop_manager")
00085     self.diagnostic_updater.add("State", self.stateDiagnostic)
00086     self.diagnostic_updater.add("Plugin Status", self.pluginStatusDiagnostic)
00087     #self.diagnostic_updater.add("Joy Input", self.joyInputDiagnostic)
00088     self.diagnostic_updater.update()
00089     if self.controller_type == 'xbox':
00090       self.JoyStatus = XBoxStatus
00091     elif self.controller_type == 'ps3':
00092       self.JoyStatus = PS3Status
00093     elif self.controller_type == 'ps3wired':
00094       self.JoyStatus = PS3WiredStatus
00095     elif self.controller_type == 'auto':
00096       s = rospy.Subscriber('/joy', Joy, autoJoyDetect)
00097       self.state = self.STATE_WAIT_FOR_JOY
00098       error_message_published = False
00099       r = rospy.Rate(1)
00100       while not rospy.is_shutdown():
00101         self.diagnostic_updater.update()
00102         if AUTO_DETECTED_CLASS == "UNKNOWN":
00103           if not error_message_published:
00104             rospy.logfatal("unknown joy type")
00105             error_message_published = True
00106           r.sleep()
00107         elif AUTO_DETECTED_CLASS:
00108           self.JoyStatus = AUTO_DETECTED_CLASS
00109           s.unregister()
00110           break
00111         else:
00112           r.sleep()
00113     self.diagnostic_updater.update()
00114     self.plugin_manager = PluginManager('jsk_teleop_joy')
00115     self.loadPlugins()
00116   def loadPlugins(self):
00117     self.plugin_manager.loadPlugins()
00118     self.plugin_instances = self.plugin_manager.loadPluginInstances(self.plugins)
00119   def switchPlugin(self, index):
00120     self.current_plugin_index = index
00121     if len(self.plugin_instances) <= self.current_plugin_index:
00122       self.current_plugin_index = 0
00123     elif self.current_plugin_index < 0:
00124       self.current_plugin_index = len(self.plugin_instances)
00125     self.current_plugin.disable()
00126     self.current_plugin = self.plugin_instances[self.current_plugin_index]
00127     self.current_plugin.enable()
00128   def nextPlugin(self):
00129     rospy.loginfo('switching to next plugin')
00130     self.switchPlugin(self, self.current_plugin_index + 1)
00131   def start(self):
00132     self.publishMenu(0, close=True) # close menu anyway
00133     self.diagnostic_updater.force_update()
00134     if len(self.plugin_instances) == 0:
00135       rospy.logfatal('no valid plugins are loaded')
00136       return False
00137     self.current_plugin = self.plugin_instances[0]
00138     self.current_plugin.enable()
00139     self.joy_subscriber = rospy.Subscriber('/joy', Joy, self.joyCB)
00140     self.state = self.STATE_RUNNING
00141     return True
00142   def publishMenu(self, index, close=False):
00143     menu = OverlayMenu()
00144     menu.menus = [p.name for p in self.plugin_instances]
00145     menu.current_index = index
00146     menu.title = "Joystick"
00147     if close:
00148       menu.action = OverlayMenu.ACTION_CLOSE
00149     self.menu_pub.publish(menu)
00150   def processMenuMode(self, status, history):
00151     if history.new(status, "down") or history.new(status, "left_analog_down"):
00152       self.selecting_plugin_index = self.selecting_plugin_index + 1
00153       if self.selecting_plugin_index >= len(self.plugin_instances):
00154         self.selecting_plugin_index = 0
00155       self.publishMenu(self.selecting_plugin_index)
00156     elif history.new(status, "up") or history.new(status, "left_analog_up"):
00157       self.selecting_plugin_index = self.selecting_plugin_index - 1
00158       if self.selecting_plugin_index < 0:
00159         self.selecting_plugin_index = len(self.plugin_instances) - 1
00160       self.publishMenu(self.selecting_plugin_index)
00161     elif history.new(status, "cross") or history.new(status, "center"):
00162       self.publishMenu(self.selecting_plugin_index, close=True)
00163       self.mode = self.MODE_PLUGIN
00164     elif history.new(status, "circle"):
00165       self.publishMenu(self.selecting_plugin_index, close=True)
00166       self.mode = self.MODE_PLUGIN
00167       self.switchPlugin(self.selecting_plugin_index)
00168   def joyCB(self, msg):
00169     status = self.JoyStatus(msg)
00170     if self.mode == self.MODE_MENU:
00171       self.processMenuMode(status, self.history)
00172     else:
00173       if self.history.new(status, "center"):
00174         self.selecting_plugin_index = self.current_plugin_index
00175         self.publishMenu(self.current_plugin_index)
00176         self.mode = self.MODE_MENU
00177       else:
00178         self.current_plugin.joyCB(status, self.history)
00179     self.pre_status = status
00180     self.history.add(status)
00181     self.diagnostic_updater.update()
00182     
00183 def main():
00184   global g_manager
00185   rospy.sleep(1)
00186   rospy.init_node('jsk_teleop_joy')
00187   g_manager = JoyManager()
00188   result = g_manager.start()
00189   if not result:
00190     rospy.logfatal("Fatal Error")
00191     return False
00192   else:
00193     rospy.spin()
00194   
00195 if __name__ == '__main__':
00196   main()
00197   


jsk_teleop_joy
Author(s): Ryohei Ueda
autogenerated on Mon Oct 6 2014 01:11:11