Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove padding from python struct packing #1150

Merged
merged 1 commit into from
Mar 2, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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.

Expand Down Expand Up @@ -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.

Expand All @@ -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.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand All @@ -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:
Expand All @@ -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)
Expand Down
Loading