Skip to content

Commit

Permalink
MAVLinkParam: remove decimal
Browse files Browse the repository at this point in the history
  • Loading branch information
meee1 committed Jan 15, 2024
1 parent 75c40eb commit 1edc52a
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 7 deletions.
6 changes: 3 additions & 3 deletions ExtLibs/ArduPilot/parampck.cs
Original file line number Diff line number Diff line change
Expand Up @@ -100,12 +100,12 @@ public static MAVLink.MAVLinkParamList unpack(byte[] data)
Array.Copy(data, dataPointer, vdata, 0, mapped.type_len);
dataPointer += mapped.type_len;

decimal? default_value = null;
double? default_value = null;
if (with_defaults) {
if ((flags & 1U) == 0) {
default_value = Convert.ToDecimal(v);
default_value = Convert.ToDouble(v);
} else {
default_value = Convert.ToDecimal(decode_value(mapped.type_format, data, dataPointer));
default_value = Convert.ToDouble(decode_value(mapped.type_format, data, dataPointer));
dataPointer += mapped.type_len;
}
}
Expand Down
8 changes: 4 additions & 4 deletions ExtLibs/Mavlink/MAVLinkParam.cs
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ public double Value
/// <summary>
/// Default value of parameter as a double, readonly, NaN if not available
/// </summary>
public readonly decimal? default_value = null;
public readonly double? default_value = null;

private MAV_PARAM_TYPE _typeap = 0;
public MAV_PARAM_TYPE TypeAP {
Expand Down Expand Up @@ -82,7 +82,7 @@ private MAVLinkParam()
/// <param name="name"></param>
/// <param name="value"></param>
/// <param name="wiretype"></param>
public MAVLinkParam(string name, double value, MAV_PARAM_TYPE wiretype, decimal? _default_value = null)
public MAVLinkParam(string name, double value, MAV_PARAM_TYPE wiretype, double? _default_value = null)
{
Name = name;
Type = wiretype;
Expand All @@ -97,7 +97,7 @@ public MAVLinkParam(string name, double value, MAV_PARAM_TYPE wiretype, decimal?
/// <param name="inputwire"></param>
/// <param name="wiretype"></param>
/// <param name="typeap"></param>
public MAVLinkParam(string name, byte[] inputwire, MAV_PARAM_TYPE wiretype, MAV_PARAM_TYPE typeap, decimal? _default_value = null)
public MAVLinkParam(string name, byte[] inputwire, MAV_PARAM_TYPE wiretype, MAV_PARAM_TYPE typeap, double? _default_value = null)
{
Name = name;
Type = wiretype;
Expand Down Expand Up @@ -129,7 +129,7 @@ public double GetValue()
(double)item.float_value
0.800000011920929
*/
return (double)(decimal)float_value;
return Math.Round((double)float_value, 7);
}

throw new FormatException("invalid type");
Expand Down

0 comments on commit 1edc52a

Please sign in to comment.