Skip to content
Snippets Groups Projects
Commit e69ff4a5 authored by Paul-Winpenny's avatar Paul-Winpenny
Browse files

Updated to publish Int32, lidar

parent a59caad3
No related branches found
No related tags found
No related merge requests found
...@@ -16,8 +16,8 @@ def generate_launch_description(): ...@@ -16,8 +16,8 @@ def generate_launch_description():
Node( Node(
package='robobin', package='robobin',
executable='motor_control_node', executable='control_feedback',
name='motor_control_node', name='control_feedback',
output='screen', output='screen',
emulate_tty=True emulate_tty=True
), ),
......
...@@ -10,6 +10,7 @@ from geometry_msgs.msg import Point ...@@ -10,6 +10,7 @@ from geometry_msgs.msg import Point
from std_msgs.msg import String from std_msgs.msg import String
import rclpy import rclpy
from rclpy.node import Node from rclpy.node import Node
from std_msgs.msg import Int32
class ApiNode(Node): class ApiNode(Node):
def __init__(self): def __init__(self):
...@@ -20,6 +21,7 @@ class ApiNode(Node): ...@@ -20,6 +21,7 @@ class ApiNode(Node):
"cmd_vel": self.create_publisher(Twist, '/cmd_vel', 10), "cmd_vel": self.create_publisher(Twist, '/cmd_vel', 10),
"nav_send": self.create_publisher(Twist, '/nav_send', 10), "nav_send": self.create_publisher(Twist, '/nav_send', 10),
"nav_command": self.create_publisher(String, '/nav_command', 10), "nav_command": self.create_publisher(String, '/nav_command', 10),
"nav_command_lidar": self.create_publisher(Int32, '/nav_command_lidar', 10)
} }
self.location_subscriber = self.create_subscription( self.location_subscriber = self.create_subscription(
Point, # Message type Point, # Message type
...@@ -130,6 +132,9 @@ class ApiNode(Node): ...@@ -130,6 +132,9 @@ class ApiNode(Node):
elif topic == "nav_command" and isinstance(message, str): elif topic == "nav_command" and isinstance(message, str):
self.get_logger().info(f"Published to {topic}: {message}") self.get_logger().info(f"Published to {topic}: {message}")
publisher.publish(String(data=message)) publisher.publish(String(data=message))
elif topic == "nav_command_lidar" and isinstance(message, int):
self.get_logger().info(f"Published to {topic}: {message}")
publisher.publish(Int32(data=message))
else: else:
self.get_logger().warning(f"Unhandled message type for topic: {topic}") self.get_logger().warning(f"Unhandled message type for topic: {topic}")
else: else:
......
...@@ -26,7 +26,8 @@ class MessageHandler: ...@@ -26,7 +26,8 @@ class MessageHandler:
print(response.decode()) print(response.decode())
else: else:
client_socket.sendall(response) client_socket.sendall(response)
return "nav_command", message
return "nav_command_lidar", int(message)
def handle_request_location(self, client_socket, message): def handle_request_location(self, client_socket, message):
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment