Skip to content

Commit 6da2160

Browse files
committed
Merge pull request #594 from dronekit/rroche/time-warp
time warp!
2 parents c5412dd + 6776725 commit 6da2160

File tree

3 files changed

+18
-15
lines changed

3 files changed

+18
-15
lines changed

dronekit/__init__.py

Lines changed: 16 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@
3131
"""
3232

3333
from __future__ import print_function
34+
import monotonic
3435
import time
3536
import socket
3637
import sys
@@ -1231,7 +1232,7 @@ def listener(self, name, msg):
12311232
self._params_loaded = False
12321233
self._params_start = False
12331234
self._params_map = {}
1234-
self._params_last = time.time() # Last new param.
1235+
self._params_last = monotonic.monotonic() # Last new param.
12351236
self._params_duration = start_duration
12361237
self._parameters = Parameters(self)
12371238

@@ -1245,7 +1246,7 @@ def listener(_):
12451246
self._params_loaded = True
12461247
self.notify_attribute_listeners('parameters', self.parameters)
12471248

1248-
if not self._params_loaded and time.time() - self._params_last > self._params_duration:
1249+
if not self._params_loaded and monotonic.monotonic() - self._params_last > self._params_duration:
12491250
c = 0
12501251
for i, v in enumerate(self._params_set):
12511252
if v == None:
@@ -1254,7 +1255,7 @@ def listener(_):
12541255
if c > 50:
12551256
break
12561257
self._params_duration = repeat_duration
1257-
self._params_last = time.time()
1258+
self._params_last = monotonic.monotonic()
12581259

12591260
@self.on_message(['PARAM_VALUE'])
12601261
def listener(self, name, msg):
@@ -1272,7 +1273,7 @@ def listener(self, name, msg):
12721273
try:
12731274
if msg.param_index < msg.param_count and msg:
12741275
if self._params_set[msg.param_index] == None:
1275-
self._params_last = time.time()
1276+
self._params_last = monotonic.monotonic()
12761277
self._params_duration = start_duration
12771278
self._params_set[msg.param_index] = msg
12781279
self._params_map[msg.param_id] = msg.param_value
@@ -1296,18 +1297,18 @@ def listener(self, name, msg):
12961297
@handler.forward_loop
12971298
def listener(_):
12981299
# Send 1 heartbeat per second
1299-
if time.time() - self._heartbeat_lastsent > 1:
1300+
if monotonic.monotonic() - self._heartbeat_lastsent > 1:
13001301
self._master.mav.heartbeat_send(mavutil.mavlink.MAV_TYPE_GCS,
13011302
mavutil.mavlink.MAV_AUTOPILOT_INVALID, 0, 0, 0)
1302-
self._heartbeat_lastsent = time.time()
1303+
self._heartbeat_lastsent = monotonic.monotonic()
13031304

13041305
# Timeouts.
13051306
if self._heartbeat_started:
1306-
if self._heartbeat_error and self._heartbeat_error > 0 and time.time(
1307+
if self._heartbeat_error and self._heartbeat_error > 0 and monotonic.monotonic(
13071308
) - self._heartbeat_lastreceived > self._heartbeat_error:
13081309
raise APIException('No heartbeat in %s seconds, aborting.' %
13091310
self._heartbeat_error)
1310-
elif time.time() - self._heartbeat_lastreceived > self._heartbeat_warning:
1311+
elif monotonic.monotonic() - self._heartbeat_lastreceived > self._heartbeat_warning:
13111312
if self._heartbeat_timeout == False:
13121313
errprinter('>>> Link timeout, no heartbeat in last %s seconds' %
13131314
self._heartbeat_warning)
@@ -1316,7 +1317,7 @@ def listener(_):
13161317
@self.on_message(['HEARTBEAT'])
13171318
def listener(self, name, msg):
13181319
self._heartbeat_system = msg.get_srcSystem()
1319-
self._heartbeat_lastreceived = time.time()
1320+
self._heartbeat_lastreceived = monotonic.monotonic()
13201321
if self._heartbeat_timeout:
13211322
errprinter('>>> ...link restored.')
13221323
self._heartbeat_timeout = False
@@ -1326,7 +1327,7 @@ def listener(self, name, msg):
13261327
@handler.forward_loop
13271328
def listener(_):
13281329
if self._heartbeat_lastreceived:
1329-
self._last_heartbeat = time.time() - self._heartbeat_lastreceived
1330+
self._last_heartbeat = monotonic.monotonic() - self._heartbeat_lastreceived
13301331
self.notify_attribute_listeners('last_heartbeat', self.last_heartbeat)
13311332

13321333
@property
@@ -2044,7 +2045,7 @@ def initialize(self, rate=4, heartbeat_timeout=30):
20442045
self._handler.start()
20452046

20462047
# Start heartbeat polling.
2047-
start = time.time()
2048+
start = monotonic.monotonic()
20482049
self._heartbeat_error = heartbeat_timeout or 0
20492050
self._heartbeat_started = True
20502051
self._heartbeat_lastreceived = start
@@ -2132,10 +2133,10 @@ def wait_ready(self, *types, **kwargs):
21322133

21332134
# Wait for these attributes to have been set.
21342135
await = set(types)
2135-
start = time.time()
2136+
start = monotonic.monotonic()
21362137
while not await.issubset(self._ready_attrs):
21372138
time.sleep(0.1)
2138-
if time.time() - start > timeout:
2139+
if monotonic.monotonic() - start > timeout:
21392140
if raise_exception:
21402141
raise APIException('wait_ready experienced a timeout after %s seconds.' %
21412142
timeout)
@@ -2385,11 +2386,11 @@ def set(self, name, value, retries=3, wait_ready=False):
23852386
remaining = retries
23862387
while True:
23872388
self._vehicle._master.param_set_send(name, value)
2388-
tstart = time.time()
2389+
tstart = monotonic.monotonic()
23892390
if remaining == 0:
23902391
break
23912392
remaining -= 1
2392-
while time.time() - tstart < 1:
2393+
while monotonic.monotonic() - tstart < 1:
23932394
if name in self._vehicle._params_map and self._vehicle._params_map[name] == value:
23942395
return True
23952396
time.sleep(0.1)

requirements.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,3 +6,4 @@ psutil>=3.0.0
66
mock>=1.3.0
77
six>=1.9.0
88
dronekit-sitl>=3.0,<=3.99999
9+
monotonic<1.0

setup.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
author='3D Robotics',
1313
install_requires=[
1414
'pymavlink>=1.1.62',
15+
'monotonic<1.0'
1516
],
1617
1718
classifiers=[

0 commit comments

Comments
 (0)