6 from rospy
import ROSException
11 from threading
import Thread
12 from rosservice
import ROSServiceException
20 Generic joystick teleoperation node. 21 Will not start without configuration, has to be stored in 'teleop' parameter. 22 See config/joy_teleop.yaml for an example. 25 if not rospy.has_param(
"teleop"):
26 rospy.logfatal(
"no configuration was found, taking node down")
40 teleop_cfg = rospy.get_param(
"teleop")
44 rospy.logerr(
"command {} was duplicated".format(i))
46 action_type = teleop_cfg[i][
'type']
48 if action_type ==
'topic':
50 elif action_type ==
'action':
52 elif action_type ==
'service':
55 rospy.logerr(
"unknown type '%s' for command '%s'", action_type, i)
58 rospy.Subscriber(
'joy', sensor_msgs.msg.Joy, self.
joy_callback)
68 except JoyTeleopException
as e:
69 rospy.logerr(
"error while parsing joystick input: %s", str(e))
73 """Add a topic publisher for a joystick command""" 74 topic_name = command[
'topic_name']
77 self.
publishers[topic_name] = rospy.Publisher(topic_name, topic_type, queue_size=1)
78 except JoyTeleopException
as e:
79 rospy.logerr(
"could not register topic for command {}: {}".format(name, str(e)))
82 """Add an action client for a joystick command""" 83 action_name = command[
'action_name']
88 self.offline_actions.remove(action_name)
89 except JoyTeleopException:
91 self.offline_actions.append(action_name)
94 def __init__(self, name, service_class, persistent=True):
96 rospy.wait_for_service(name, timeout=2.0)
105 if self._thread.is_alive():
106 self._thread.join(1.0)
109 if self._thread.is_alive():
110 self._thread.join(0.01)
111 if self._thread.is_alive():
119 """ Add an AsyncServiceProxy for a joystick command """ 120 service_name = command[
'service_name']
128 self.offline_services.remove(service_name)
129 except JoyTeleopException:
131 self.offline_services.append(service_name)
134 """Find a command matching a joystick configuration""" 136 if b < 0
or len(buttons) <= b
or buttons[b] != 1:
138 return sum(buttons) >= len(self.
command_list[c][
'buttons'])
141 """Add a command to the command list""" 142 if command[
'type'] ==
'topic':
143 if 'deadman_buttons' not in command:
144 command[
'deadman_buttons'] = []
145 command[
'buttons'] = command[
'deadman_buttons']
146 elif command[
'type'] ==
'action':
147 if 'action_goal' not in command:
148 command[
'action_goal'] = {}
149 elif command[
'type'] ==
'service':
150 if 'service_request' not in command:
151 command[
'service_request'] = {}
155 """Run a joystick command""" 157 if cmd[
'type'] ==
'topic':
159 elif cmd[
'type'] ==
'action':
161 rospy.logerr(
"command {} was not played because the action " 162 "server was unavailable. Trying to reconnect..." 163 .format(cmd[
'action_name']))
168 elif cmd[
'type'] ==
'service':
170 rospy.logerr(
"command {} was not played because the service " 171 "server was unavailable. Trying to reconnect..." 172 .format(cmd[
'service_name']))
178 raise JoyTeleopException(
'command {} is neither a topic publisher nor an action or service client' 185 if 'message_value' in cmd:
186 for param
in cmd[
'message_value']:
187 self.
set_member(msg, param[
'target'], param[
'value'])
190 for mapping
in cmd[
'axis_mappings']:
191 if 'axis' in mapping:
192 if len(joy_state.axes) > mapping[
'axis']:
193 val = joy_state.axes[mapping[
'axis']] * mapping.get(
'scale', 1.0) + mapping.get(
'offset', 0.0)
195 rospy.logerr(
'Joystick has only {} axes (indexed from 0), but #{} was referenced in config.'.format(len(joy_state.axes), mapping[
'axis']))
197 elif 'button' in mapping:
198 if len(joy_state.buttons) > mapping[
'button']:
199 val = joy_state.buttons[mapping[
'button']] * mapping.get(
'scale', 1.0) + mapping.get(
'offset', 0.0)
201 rospy.logerr(
'Joystick has only {} buttons (indexed from 0), but #{} was referenced in config.'.format(len(joy_state.buttons), mapping[
'button']))
204 rospy.logerr(
'No Supported axis_mappings type found in: {}'.format(mapping))
209 self.
publishers[cmd[
'topic_name']].publish(msg)
214 genpy.message.fill_message_args(goal, [cmd[
'action_goal']])
215 self.
al_clients[cmd[
'action_name']].send_goal(goal)
221 genpy.message.fill_message_args(request, [cmd[
'service_request']])
222 if not self.
srv_clients[cmd[
'service_name']](request):
223 rospy.loginfo(
'Not sending new service request for command {} because previous request has not finished' 227 ml = member.split(
'.')
232 target = getattr(target, i)
233 setattr(target, ml[-1], value)
238 package, message = type_name.split(
'/')
239 mod = importlib.import_module(package +
'.msg')
245 except AttributeError:
246 raise JoyTeleopException(
"message {} could not be loaded from module {}".format(package, message))
251 return rostopic._get_topic_type(rospy.resolve_name(action_name) +
'/goal')[0][:-4]
258 self.
service_types[service_name] = rosservice.get_service_class_by_name(service_name)
259 except ROSServiceException, e:
260 raise JoyTeleopException(
"service {} could not be loaded: {}".format(service_name, str(e)))
264 for name, cmd
in self.command_list.iteritems():
265 if cmd[
'type'] !=
'action':
271 if __name__ ==
"__main__":
273 rospy.init_node(
'joy_teleop')
276 except JoyTeleopException:
278 except rospy.ROSInterruptException:
def run_service(self, c, joy_state)
def register_topic(self, name, command)
def get_message_type(self, type_name)
def run_topic(self, c, joy_state)
def get_action_type(self, action_name)
def update_actions(self, evt=None)
def get_service_type(self, service_name)
def set_member(self, msg, member, value)
def joy_callback(self, data)
def run_command(self, command, joy_state)
def run_action(self, c, joy_state)
def __call__(self, request)
def add_command(self, name, command)
def register_action(self, name, command)
def __init__(self, name, service_class, persistent=True)
def match_command(self, c, buttons)
def register_service(self, name, command)