mirror of
https://github.com/SHC-ASTRA/rover-ros2.git
synced 2026-04-20 20:01:15 -05:00
Compare commits
3 Commits
f7efa604d2
...
4ef226c094
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
4ef226c094 | ||
|
|
327539467c | ||
|
|
e570d371c6 |
@@ -1,9 +1,9 @@
|
|||||||
|
from warnings import deprecated
|
||||||
import rclpy
|
import rclpy
|
||||||
from rclpy.node import Node
|
from rclpy.node import Node
|
||||||
from rclpy.executors import ExternalShutdownException
|
from rclpy.executors import ExternalShutdownException
|
||||||
from rcl_interfaces.msg import ParameterDescriptor, ParameterType
|
from rcl_interfaces.msg import ParameterDescriptor, ParameterType
|
||||||
|
|
||||||
import signal
|
|
||||||
import atexit
|
import atexit
|
||||||
|
|
||||||
from .connector import (
|
from .connector import (
|
||||||
@@ -14,7 +14,7 @@ from .connector import (
|
|||||||
NoValidDeviceException,
|
NoValidDeviceException,
|
||||||
NoWorkingDeviceException,
|
NoWorkingDeviceException,
|
||||||
)
|
)
|
||||||
from .convert import string_to_viccan, viccan_to_string
|
from .convert import string_to_viccan
|
||||||
import threading
|
import threading
|
||||||
|
|
||||||
from astra_msgs.msg import VicCAN
|
from astra_msgs.msg import VicCAN
|
||||||
@@ -163,6 +163,12 @@ class Anchor(Node):
|
|||||||
self.write_connector,
|
self.write_connector,
|
||||||
20,
|
20,
|
||||||
)
|
)
|
||||||
|
self.tovic_sub_legacy_ = self.create_subscription(
|
||||||
|
String,
|
||||||
|
"/anchor/relay",
|
||||||
|
self.write_connector_legacy,
|
||||||
|
20,
|
||||||
|
)
|
||||||
self.mock_mcu_sub_ = self.create_subscription(
|
self.mock_mcu_sub_ = self.create_subscription(
|
||||||
String,
|
String,
|
||||||
"/anchor/from_vic/mock_mcu",
|
"/anchor/from_vic/mock_mcu",
|
||||||
@@ -195,7 +201,21 @@ 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(viccan_to_string(msg))
|
self.tovic_debug_pub_.publish(msg)
|
||||||
|
|
||||||
|
@deprecated("Use /anchor/to_vic/relay instead of /anchor/relay")
|
||||||
|
def write_connector_legacy(self, msg: String):
|
||||||
|
"""Write to the connector by first attempting to convert String to VicCAN"""
|
||||||
|
# please do not reference this code. ~riley
|
||||||
|
for cmd in msg.data.split("\n"):
|
||||||
|
viccan = string_to_viccan(
|
||||||
|
cmd,
|
||||||
|
"anchor",
|
||||||
|
self.get_logger(),
|
||||||
|
self.get_clock().now().to_msg(),
|
||||||
|
)
|
||||||
|
if viccan:
|
||||||
|
self.write_connector(viccan)
|
||||||
|
|
||||||
def relay_fromvic(self, msg: VicCAN):
|
def relay_fromvic(self, msg: VicCAN):
|
||||||
"""Relay a message from the MCU to the appropriate VicCAN topic"""
|
"""Relay a message from the MCU to the appropriate VicCAN topic"""
|
||||||
|
|||||||
@@ -21,6 +21,16 @@ KNOWN_USBS = [
|
|||||||
]
|
]
|
||||||
BAUD_RATE = 115200
|
BAUD_RATE = 115200
|
||||||
|
|
||||||
|
MCU_IDS = [
|
||||||
|
"broadcast",
|
||||||
|
"core",
|
||||||
|
"arm",
|
||||||
|
"digit",
|
||||||
|
"faerie",
|
||||||
|
"citadel",
|
||||||
|
"libs",
|
||||||
|
]
|
||||||
|
|
||||||
|
|
||||||
class NoValidDeviceException(Exception):
|
class NoValidDeviceException(Exception):
|
||||||
pass
|
pass
|
||||||
@@ -217,6 +227,7 @@ class CANConnector(Connector):
|
|||||||
|
|
||||||
# filter to busses whose channel matches the can_override
|
# filter to busses whose channel matches the can_override
|
||||||
if can_override:
|
if can_override:
|
||||||
|
self.logger.info(f"overrode can interface with {can_override}")
|
||||||
avail = list(
|
avail = list(
|
||||||
filter(
|
filter(
|
||||||
lambda b: b.get("channel") == can_override,
|
lambda b: b.get("channel") == can_override,
|
||||||
@@ -268,17 +279,9 @@ class CANConnector(Connector):
|
|||||||
data_type_key = (arbitration_id >> 6) & 0b11
|
data_type_key = (arbitration_id >> 6) & 0b11
|
||||||
command = arbitration_id & 0x3F
|
command = arbitration_id & 0x3F
|
||||||
|
|
||||||
key_to_mcu: dict[int, str] = {
|
try:
|
||||||
1: "broadcast",
|
mcu_name = MCU_IDS[mcu_key]
|
||||||
2: "core",
|
except IndexError:
|
||||||
3: "arm",
|
|
||||||
4: "digit",
|
|
||||||
5: "faerie",
|
|
||||||
6: "citadel",
|
|
||||||
}
|
|
||||||
|
|
||||||
mcu_name = key_to_mcu.get(mcu_key)
|
|
||||||
if mcu_name is None:
|
|
||||||
self.logger.warn(
|
self.logger.warn(
|
||||||
f"received CAN frame with unknown MCU key {mcu_key}; id=0x{arbitration_id:X}"
|
f"received CAN frame with unknown MCU key {mcu_key}; id=0x{arbitration_id:X}"
|
||||||
)
|
)
|
||||||
@@ -295,7 +298,7 @@ class CANConnector(Connector):
|
|||||||
f"received double payload with insufficient length {len(data_bytes)}; dropping frame"
|
f"received double payload with insufficient length {len(data_bytes)}; dropping frame"
|
||||||
)
|
)
|
||||||
return (None, None)
|
return (None, None)
|
||||||
(value,) = struct.unpack("<d", data_bytes[:8])
|
(value,) = struct.unpack(">d", data_bytes[:8])
|
||||||
data = [float(value)]
|
data = [float(value)]
|
||||||
elif data_type_key == 1:
|
elif data_type_key == 1:
|
||||||
if len(data_bytes) < 8:
|
if len(data_bytes) < 8:
|
||||||
@@ -303,7 +306,7 @@ class CANConnector(Connector):
|
|||||||
f"received float32x2 payload with insufficient length {len(data_bytes)}; dropping frame"
|
f"received float32x2 payload with insufficient length {len(data_bytes)}; dropping frame"
|
||||||
)
|
)
|
||||||
return (None, None)
|
return (None, None)
|
||||||
v1, v2 = struct.unpack("<ff", data_bytes[:8])
|
v1, v2 = struct.unpack(">ff", data_bytes[:8])
|
||||||
data = [float(v1), float(v2)]
|
data = [float(v1), float(v2)]
|
||||||
elif data_type_key == 2:
|
elif data_type_key == 2:
|
||||||
if len(data_bytes) < 8:
|
if len(data_bytes) < 8:
|
||||||
@@ -311,7 +314,7 @@ class CANConnector(Connector):
|
|||||||
f"received int16x4 payload with insufficient length {len(data_bytes)}; dropping frame"
|
f"received int16x4 payload with insufficient length {len(data_bytes)}; dropping frame"
|
||||||
)
|
)
|
||||||
return (None, None)
|
return (None, None)
|
||||||
i1, i2, i3, i4 = struct.unpack("<hhhh", data_bytes[:8])
|
i1, i2, i3, i4 = struct.unpack(">hhhh", data_bytes[:8])
|
||||||
data = [float(i1), float(i2), float(i3), float(i4)]
|
data = [float(i1), float(i2), float(i3), float(i4)]
|
||||||
else:
|
else:
|
||||||
self.logger.warn(
|
self.logger.warn(
|
||||||
@@ -343,92 +346,53 @@ class CANConnector(Connector):
|
|||||||
if not self.can_bus:
|
if not self.can_bus:
|
||||||
raise DeviceClosedException("CAN bus not initialized")
|
raise DeviceClosedException("CAN bus not initialized")
|
||||||
|
|
||||||
# Build 11-bit arbitration ID according to the VicCAN scheme:
|
# build 11-bit arbitration ID according to VicCAN spec:
|
||||||
# bits 10..8: targeted MCU key
|
# bits 10..8: targeted MCU key
|
||||||
# bits 7..6: data type key
|
# bits 7..6: data type key
|
||||||
# bits 5..0: command
|
# bits 5..0: command
|
||||||
|
|
||||||
# Map MCU name to 3-bit key.
|
# map MCU name to 3-bit key.
|
||||||
mcu_name = (msg.mcu_name or "").lower()
|
try:
|
||||||
mcu_key_map: dict[str, int] = {
|
mcu_id = MCU_IDS.index((msg.mcu_name or "").lower())
|
||||||
"broadcast": 1,
|
except ValueError:
|
||||||
"core": 2,
|
|
||||||
"arm": 3,
|
|
||||||
"digit": 4,
|
|
||||||
"faerie": 5,
|
|
||||||
"citadel": 6,
|
|
||||||
}
|
|
||||||
|
|
||||||
if mcu_name not in mcu_key_map:
|
|
||||||
self.logger.error(
|
self.logger.error(
|
||||||
f"unknown VicCAN mcu_name '{msg.mcu_name}' for CAN frame; dropping message"
|
f"unknown VicCAN mcu_name '{msg.mcu_name}' for CAN frame; dropping message"
|
||||||
)
|
)
|
||||||
return
|
return
|
||||||
|
|
||||||
mcu_key = mcu_key_map[mcu_name] & 0b111
|
# determine data type from length:
|
||||||
|
|
||||||
# Infer data type key from payload length according to the table:
|
|
||||||
# 0: double x1, 1: float32 x2, 2: int16 x4, 3: empty
|
# 0: double x1, 1: float32 x2, 2: int16 x4, 3: empty
|
||||||
data_len = len(msg.data)
|
match data_len := len(msg.data):
|
||||||
if data_len == 0:
|
case 0:
|
||||||
data_type_key = 3
|
data_type = 3
|
||||||
elif data_len == 1:
|
data = bytes()
|
||||||
data_type_key = 0
|
case 1:
|
||||||
elif data_len == 2:
|
data_type = 0
|
||||||
data_type_key = 1
|
data = struct.pack(">d", *msg.data)
|
||||||
elif data_len == 4:
|
case 2:
|
||||||
data_type_key = 2
|
data_type = 1
|
||||||
else:
|
data = struct.pack(">ff", *msg.data)
|
||||||
# Fallback: treat any other non-zero length as float32 x2
|
case 4:
|
||||||
self.logger.warn(
|
data_type = 2
|
||||||
f"unexpected VicCAN data length {data_len}; encoding as float32 x2 (key=1) and truncating/padding as needed"
|
data = struct.pack(">hhhh", *[int(x) for x in msg.data])
|
||||||
)
|
case _:
|
||||||
data_type_key = 1
|
|
||||||
|
|
||||||
# Command is limited to 6 bits.
|
|
||||||
command = int(msg.command_id)
|
|
||||||
if command < 0:
|
|
||||||
self.logger.error(f"invalid negative command_id for CAN frame: {command}")
|
|
||||||
return
|
|
||||||
if command > 0x3F:
|
|
||||||
self.logger.warn(
|
|
||||||
f"command_id 0x{command:X} exceeds 6-bit range; truncating to lower 6 bits"
|
|
||||||
)
|
|
||||||
command &= 0x3F
|
|
||||||
|
|
||||||
arbitration_id = (
|
|
||||||
((mcu_key & 0b111) << 8) | ((data_type_key & 0b11) << 6) | (command & 0x3F)
|
|
||||||
)
|
|
||||||
|
|
||||||
# Map VicCAN.data (floats) to up to 8 CAN data bytes.
|
|
||||||
raw_bytes: list[int] = []
|
|
||||||
for value in msg.data:
|
|
||||||
try:
|
|
||||||
b = int(round(value))
|
|
||||||
except (TypeError, ValueError):
|
|
||||||
self.logger.error(
|
self.logger.error(
|
||||||
f"non-numeric VicCAN data value: {value}; dropping message"
|
f"unexpected VicCAN data length: {data_len}; dropping message"
|
||||||
)
|
)
|
||||||
return
|
return
|
||||||
|
|
||||||
if b < 0 or b > 255:
|
# command is limited to 6 bits.
|
||||||
self.logger.warn(
|
command = int(msg.command_id)
|
||||||
f"VicCAN data value {value} out of byte range; clamping into [0, 255]"
|
if command < 0 or command > 0x3F:
|
||||||
)
|
self.logger.error(
|
||||||
b = max(0, min(255, b))
|
f"invalid command_id for CAN frame: {command}; dropping message"
|
||||||
|
|
||||||
raw_bytes.append(b)
|
|
||||||
|
|
||||||
if len(raw_bytes) > 8:
|
|
||||||
self.logger.warn(
|
|
||||||
f"VicCAN data too long for single CAN frame ({len(raw_bytes)} > 8); truncating"
|
|
||||||
)
|
)
|
||||||
raw_bytes = raw_bytes[:8]
|
return
|
||||||
|
|
||||||
try:
|
try:
|
||||||
can_message = can.Message(
|
can_message = can.Message(
|
||||||
arbitration_id=arbitration_id,
|
arbitration_id=(mcu_id << 8) | (data_type << 6) | command,
|
||||||
data=raw_bytes,
|
data=data,
|
||||||
is_extended_id=False,
|
is_extended_id=False,
|
||||||
)
|
)
|
||||||
except Exception as e:
|
except Exception as e:
|
||||||
|
|||||||
@@ -16,7 +16,7 @@ def string_to_viccan(
|
|||||||
parts: list[str] = msg.strip().split(",")
|
parts: list[str] = msg.strip().split(",")
|
||||||
|
|
||||||
# don't need an extra check because len of .split output is always >= 1
|
# don't need an extra check because len of .split output is always >= 1
|
||||||
if parts[0] != "can_relay_fromvic":
|
if not parts[0].startswith("can_relay_"):
|
||||||
logger.debug(f"got non-CAN data from {mcu_name}: {msg}")
|
logger.debug(f"got non-CAN data from {mcu_name}: {msg}")
|
||||||
return None
|
return None
|
||||||
elif len(parts) < 3:
|
elif len(parts) < 3:
|
||||||
@@ -59,4 +59,4 @@ def viccan_to_string(viccan: VicCAN) -> str:
|
|||||||
"""Converts a ROS2 VicCAN message to the serial string VicCAN format."""
|
"""Converts a ROS2 VicCAN message to the serial string VicCAN format."""
|
||||||
# go from [ w, x, y, z ] -> ",w,x,y,z" & round to 7 digits max
|
# go from [ w, x, y, z ] -> ",w,x,y,z" & round to 7 digits max
|
||||||
data = "".join([f",{round(val,7)}" for val in viccan.data])
|
data = "".join([f",{round(val,7)}" for val in viccan.data])
|
||||||
return f"can_relay_tovic,{viccan.mcu_name}{data}\n"
|
return f"can_relay_tovic,{viccan.mcu_name},{viccan.command_id}{data}\n"
|
||||||
|
|||||||
@@ -33,7 +33,7 @@ def generate_launch_description():
|
|||||||
ld.add_action(
|
ld.add_action(
|
||||||
DeclareLaunchArgument(
|
DeclareLaunchArgument(
|
||||||
"can_override",
|
"can_override",
|
||||||
default_value="auto",
|
default_value="",
|
||||||
description="CAN network override parameter for anchor node (default: '')",
|
description="CAN network override parameter for anchor node (default: '')",
|
||||||
)
|
)
|
||||||
)
|
)
|
||||||
|
|||||||
@@ -262,7 +262,7 @@ class PtzNode(Node):
|
|||||||
f"[{self.get_clock().now().nanoseconds / 1e9:.2f}] PTZ Node: {message_text}"
|
f"[{self.get_clock().now().nanoseconds / 1e9:.2f}] PTZ Node: {message_text}"
|
||||||
)
|
)
|
||||||
self.debug_pub.publish(msg)
|
self.debug_pub.publish(msg)
|
||||||
self.get_logger().info(message_text)
|
self.get_logger().debug(message_text)
|
||||||
|
|
||||||
def run_async_func(self, coro):
|
def run_async_func(self, coro):
|
||||||
"""Run an async function in the event loop."""
|
"""Run an async function in the event loop."""
|
||||||
|
|||||||
Reference in New Issue
Block a user