From 842cdb8fef3dc5b068742f3944a8cb7562bd6041 Mon Sep 17 00:00:00 2001 From: andrew-aj Date: Fri, 1 Mar 2024 17:46:26 -0500 Subject: [PATCH] removed padding between struct members --- .../sub9_thrust_and_kill_board/packets.py | 6 +++--- .../drivers/mil_usb_to_can/mil_usb_to_can/sub9/packet.py | 8 ++++---- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/SubjuGator/drivers/sub9_thrust_and_kill_board/sub9_thrust_and_kill_board/packets.py b/SubjuGator/drivers/sub9_thrust_and_kill_board/sub9_thrust_and_kill_board/packets.py index f609c1c42..93d892fd3 100644 --- a/SubjuGator/drivers/sub9_thrust_and_kill_board/sub9_thrust_and_kill_board/packets.py +++ b/SubjuGator/drivers/sub9_thrust_and_kill_board/sub9_thrust_and_kill_board/packets.py @@ -19,7 +19,7 @@ class HeartbeatReceivePacket(Packet, msg_id=0x02, subclass_id=0x01, payload_form @dataclass -class ThrustSetPacket(Packet, msg_id=0x02, subclass_id=0x02, payload_format="Bf"): +class ThrustSetPacket(Packet, msg_id=0x02, subclass_id=0x02, payload_format="=Bf"): """ Packet to set the speed of a specific thruster. @@ -71,7 +71,7 @@ class KillStatus(IntEnum): @dataclass -class KillSetPacket(Packet, msg_id=0x02, subclass_id=0x03, payload_format="BB"): +class KillSetPacket(Packet, msg_id=0x02, subclass_id=0x03, payload_format="=BB"): """ Packet sent by the motherboard to set/unset the kill. @@ -85,7 +85,7 @@ class KillSetPacket(Packet, msg_id=0x02, subclass_id=0x03, payload_format="BB"): @dataclass -class KillReceivePacket(Packet, msg_id=0x02, subclass_id=0x04, payload_format="BB"): +class KillReceivePacket(Packet, msg_id=0x02, subclass_id=0x04, payload_format="=BB"): """ Packet sent by the motherboard to set/unset the kill. diff --git a/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub9/packet.py b/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub9/packet.py index 59ddc3a72..06f625b9b 100644 --- a/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub9/packet.py +++ b/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub9/packet.py @@ -117,7 +117,7 @@ def _calculate_checksum(cls, data: bytes) -> tuple[int, int]: def __bytes__(self): payload = struct.pack(self.payload_format, *self.__dict__.values()) data = struct.pack( - f"BBBBH{len(payload)}s", + f"=BBBBH{len(payload)}s", SYNC_CHAR_1, SYNC_CHAR_2, self.msg_id, @@ -126,7 +126,7 @@ def __bytes__(self): payload, ) checksum = self._calculate_checksum(data[2:]) - return data + struct.pack("BB", *checksum) + return data + struct.pack("=BB", *checksum) @classmethod def from_bytes(cls, packed: bytes) -> Packet: @@ -141,12 +141,12 @@ def from_bytes(cls, packed: bytes) -> Packet: if msg_id in _packet_registry and subclass_id in _packet_registry[msg_id]: subclass = _packet_registry[msg_id][subclass_id] payload = packed[6:-2] - if struct.unpack("BB", packed[-2:]) != cls._calculate_checksum( + if struct.unpack("=BB", packed[-2:]) != cls._calculate_checksum( packed[2:-2], ): raise ChecksumException( subclass, - struct.unpack("BB", packed[-2:]), + struct.unpack("=BB", packed[-2:]), cls._calculate_checksum(packed[2:-2]), ) unpacked = struct.unpack(subclass.payload_format, payload)