From 6ec3f826502e405ddc84549c45b539348d56af73 Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar Do Carmo Lucas" Date: Fri, 10 Feb 2017 11:29:26 +0100 Subject: [PATCH] convert paratenter set value to single precision floating point number (the type used by low level mavlink messages) before sending/comparing it This fixes bougus "timeout setting parameter x to y" messages when the passed double value and it's single representation differ --- dronekit/__init__.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/dronekit/__init__.py b/dronekit/__init__.py index a11b9eb50..ad0baa045 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -45,6 +45,7 @@ import types import threading import math +import struct import copy import collections from pymavlink.dialects.v10 import ardupilotmega @@ -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: