joy_teleop.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 import importlib
00003 
00004 import rospy
00005 import genpy.message
00006 from rospy import ROSException
00007 import sensor_msgs.msg
00008 import actionlib
00009 import rostopic
00010 import rosservice
00011 from threading import Thread
00012 from rosservice import ROSServiceException
00013 
00014 class JoyTeleopException(Exception):
00015     pass
00016 
00017 
00018 class JoyTeleop:
00019     """
00020     Generic joystick teleoperation node.
00021     Will not start without configuration, has to be stored in 'teleop' parameter.
00022     See config/joy_teleop.yaml for an example.
00023     """
00024     def __init__(self):
00025         if not rospy.has_param("teleop"):
00026             rospy.logfatal("no configuration was found, taking node down")
00027             raise JoyTeleopException("no config")
00028 
00029         self.publishers = {}
00030         self.al_clients = {}
00031         self.srv_clients = {}
00032         self.service_types = {}
00033         self.message_types = {}
00034         self.command_list = {}
00035         self.offline_actions = []
00036         self.offline_services = []
00037 
00038         self.old_buttons = []
00039 
00040         teleop_cfg = rospy.get_param("teleop")
00041 
00042         for i in teleop_cfg:
00043             if i in self.command_list:
00044                 rospy.logerr("command {} was duplicated".format(i))
00045                 continue
00046             action_type = teleop_cfg[i]['type']
00047             self.add_command(i, teleop_cfg[i])
00048             if action_type == 'topic':
00049                 self.register_topic(i, teleop_cfg[i])
00050             elif action_type == 'action':
00051                 self.register_action(i, teleop_cfg[i])
00052             elif action_type == 'service':
00053                 self.register_service(i, teleop_cfg[i])
00054             else:
00055                 rospy.logerr("unknown type '%s' for command '%s'", action_type, i)
00056 
00057         # Don't subscribe until everything has been initialized.
00058         rospy.Subscriber('joy', sensor_msgs.msg.Joy, self.joy_callback)
00059 
00060         # Run a low-freq action updater
00061         rospy.Timer(rospy.Duration(2.0), self.update_actions)
00062 
00063     def joy_callback(self, data):
00064         try:
00065             for c in self.command_list:
00066                 if self.match_command(c, data.buttons):
00067                     self.run_command(c, data)
00068         except JoyTeleopException as e:
00069             rospy.logerr("error while parsing joystick input: %s", str(e))
00070         self.old_buttons = data.buttons
00071 
00072     def register_topic(self, name, command):
00073         """Add a topic publisher for a joystick command"""
00074         topic_name = command['topic_name']
00075         try:
00076             topic_type = self.get_message_type(command['message_type'])
00077             self.publishers[topic_name] = rospy.Publisher(topic_name, topic_type, queue_size=1)
00078         except JoyTeleopException as e:
00079             rospy.logerr("could not register topic for command {}: {}".format(name, str(e)))
00080 
00081     def register_action(self, name, command):
00082         """Add an action client for a joystick command"""
00083         action_name = command['action_name']
00084         try:
00085             action_type = self.get_message_type(self.get_action_type(action_name))
00086             self.al_clients[action_name] = actionlib.SimpleActionClient(action_name, action_type)
00087             if action_name in self.offline_actions:
00088                 self.offline_actions.remove(action_name)
00089         except JoyTeleopException:
00090             if action_name not in self.offline_actions:
00091                 self.offline_actions.append(action_name)
00092 
00093     class AsyncServiceProxy(object):
00094         def __init__(self, name, service_class, persistent=True):
00095             try:
00096                 rospy.wait_for_service(name, timeout=2.0)
00097             except ROSException:
00098                 raise JoyTeleopException("Service {} is not available".format(name))
00099             self._service_proxy = rospy.ServiceProxy(name, service_class, persistent)
00100             self._thread = Thread(target=self._service_proxy, args=[])
00101 
00102         def __del__(self):
00103             # try to join our thread - no way I know of to interrupt a service
00104             # request
00105             if self._thread.is_alive():
00106                 self._thread.join(1.0)
00107 
00108         def __call__(self, request):
00109             if self._thread.is_alive():
00110                 self._thread.join(0.01)
00111                 if self._thread.is_alive():
00112                     return False
00113 
00114             self._thread = Thread(target=self._service_proxy, args=[request])
00115             self._thread.start()
00116             return True
00117 
00118     def register_service(self, name, command):
00119         """ Add an AsyncServiceProxy for a joystick command """
00120         service_name = command['service_name']
00121         try:
00122             service_type = self.get_service_type(service_name)
00123             self.srv_clients[service_name] = self.AsyncServiceProxy(
00124                 service_name,
00125                 service_type)
00126 
00127             if service_name in self.offline_services:
00128                 self.offline_services.remove(service_name)
00129         except JoyTeleopException:
00130             if service_name not in self.offline_services:
00131                 self.offline_services.append(service_name)
00132 
00133     def match_command(self, c, buttons):
00134         """Find a command matching a joystick configuration"""
00135         for b in self.command_list[c]['buttons']:
00136             if b < 0 or len(buttons) <= b or buttons[b] != 1:
00137                 return False
00138         return sum(buttons) >= len(self.command_list[c]['buttons'])
00139 
00140     def add_command(self, name, command):
00141         """Add a command to the command list"""
00142         if command['type'] == 'topic':
00143             if 'deadman_buttons' not in command:
00144                 command['deadman_buttons'] = []
00145             command['buttons'] = command['deadman_buttons']
00146         elif command['type'] == 'action':
00147             if 'action_goal' not in command:
00148                 command['action_goal'] = {}
00149         elif command['type'] == 'service':
00150             if 'service_request' not in command:
00151                 command['service_request'] = {}
00152         self.command_list[name] = command
00153 
00154     def run_command(self, command, joy_state):
00155         """Run a joystick command"""
00156         cmd = self.command_list[command]
00157         if cmd['type'] == 'topic':
00158             self.run_topic(command, joy_state)
00159         elif cmd['type'] == 'action':
00160             if cmd['action_name'] in self.offline_actions:
00161                 rospy.logerr("command {} was not played because the action "
00162                              "server was unavailable. Trying to reconnect..."
00163                              .format(cmd['action_name']))
00164                 self.register_action(command, self.command_list[command])
00165             else:
00166                 if joy_state.buttons != self.old_buttons:
00167                     self.run_action(command, joy_state)
00168         elif cmd['type'] == 'service':
00169             if cmd['service_name'] in self.offline_services:
00170                 rospy.logerr("command {} was not played because the service "
00171                              "server was unavailable. Trying to reconnect..."
00172                              .format(cmd['service_name']))
00173                 self.register_service(command, self.command_list[command])
00174             else:
00175                 if joy_state.buttons != self.old_buttons:
00176                     self.run_service(command, joy_state)
00177         else:
00178             raise JoyTeleopException('command {} is neither a topic publisher nor an action or service client'
00179                                      .format(command))
00180 
00181     def run_topic(self, c, joy_state):
00182         cmd = self.command_list[c]
00183         msg = self.get_message_type(cmd['message_type'])()
00184 
00185         if 'message_value' in cmd:
00186             for param in cmd['message_value']:
00187                 self.set_member(msg, param['target'], param['value'])
00188 
00189         else:
00190             for mapping in cmd['axis_mappings']:
00191                 if 'axis' in mapping:
00192                     if len(joy_state.axes) > mapping['axis']:
00193                         val = joy_state.axes[mapping['axis']] * mapping.get('scale', 1.0) + mapping.get('offset', 0.0)
00194                     else:
00195                         rospy.logerr('Joystick has only {} axes (indexed from 0), but #{} was referenced in config.'.format(len(joy_state.axes), mapping['axis']))
00196                         val = 0.0
00197                 elif 'button' in mapping:
00198                     if len(joy_state.buttons) > mapping['button']:
00199                         val = joy_state.buttons[mapping['button']] * mapping.get('scale', 1.0) + mapping.get('offset', 0.0)
00200                     else:
00201                         rospy.logerr('Joystick has only {} buttons (indexed from 0), but #{} was referenced in config.'.format(len(joy_state.buttons), mapping['button']))
00202                         val = 0.0
00203                 else:
00204                     rospy.logerr('No Supported axis_mappings type found in: {}'.format(mapping))
00205                     val = 0.0
00206 
00207                 self.set_member(msg, mapping['target'], val)
00208 
00209         self.publishers[cmd['topic_name']].publish(msg)
00210 
00211     def run_action(self, c, joy_state):
00212         cmd = self.command_list[c]
00213         goal = self.get_message_type(self.get_action_type(cmd['action_name'])[:-6] + 'Goal')()
00214         genpy.message.fill_message_args(goal, [cmd['action_goal']])
00215         self.al_clients[cmd['action_name']].send_goal(goal)
00216 
00217     def run_service(self, c, joy_state):
00218         cmd = self.command_list[c]
00219         request = self.get_service_type(cmd['service_name'])._request_class()
00220         # should work for requests, too
00221         genpy.message.fill_message_args(request, [cmd['service_request']])
00222         if not self.srv_clients[cmd['service_name']](request):
00223             rospy.loginfo('Not sending new service request for command {} because previous request has not finished'
00224                           .format(c))
00225 
00226     def set_member(self, msg, member, value):
00227         ml = member.split('.')
00228         if len(ml) < 1:
00229             return
00230         target = msg
00231         for i in ml[:-1]:
00232             target = getattr(target, i)
00233         setattr(target, ml[-1], value)
00234 
00235     def get_message_type(self, type_name):
00236         if type_name not in self.message_types:
00237             try:
00238                 package, message = type_name.split('/')
00239                 mod = importlib.import_module(package + '.msg')
00240                 self.message_types[type_name] = getattr(mod, message)
00241             except ValueError:
00242                 raise JoyTeleopException("message type format error")
00243             except ImportError:
00244                 raise JoyTeleopException("module {} could not be loaded".format(package))
00245             except AttributeError:
00246                 raise JoyTeleopException("message {} could not be loaded from module {}".format(package, message))
00247         return self.message_types[type_name]
00248 
00249     def get_action_type(self, action_name):
00250         try:
00251             return rostopic._get_topic_type(rospy.resolve_name(action_name) + '/goal')[0][:-4]
00252         except TypeError:
00253             raise JoyTeleopException("could not find action {}".format(action_name))
00254 
00255     def get_service_type(self, service_name):
00256         if service_name not in self.service_types:
00257             try:
00258                 self.service_types[service_name] = rosservice.get_service_class_by_name(service_name)
00259             except ROSServiceException, e:
00260                 raise JoyTeleopException("service {} could not be loaded: {}".format(service_name, str(e)))
00261         return self.service_types[service_name]
00262 
00263     def update_actions(self, evt=None):
00264         for name, cmd in self.command_list.iteritems():
00265             if cmd['type'] != 'action':
00266                 continue
00267             if cmd['action_name'] in self.offline_actions:
00268                 self.register_action(name, cmd)
00269 
00270 
00271 if __name__ == "__main__":
00272     try:
00273         rospy.init_node('joy_teleop')
00274         jt = JoyTeleop()
00275         rospy.spin()
00276     except JoyTeleopException:
00277         pass
00278     except rospy.ROSInterruptException:
00279         pass


joy_teleop
Author(s): Paul Mathieu
autogenerated on Thu Jun 6 2019 20:38:24