Skip to content

Commit

Permalink
convert paratenter set value to single precision floating point numbe…
Browse files Browse the repository at this point in the history
…r (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
  • Loading branch information
amilcarlucas authored and mrpollo committed Apr 21, 2017
1 parent 62eb688 commit 4d05c05
Showing 1 changed file with 3 additions and 1 deletion.
4 changes: 3 additions & 1 deletion dronekit/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
import types
import threading
import math
import struct
import copy
import collections
from pymavlink.dialects.v10 import ardupilotmega
Expand Down Expand Up @@ -2433,7 +2434,8 @@ def set(self, name, value, retries=3, wait_ready=False):
# instead just wait until the value itself was changed

name = name.upper()
value = float(value)
# convert to single precision floating point number (the type used by low level mavlink messages)
value = float(struct.unpack('f', struct.pack('f', value))[0])
success = False
remaining = retries
while True:
Expand Down

0 comments on commit 4d05c05

Please sign in to comment.