Skip to content

Commit 930f9e9

Browse files
committed
Bump versions
1 parent 3fb18bc commit 930f9e9

File tree

3 files changed

+20
-18
lines changed

3 files changed

+20
-18
lines changed

docs/source/conf.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@
1111
project = "MAVez"
1212
copyright = "2025, The Pennsylvania State University Unmanned Aerial Systems Club"
1313
author = "The Pennsylvania State University Unmanned Aerial Systems Club"
14-
version = "3.5.1"
14+
version = "3.5.2"
1515

1616
# -- General configuration ---------------------------------------------------
1717
# https://www.sphinx-doc.org/en/master/usage/configuration.html#general-configuration

pyproject.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@ build-backend = "setuptools.build_meta"
44

55
[project]
66
name='MAVez'
7-
version='3.5.1'
7+
version='3.5.2'
88
description='An intuitive MAVLink library for ArduPilot via pymavlink'
99
authors=[
1010
{name='The Pennsylvania State University Unmanned Aerial Systems Club', email='psuuasofficial@gmail.com'}

src/MAVez/controller.py

Lines changed: 18 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -1026,15 +1026,19 @@ async def sync_clocks(self) -> int:
10261026
int: 0 if the clocks were synced successfully, otherwise an error code.
10271027
"""
10281028
self.logger.debug("[Flight] Syncing clocks...")
1029-
1029+
ALPHA = 0.5
10301030
NUM_SAMPLES = 10
10311031
i = 0
1032+
1033+
rtt_samples = []
1034+
offset_samples = []
1035+
10321036
while i < NUM_SAMPLES:
1033-
ts1 = time.monotonic_ns() - self.start_time
1037+
ts1 = time.monotonic_ns()
10341038
self.request_timesync(ts1)
10351039

10361040
response = await self.receive_timesync()
1037-
ts4 = time.monotonic_ns() - self.start_time
1041+
ts4 = time.monotonic_ns()
10381042

10391043
if isinstance(response, int):
10401044
self.logger.error("[Controller] Failed to sync clocks.")
@@ -1053,22 +1057,20 @@ async def sync_clocks(self) -> int:
10531057
if len(self.local_samples) > self.ROLLING_WINDOW:
10541058
self.local_samples.pop(0)
10551059
self.peer_samples.pop(0)
1056-
# rolling average for RTT
1057-
if self.rtt is None:
1058-
self.rtt = rtt
1059-
else:
1060-
self.rtt = (self.rtt * len(self.local_samples) + rtt) // (len(self.local_samples) + 1)
1061-
1062-
# rolling average for offset
1063-
if self.offset is None:
1064-
self.offset = offset
1065-
elif abs(self.offset - offset) > self.offset * 0.1: # if offset differs by more than 10%, ignore it
1066-
self.logger.debug("[Controller] Offset differs significantly, ignoring sample.")
1067-
else:
1068-
self.offset = (self.offset * len(self.local_samples) + offset) // (len(self.local_samples) + 1)
1060+
1061+
rtt_samples.append(rtt)
1062+
offset_samples.append(offset)
10691063

10701064
i += 1
10711065

1066+
rtt = sum(rtt_samples) / len(rtt_samples)
1067+
offset = sum(offset_samples) / len(offset_samples)
1068+
self.rtt = rtt
1069+
if self.offset:
1070+
self.offset = (1 - ALPHA) * self.offset + ALPHA * offset
1071+
else:
1072+
self.offset = offset
1073+
10721074
timesync_update = Message(
10731075
topic=f"{self.message_topic}_timesync_update" if self.message_topic else "timesync_update",
10741076
header={

0 commit comments

Comments
 (0)