Skip to content

Commit

Permalink
xbox_controller: Set sensible speed values
Browse files Browse the repository at this point in the history
  • Loading branch information
RandomSpaceship committed Dec 21, 2024
1 parent 67af030 commit 93f1be2
Showing 1 changed file with 8 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,9 @@ def __init__(self):
self.subscription = self.create_subscription(Joy, "joy", self.joy_callback, 10)
self.subscription # prevent unused variable warning

self.TRANSLATE_SCALING = 0.25
self.ROTATE_SCALING = 0.5

def joy_callback(self, joy_msg):
twist = Twist()

Expand All @@ -19,16 +22,14 @@ def joy_callback(self, joy_msg):
sideways_input = 0.0
direction_reversed = False

# Check if Axis 5 (right trigger) is fully pressed (-1.0)
dead_man_switch = joy_msg.axes[5] == -1.0
# Check if Axis 5 (right trigger) is fully pressed (close to -1.0)
dead_man_switch = joy_msg.axes[5] <= -0.95

if dead_man_switch:
# Axis 1 (left stick Y-axis) for forward/backward movement
forward_input = joy_msg.axes[1]
forward_input = forward_input / 10 # scale down factor
twist.linear.x = forward_input
# Axis 2 (left stick X-axis) for left/right movement
sideways_input = joy_msg.axes[2]
twist.linear.x = joy_msg.axes[1] * self.TRANSLATE_SCALING
# Axis 2 (right stick X-axis) for left/right movement
sideways_input = joy_msg.axes[2] * self.ROTATE_SCALING

if forward_input < 0:
twist.angular.z = -1.0 * sideways_input
Expand Down

0 comments on commit 93f1be2

Please sign in to comment.