Skip to content

Commit

Permalink
Updated so that it initiates rclpy and shutsdown in each test
Browse files Browse the repository at this point in the history
  • Loading branch information
Aldokan authored Oct 1, 2023
1 parent c0e3c27 commit d610d55
Showing 1 changed file with 3 additions and 1 deletion.
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
from scripts.joystick_interface import JoystickInterface
from joystick_interface.joystick_interface import JoystickInterface
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Wrench
Expand All @@ -9,13 +9,15 @@
class TestJoystickInterface:

def test_2d_wrench_msg(self):
rclpy.init()
msg = JoystickInterface().create_2d_wrench_message(2.0, 3.0, 4.0)
assert msg.force.x == 2.0
assert msg.force.y == 3.0
assert msg.torque.z == 4.0
rclpy.shutdown()

def test_input_from_controller_into_wrench_msg(self):
rclpy.init()
joy_msg = Joy()
joy_msg.axes = [-1.0, -1.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0] #Should have 8 inputs self.joystick_axes_map
Expand Down

0 comments on commit d610d55

Please sign in to comment.