Skip to content

Commit

Permalink
Made a functioning subscriber and shell for callback function
Browse files Browse the repository at this point in the history
  • Loading branch information
Aldokan committed Sep 28, 2023
1 parent 7d9f22b commit 78e8ae2
Show file tree
Hide file tree
Showing 2 changed files with 23 additions and 33 deletions.
29 changes: 17 additions & 12 deletions mission/joystick_interface/scripts/joystick_interface.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Wrench
Expand All @@ -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",
Expand All @@ -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()
Expand All @@ -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
27 changes: 6 additions & 21 deletions mission/joystick_interface/scripts/test/test_joystick_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()


0 comments on commit 78e8ae2

Please sign in to comment.