Skip to content

Commit

Permalink
joy_teleop: check all deadman inputs are satisfied
Browse files Browse the repository at this point in the history
  • Loading branch information
russkel committed Sep 4, 2021
1 parent 143e3bb commit c7c0fce
Showing 1 changed file with 15 additions and 9 deletions.
24 changes: 15 additions & 9 deletions joy_teleop/joy_teleop/joy_teleop.py
Original file line number Diff line number Diff line change
Expand Up @@ -120,19 +120,15 @@ def update_active_from_buttons_and_axes(self, joy_state: sensor_msgs.msg.Joy) \

self.active = len(active_buttons) != 0 or len(active_axes) != 0

for axis in self.axes:
try:
self.active |= joy_state.axes[axis] == 1.0
except IndexError:
# An index error can occur if this command is configured for multiple buttons
# like (0, 10), but the length of the joystick buttons is only 1. Ignore these.
pass
return active_buttons, active_axes


class JoyTeleopTopicCommand(JoyTeleopCommand):

def __init__(self, name: str, config: typing.Dict[str, typing.Any], node: Node) -> None:
super().__init__(name, config.get('deadman_buttons', []), config.get('deadman_axes', []))
self.deadman_buttons = config.get('deadman_buttons', [])
self.deadman_axes = config.get('deadman_axes', [])
super().__init__(name, self.deadman_buttons, self.deadman_axes)

self.topic_type = get_interface_type(config['interface_type'], 'msg')

Expand Down Expand Up @@ -186,12 +182,22 @@ def run(self, node: Node, joy_state: sensor_msgs.msg.Joy) -> None:
# continue to be published without debouncing.

last_active = self.active
self.update_active_from_buttons_and_axes(joy_state)
active_buttons, active_axes = self.update_active_from_buttons_and_axes(joy_state)
if not self.active:
return
if self.msg_value is not None and last_active == self.active:
return

if self.deadman_buttons:
# if all the deadman buttons are not active then return
if (set(self.deadman_buttons) - active_buttons) != set():
return

if self.deadman_axes:
# if all the deadman axes are not active then return
if (set(self.deadman_axes) - active_axes) != set():
return

if self.msg_value is not None:
# This is the case for a static message.
msg = self.msg_value
Expand Down

0 comments on commit c7c0fce

Please sign in to comment.