ArduPilot / MissionPlanner

Mission Planner Ground Control Station for ArduPilot (c# .net)
http://ardupilot.org/planner/
GNU General Public License v3.0
1.8k stars 2.42k forks source link

MAVLinkParam: fix rounding to 7 digits #3389

Closed robertlong13 closed 3 months ago

robertlong13 commented 3 months ago

Rounding to a fixed number of decimal places leads to over rounding small numbers and under-rounding big numbers. I first encountered this problem when dealing parameter values in the range of 10^-6 that kept getting way rounded off. That's not a common order of magnitude for a parameter in ArduPilot, but we shouldn't rule it out (in my case, they were part of a lua script; I don't think any official params are in this range).

Some samples from the "Immediate Window" in Visual Studio

(double)0.8f
0.800000011920929
Math.Round((double)0.8f, 7)
0.8
RoundToSignificantDigits((double)0.8f, 7)
0.8

(double)100.8f
100.80000305175781
Math.Round((double)100.8f, 7)
100.8000031
RoundToSignificantDigits((double)100.8f, 7)
100.8

(double)8e-9f
7.9999997737445483E-09
Math.Round((double)8e-9f, 7)
0
RoundToSignificantDigits((double)8e-9f, 7)
8E-09

Now, another thing to consider, do we actually need to round at all, or should we just be casting to double and be done with it? The only application I could think of where this rounding was important was string conversion, but we already correctly handle that in the ToString method.