8 Commits

Author SHA1 Message Date
David
87237bd841 chore(anchor): use new version commit hash field name 2026-04-18 15:09:30 -05:00
David
79b2d0020f feat(anchor): add is_main and is_dirty to versioning 2026-04-15 23:50:47 -05:00
David
3dd9525833 feat(anchor): add MCU Versioning feedback 2026-04-14 15:38:41 -05:00
Riley M.
8404999369 Merge pull request #31 from SHC-ASTRA/can-refactor
Refactor anchor & add direct CAN connector
2026-04-08 00:18:13 -05:00
ryleu
88574524cf clarify the mock connector usage in the README 2026-04-08 00:15:39 -05:00
ryleu
30bb32a66b remove extraneous slice 2026-04-08 00:09:04 -05:00
David
010d2da0b6 fix: string number 2026-04-07 23:45:40 -05:00
ryleu
0a257abf43 make the pad 3 -> logic consistent 2026-04-07 23:44:38 -05:00
5 changed files with 43 additions and 12 deletions

View File

@@ -68,20 +68,20 @@ Anchor provides a mock connector meant for testing and scripting purposes. You c
$ ros2 launch anchor_pkg rover.launch.py connector:="mock"
```
You can see all data sent to it in a string format with this command:
To see all data that would be sent over the CAN network (and thus to the microcontrollers), use this command:
```bash
$ ros2 topic echo /anchor/to_vic/debug
```
To send data to it, use the normal topic:
To send data to the mock connector (as if you were a ROS2 node), use the normal relay topic:
```bash
$ ros2 topic pub /anchor/to_vic/relay astra_msgs/msg/VicCAN '{mcu_name: "core", command_id: 50, data: [0.0, 2.0, 0.0, 1.0]}'
```
To emulate receiving data from a microcontroller, publish to the dedicated topic:
To send data to the mock connector (as if you were a microcontroller), publish to the dedicated topic:
```bash
$ ros2 topic pub /anchor/from_vic/mock_mcu astra_msgs/msg/VicCAN '{mcu_name: "arm", command_id: 55, data: [0.0, 450.0, 900.0, 0.0]}'

View File

@@ -1,4 +1,5 @@
from warnings import deprecated
import time
import rclpy
from rclpy.node import Node
from rclpy.executors import ExternalShutdownException
@@ -17,8 +18,9 @@ from .connector import (
from .convert import string_to_viccan
import threading
from astra_msgs.msg import VicCAN
from builtin_interfaces.msg import Time
from std_msgs.msg import String
from astra_msgs.msg import VicCAN, McuVersion
class Anchor(Node):
@@ -47,6 +49,8 @@ class Anchor(Node):
Instead, it converts them to VicCAN messages first.
"""
ASTRA_EPOCH = time.struct_time((2022, 1, 1, 0, 0, 0, 0, 0, 0)) # January 1, 2022
connector: Connector
def __init__(self):
@@ -158,6 +162,12 @@ class Anchor(Node):
"/anchor/to_vic/debug",
20,
)
# MCU Version publisher
self.mcu_version_pub_ = self.create_publisher(
McuVersion,
"/anchor/from_vic/mcu_version",
20,
)
# Subscribers
self.tovic_sub_ = self.create_subscription(
@@ -173,7 +183,7 @@ class Anchor(Node):
20,
)
self.mock_mcu_sub_ = self.create_subscription(
String,
VicCAN,
"/anchor/from_vic/mock_mcu",
self.relay_fromvic,
20,
@@ -185,6 +195,8 @@ class Anchor(Node):
20,
)
self.mcu_versions: dict[str, McuVersion] = {}
# Close devices on exit
atexit.register(self.cleanup)
@@ -231,6 +243,26 @@ class Anchor(Node):
elif msg.mcu_name == "citadel" or msg.mcu_name == "digit":
self.fromvic_bio_pub_.publish(msg)
# MCU Versioning information
if msg.command_id in (46, 47) and msg.mcu_name not in self.mcu_versions:
self.mcu_versions[msg.mcu_name] = McuVersion(mcu_name=msg.mcu_name)
if msg.command_id == 46: # commit hashes
self.mcu_versions[msg.mcu_name].project_commit_fragment = msg.data[0]
self.mcu_versions[msg.mcu_name].astra_lib_commit_fragment = msg.data[1]
elif msg.command_id == 47: # build timestamp and version numbers
version_msg = self.mcu_versions[msg.mcu_name]
version_msg.build_time = Time(
sec=int(time.mktime(self.ASTRA_EPOCH) + msg.data[0])
)
# is_main and is_dirty is in msg.data[1]
# Out of 1 byte, it looks like [lib_isdirty][lib_ismain][proj_isdirty][proj_ismain]
version_msg.astra_lib_is_dirty = bool(int(msg.data[1]) >> 3 & 0x1)
version_msg.astra_lib_is_main = bool(int(msg.data[1]) >> 2 & 0x1)
version_msg.project_is_dirty = bool(int(msg.data[1]) >> 1 & 0x1)
version_msg.project_is_main = bool(int(msg.data[1]) & 0x1)
self.mcu_version_pub_.publish(version_msg)
def main(args=None):
try:

View File

@@ -257,7 +257,7 @@ class CANConnector(Connector):
)
if self.can_channel and self.can_channel.startswith("v"):
self.logger.warn("likely using virtual CAN interface")
self.logger.warn("CAN interface is likely virtual")
def read(self) -> tuple[VicCAN | None, str | None]:
if not self.can_bus:
@@ -372,11 +372,10 @@ class CANConnector(Connector):
case 2:
data_type = 1
data = struct.pack(">ff", *msg.data)
case 3 | 4: # 3 gets padded and is treated as 4
case 3 | 4: # 3 gets treated as 4
data_type = 2
# pad till we have 4 otherwise struct.pack will freak out
if data_len == 3:
msg.data.append(0)
msg.data = msg.data[:4]
data = struct.pack(">hhhh", *[int(x) for x in msg.data])
case _:
self.logger.error(

View File

@@ -59,7 +59,7 @@ def viccan_to_string(viccan: VicCAN) -> str:
"""Converts a ROS2 VicCAN message to the serial string VicCAN format."""
# make sure we accept 3 digits and treat it as 4
if len(viccan.data) == 3:
viccan.data.append("0")
viccan.data.append(0)
# 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])
return f"can_relay_tovic,{viccan.mcu_name},{viccan.command_id}{data}\n"