Skip to content

Commit 4d05c05

Browse files
amilcarlucasmrpollo
authored andcommitted
convert paratenter set value to single precision floating point number (the type used by low level mavlink messages) before sending/comparing it (#707)
This fixes bougus "timeout setting parameter x to y" messages when the passed double value and it's single representation differ
1 parent 62eb688 commit 4d05c05

File tree

1 file changed

+3
-1
lines changed

1 file changed

+3
-1
lines changed

dronekit/__init__.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@
4545
import types
4646
import threading
4747
import math
48+
import struct
4849
import copy
4950
import collections
5051
from pymavlink.dialects.v10 import ardupilotmega
@@ -2433,7 +2434,8 @@ def set(self, name, value, retries=3, wait_ready=False):
24332434
# instead just wait until the value itself was changed
24342435

24352436
name = name.upper()
2436-
value = float(value)
2437+
# convert to single precision floating point number (the type used by low level mavlink messages)
2438+
value = float(struct.unpack('f', struct.pack('f', value))[0])
24372439
success = False
24382440
remaining = retries
24392441
while True:

0 commit comments

Comments
 (0)