mirror of
https://github.com/SHC-ASTRA/rover-ros2.git
synced 2026-04-20 03:41:17 -05:00
fix(anchor): /anchor/to_vic/relay_string crash fixed
This commit is contained in:
@@ -12,8 +12,7 @@ from .connector import (
|
|||||||
NoValidDeviceException,
|
NoValidDeviceException,
|
||||||
NoWorkingDeviceException,
|
NoWorkingDeviceException,
|
||||||
)
|
)
|
||||||
from .convert import string_to_viccan
|
from .convert import string_to_viccan, viccan_to_string
|
||||||
import threading
|
|
||||||
|
|
||||||
from astra_msgs.msg import VicCAN
|
from astra_msgs.msg import VicCAN
|
||||||
from std_msgs.msg import String
|
from std_msgs.msg import String
|
||||||
@@ -152,7 +151,7 @@ class Anchor(Node):
|
|||||||
)
|
)
|
||||||
# Debug publisher
|
# Debug publisher
|
||||||
self.tovic_debug_pub_ = self.create_publisher(
|
self.tovic_debug_pub_ = self.create_publisher(
|
||||||
VicCAN,
|
String,
|
||||||
"/anchor/to_vic/debug",
|
"/anchor/to_vic/debug",
|
||||||
20,
|
20,
|
||||||
)
|
)
|
||||||
@@ -171,7 +170,7 @@ class Anchor(Node):
|
|||||||
20,
|
20,
|
||||||
)
|
)
|
||||||
self.mock_mcu_sub_ = self.create_subscription(
|
self.mock_mcu_sub_ = self.create_subscription(
|
||||||
String,
|
VicCAN,
|
||||||
"/anchor/from_vic/mock_mcu",
|
"/anchor/from_vic/mock_mcu",
|
||||||
self.relay_fromvic,
|
self.relay_fromvic,
|
||||||
20,
|
20,
|
||||||
@@ -179,7 +178,7 @@ class Anchor(Node):
|
|||||||
self.tovic_string_sub_ = self.create_subscription(
|
self.tovic_string_sub_ = self.create_subscription(
|
||||||
String,
|
String,
|
||||||
"/anchor/to_vic/relay_string",
|
"/anchor/to_vic/relay_string",
|
||||||
self.connector.write_raw,
|
self.write_connector_raw,
|
||||||
20,
|
20,
|
||||||
)
|
)
|
||||||
|
|
||||||
@@ -204,6 +203,11 @@ class Anchor(Node):
|
|||||||
def write_connector(self, msg: VicCAN):
|
def write_connector(self, msg: VicCAN):
|
||||||
"""Write to the connector and send a copy to /anchor/to_vic/debug"""
|
"""Write to the connector and send a copy to /anchor/to_vic/debug"""
|
||||||
self.connector.write(msg)
|
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)
|
self.tovic_debug_pub_.publish(msg)
|
||||||
|
|
||||||
@deprecated(
|
@deprecated(
|
||||||
|
|||||||
@@ -1,5 +1,6 @@
|
|||||||
from abc import ABC, abstractmethod
|
from abc import ABC, abstractmethod
|
||||||
from astra_msgs.msg import VicCAN
|
from astra_msgs.msg import VicCAN
|
||||||
|
from std_msgs.msg import String
|
||||||
from rclpy.clock import Clock
|
from rclpy.clock import Clock
|
||||||
from rclpy.impl.rcutils_logger import RcutilsLogger
|
from rclpy.impl.rcutils_logger import RcutilsLogger
|
||||||
from .convert import string_to_viccan as _string_to_viccan, viccan_to_string
|
from .convert import string_to_viccan as _string_to_viccan, viccan_to_string
|
||||||
@@ -77,7 +78,7 @@ class Connector(ABC):
|
|||||||
pass
|
pass
|
||||||
|
|
||||||
@abstractmethod
|
@abstractmethod
|
||||||
def write_raw(self, msg: str):
|
def write_raw(self, msg: String):
|
||||||
pass
|
pass
|
||||||
|
|
||||||
def cleanup(self):
|
def cleanup(self):
|
||||||
@@ -199,10 +200,10 @@ class SerialConnector(Connector):
|
|||||||
return (None, None) # pretty much no other error matters
|
return (None, None) # pretty much no other error matters
|
||||||
|
|
||||||
def write(self, msg: VicCAN):
|
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):
|
def write_raw(self, msg: String):
|
||||||
self.serial_interface.write(bytes(msg, "utf8"))
|
self.serial_interface.write(bytes(msg.data, "utf8"))
|
||||||
|
|
||||||
def cleanup(self):
|
def cleanup(self):
|
||||||
self.logger.info(f"closing serial port if open {self.port}")
|
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}")
|
self.logger.error(f"CAN error while sending: {e}")
|
||||||
raise DeviceClosedException("CAN bus closed unexpectedly")
|
raise DeviceClosedException("CAN bus closed unexpectedly")
|
||||||
|
|
||||||
def write_raw(self, msg: str):
|
def write_raw(self, msg: String):
|
||||||
self.logger.warn(f"write_raw is not supported for CANConnector. msg: {msg}")
|
self.logger.warn(
|
||||||
|
f"write_raw is not supported for CANConnector. msg: {msg.data}"
|
||||||
|
)
|
||||||
|
|
||||||
def cleanup(self):
|
def cleanup(self):
|
||||||
try:
|
try:
|
||||||
@@ -434,5 +437,5 @@ class MockConnector(Connector):
|
|||||||
def write(self, msg: VicCAN):
|
def write(self, msg: VicCAN):
|
||||||
pass
|
pass
|
||||||
|
|
||||||
def write_raw(self, msg: str):
|
def write_raw(self, msg: String):
|
||||||
pass
|
pass
|
||||||
|
|||||||
Reference in New Issue
Block a user