From 78e8ae2996f5eff6c18f57f53ddb48ca44cd772b Mon Sep 17 00:00:00 2001 From: Aldokan Date: Thu, 28 Sep 2023 15:12:01 +0200 Subject: [PATCH] Made a functioning subscriber and shell for callback function --- .../scripts/joystick_interface.py | 29 +++++++++++-------- .../scripts/test/test_joystick_interface.py | 27 ++++------------- 2 files changed, 23 insertions(+), 33 deletions(-) mode change 100644 => 100755 mission/joystick_interface/scripts/joystick_interface.py diff --git a/mission/joystick_interface/scripts/joystick_interface.py b/mission/joystick_interface/scripts/joystick_interface.py old mode 100644 new mode 100755 index 6cd4066b..32791744 --- a/mission/joystick_interface/scripts/joystick_interface.py +++ b/mission/joystick_interface/scripts/joystick_interface.py @@ -1,3 +1,4 @@ +#!/usr/bin/env python3 import rclpy from rclpy.node import Node from geometry_msgs.msg import Wrench @@ -8,8 +9,8 @@ class JoystickInterface(Node): def __init__(self): - #rclpy.init() - super().__init__('joystick_interface_node') + rclpy.init() + #Mapping copy pasted from the original file self.joystick_buttons_map = [ "A", @@ -36,12 +37,13 @@ def __init__(self): "dpad_vertical", ] - #self.wrench_publisher = self.create_publisher(Wrench, 'wrench_topic', 1) - #self.node = rclpy.create_node('joystick_interface') + + super().__init__('joystick_interface_node') self.subscriber = self.create_subscription(Joy, 'joy', self.joystick_cb, 1) - #rclpy.shutdown() + + #self.wrench_publisher = self.create_publisher(Wrench, 'wrench_topic', 1) def create_2d_wrench_message(self, x, y, yaw): wrench_msg = Wrench() @@ -58,13 +60,16 @@ def publish_wrench_message(self, wrench): def joystick_cb(self, msg): #print(f"Received message: {msg.buttons}") + print("hello") a = msg.buttons return a - def main(args=None): - rclpy.init(args=args) - joystick_interface = JoystickInterface() - rclpy.spin(joystick_interface) - joystick_interface.destroy_node() - rclpy.shutdown() - return +def main(args=None): + #rclpy.init(args=args) + print("hello from main") + joystick_interface = JoystickInterface().subscriber + rclpy.spin(joystick_interface) + joystick_interface.destroy_node() + + rclpy.shutdown() + return diff --git a/mission/joystick_interface/scripts/test/test_joystick_interface.py b/mission/joystick_interface/scripts/test/test_joystick_interface.py index a154c49d..c6298ad1 100644 --- a/mission/joystick_interface/scripts/test/test_joystick_interface.py +++ b/mission/joystick_interface/scripts/test/test_joystick_interface.py @@ -8,34 +8,19 @@ class TestJoystickInterface: - def start(self): - rclpy.init() - j = JoystickInterface() - rclpy.shutdown() - def test_2d_wrench_msg(self): - self.start() + #self.start() 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_publish_wrench_msg(self): - #msg = JoystickInterface().create_2d_wrench_message(2.0, 3.0, 4.0) - #publisher = JoystickInterface().publish_wrench_message(msg) - #assert self.get_logger() == msg - - #def test_joystick_input_output(self): - # return - # - # def test_suscriber(self): - self.start() - #subscriber = JoystickInterface().subscriber - #joystick = JoystickInterface() joy_msg = Joy() - joy_msg.axes = [0.1, 0.2, 0.3] # Customize axes values as needed + joy_msg.axes = [0.1, 0.2, 0.3] joy_msg.buttons = [1, 0, 1] - #JoystickInterface().joystick_cb(joy_msg, subscriber) - #assert JoystickInterface().node.joy_msg assert JoystickInterface().joystick_cb(joy_msg) == joy_msg.buttons + rclpy.shutdown() + +