Skip to content

Commit

Permalink
Automated autoyapf fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
github-actions committed Feb 7, 2024
1 parent 510f0cf commit e75d24e
Show file tree
Hide file tree
Showing 2 changed files with 24 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,8 @@ def __init__(self):
)

self.last_button_press_time_ = 0
self.debounce_duration_ = 0.25
self.state_ = States.NO_GO
self.debounce_duration_ = 0.25
self.state_ = States.NO_GO

self.joystick_buttons_map_ = [
"A",
Expand Down Expand Up @@ -168,11 +168,10 @@ def joystick_cb(self, msg: Joy) -> Wrench:
left_shoulder = buttons["LB"]
right_shoulder = buttons["RB"]

surge = axes[
"vertical_axis_left_stick"] * self.joystick_surge_scaling_
sway = axes[
"horizontal_axis_left_stick"] * self.joystick_sway_scaling_
heave = -(left_trigger - right_trigger)/2 * self.joystick_heave_scaling_
surge = axes["vertical_axis_left_stick"] * self.joystick_surge_scaling_
sway = axes["horizontal_axis_left_stick"] * self.joystick_sway_scaling_
heave = -(left_trigger -
right_trigger) / 2 * self.joystick_heave_scaling_
roll = (left_shoulder - right_shoulder) * self.joystick_roll_scaling_
pitch = -axes[
"vertical_axis_right_stick"] * self.joystick_pitch_scaling_
Expand Down
32 changes: 18 additions & 14 deletions mission/joystick_interface_auv/test/test_joystick_interface_auv.py
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
from joystick_interface_auv.joystick_interface_auv import JoystickInterface
from joystick_interface_auv.joystick_interface_auv import JoystickInterface
from joystick_interface_auv.joystick_interface_auv import States
import rclpy
from sensor_msgs.msg import Joy
from sensor_msgs.msg import Joy


class TestJoystickInterface():
#test that the wrench msg is created successfully
#test that the wrench msg is created successfully
def test_wrench_msg(self):
rclpy.init()
msg = JoystickInterface().create_wrench_message(
Expand All @@ -26,9 +26,11 @@ def test_input_from_controller_into_wrench_msg(self):
joy_msg.axes = [-1.0, -1.0, 1.0, 0.0, 0.0, 1.0, 0.0, 0.0]
joy_msg.buttons = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
wrench_msg = JoystickInterface().joystick_cb(joy_msg)
assert wrench_msg.force.x == -1.0 * JoystickInterface().joystick_surge_scaling_
assert wrench_msg.force.y == -1.0 * JoystickInterface().joystick_sway_scaling_
assert wrench_msg.force.z == 0.0
assert wrench_msg.force.x == -1.0 * JoystickInterface(
).joystick_surge_scaling_
assert wrench_msg.force.y == -1.0 * JoystickInterface(
).joystick_sway_scaling_
assert wrench_msg.force.z == 0.0
assert wrench_msg.torque.x == 0.0
assert wrench_msg.torque.y == 0.0
assert wrench_msg.torque.z == 0.0
Expand All @@ -43,9 +45,9 @@ def test_killswitch_button(self):
joy_msg.axes = [-1.0, -1.0, 1.0, 0.0, 0.0, 1.0, 0.0, 0.0]
joy_msg.buttons = [0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0]
wrench_msg = joystick.joystick_cb(joy_msg)
assert wrench_msg.force.x == 0.0
assert wrench_msg.force.y == 0.0
assert wrench_msg.force.z == 0.0
assert wrench_msg.force.x == 0.0
assert wrench_msg.force.y == 0.0
assert wrench_msg.force.z == 0.0
assert wrench_msg.torque.x == 0.0
assert wrench_msg.torque.y == 0.0
assert wrench_msg.torque.z == 0.0
Expand All @@ -60,10 +62,12 @@ def test_moving_in_of_xbox_mode(self):
joy_msg.axes = [-1.0, -1.0, 1.0, 0.0, 0.0, 1.0, 0.0, 0.0]
joy_msg.buttons = [1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
wrench_msg = joystick.joystick_cb(joy_msg)
assert wrench_msg.force.x == -1.0 * JoystickInterface().joystick_surge_scaling_
assert wrench_msg.force.y == -1.0 * JoystickInterface().joystick_sway_scaling_
assert wrench_msg.force.z == 0.0
assert wrench_msg.torque.x == 0.0
assert wrench_msg.torque.y == 0.0
assert wrench_msg.torque.z == 0.0
assert wrench_msg.force.x == -1.0 * JoystickInterface(
).joystick_surge_scaling_
assert wrench_msg.force.y == -1.0 * JoystickInterface(
).joystick_sway_scaling_
assert wrench_msg.force.z == 0.0
assert wrench_msg.torque.x == 0.0
assert wrench_msg.torque.y == 0.0
assert wrench_msg.torque.z == 0.0
rclpy.shutdown()

0 comments on commit e75d24e

Please sign in to comment.