fix(anchor): /anchor/to_vic/relay_string crash fixed

This commit is contained in:
ryleu
2026-04-12 12:15:55 -05:00
parent dfabd6c330
commit 7d80ad1ab5
2 changed files with 19 additions and 12 deletions

View File

@@ -12,8 +12,7 @@ from .connector import (
NoValidDeviceException,
NoWorkingDeviceException,
)
from .convert import string_to_viccan
import threading
from .convert import string_to_viccan, viccan_to_string
from astra_msgs.msg import VicCAN
from std_msgs.msg import String
@@ -152,7 +151,7 @@ class Anchor(Node):
)
# Debug publisher
self.tovic_debug_pub_ = self.create_publisher(
VicCAN,
String,
"/anchor/to_vic/debug",
20,
)
@@ -171,7 +170,7 @@ class Anchor(Node):
20,
)
self.mock_mcu_sub_ = self.create_subscription(
String,
VicCAN,
"/anchor/from_vic/mock_mcu",
self.relay_fromvic,
20,
@@ -179,7 +178,7 @@ class Anchor(Node):
self.tovic_string_sub_ = self.create_subscription(
String,
"/anchor/to_vic/relay_string",
self.connector.write_raw,
self.write_connector_raw,
20,
)
@@ -204,6 +203,11 @@ class Anchor(Node):
def write_connector(self, msg: VicCAN):
"""Write to the connector and send a copy to /anchor/to_vic/debug"""
self.connector.write(msg)
self.tovic_debug_pub_.publish(String(data=viccan_to_string(msg)))
def write_connector_raw(self, msg: String):
"""Write raw string to the connector and send a copy to /anchor/to_vic/debug"""
self.connector.write_raw(msg)
self.tovic_debug_pub_.publish(msg)
@deprecated(

View File

@@ -1,5 +1,6 @@
from abc import ABC, abstractmethod
from astra_msgs.msg import VicCAN
from std_msgs.msg import String
from rclpy.clock import Clock
from rclpy.impl.rcutils_logger import RcutilsLogger
from .convert import string_to_viccan as _string_to_viccan, viccan_to_string
@@ -77,7 +78,7 @@ class Connector(ABC):
pass
@abstractmethod
def write_raw(self, msg: str):
def write_raw(self, msg: String):
pass
def cleanup(self):
@@ -199,10 +200,10 @@ class SerialConnector(Connector):
return (None, None) # pretty much no other error matters
def write(self, msg: VicCAN):
self.write_raw(viccan_to_string(msg))
self.write_raw(String(data=viccan_to_string(msg)))
def write_raw(self, msg: str):
self.serial_interface.write(bytes(msg, "utf8"))
def write_raw(self, msg: String):
self.serial_interface.write(bytes(msg.data, "utf8"))
def cleanup(self):
self.logger.info(f"closing serial port if open {self.port}")
@@ -411,8 +412,10 @@ class CANConnector(Connector):
self.logger.error(f"CAN error while sending: {e}")
raise DeviceClosedException("CAN bus closed unexpectedly")
def write_raw(self, msg: str):
self.logger.warn(f"write_raw is not supported for CANConnector. msg: {msg}")
def write_raw(self, msg: String):
self.logger.warn(
f"write_raw is not supported for CANConnector. msg: {msg.data}"
)
def cleanup(self):
try:
@@ -434,5 +437,5 @@ class MockConnector(Connector):
def write(self, msg: VicCAN):
pass
def write_raw(self, msg: str):
def write_raw(self, msg: String):
pass