From d610d55b6f6d4c54670d0110b199df81bdbcfda9 Mon Sep 17 00:00:00 2001 From: Aldokan <114017858+Aldokan@users.noreply.github.com> Date: Sun, 1 Oct 2023 17:22:44 +0200 Subject: [PATCH] Updated so that it initiates rclpy and shutsdown in each test --- .../scripts/test/test_joystick_interface.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/mission/joystick_interface/scripts/test/test_joystick_interface.py b/mission/joystick_interface/scripts/test/test_joystick_interface.py index 0b2cf559..2009d1a8 100644 --- a/mission/joystick_interface/scripts/test/test_joystick_interface.py +++ b/mission/joystick_interface/scripts/test/test_joystick_interface.py @@ -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 @@ -9,6 +9,7 @@ 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 @@ -16,6 +17,7 @@ def test_2d_wrench_msg(self): 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