3 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
2 changed files with 35 additions and 3 deletions

View File

@@ -1,4 +1,5 @@
from warnings import deprecated from warnings import deprecated
import time
import rclpy import rclpy
from rclpy.node import Node from rclpy.node import Node
from rclpy.executors import ExternalShutdownException from rclpy.executors import ExternalShutdownException
@@ -17,8 +18,9 @@ from .connector import (
from .convert import string_to_viccan from .convert import string_to_viccan
import threading import threading
from astra_msgs.msg import VicCAN from builtin_interfaces.msg import Time
from std_msgs.msg import String from std_msgs.msg import String
from astra_msgs.msg import VicCAN, McuVersion
class Anchor(Node): class Anchor(Node):
@@ -47,6 +49,8 @@ class Anchor(Node):
Instead, it converts them to VicCAN messages first. 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 connector: Connector
def __init__(self): def __init__(self):
@@ -158,6 +162,12 @@ class Anchor(Node):
"/anchor/to_vic/debug", "/anchor/to_vic/debug",
20, 20,
) )
# MCU Version publisher
self.mcu_version_pub_ = self.create_publisher(
McuVersion,
"/anchor/from_vic/mcu_version",
20,
)
# Subscribers # Subscribers
self.tovic_sub_ = self.create_subscription( self.tovic_sub_ = self.create_subscription(
@@ -173,7 +183,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,
@@ -185,6 +195,8 @@ class Anchor(Node):
20, 20,
) )
self.mcu_versions: dict[str, McuVersion] = {}
# Close devices on exit # Close devices on exit
atexit.register(self.cleanup) atexit.register(self.cleanup)
@@ -231,6 +243,26 @@ class Anchor(Node):
elif msg.mcu_name == "citadel" or msg.mcu_name == "digit": elif msg.mcu_name == "citadel" or msg.mcu_name == "digit":
self.fromvic_bio_pub_.publish(msg) 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): def main(args=None):
try: try: