Skip to content

Commit

Permalink
Enforce little endian over native byte order
Browse files Browse the repository at this point in the history
  • Loading branch information
cbrxyz committed Mar 23, 2024
1 parent 7c2dff0 commit 83f15e7
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ class ThrusterId(IntEnum):


@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 @@ -74,7 +74,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 @@ -88,7 +88,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 @@ -18,7 +18,7 @@ class ActuatorPacketId(IntEnum):


@dataclass
class ActuatorSetPacket(Packet, msg_id=0x03, subclass_id=0x00, payload_format="BB"):
class ActuatorSetPacket(Packet, msg_id=0x03, subclass_id=0x00, payload_format="<BB"):
"""
Packet used by the actuator board to set a specific valve.
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

0 comments on commit 83f15e7

Please sign in to comment.