Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Grab param defaults and display in full list #2907

Merged
merged 4 commits into from Jul 20, 2022

Conversation

IamPete1
Copy link
Member

Implementation of updated ftp format per ArduPilot/ardupilot#20972

Displays all defualt values and adds tick box to only show params which have a none default value.
image

This is the full list only, still works with older version new stuff is hidden in that case.

Would be nice to make the save to file have a option to only save none defualts too.

Only draft because needs the AP pr merged first.

case 'i': return BitConverter.ToUInt32(data, startIndex);
case 'f': return BitConverter.ToSingle(data, startIndex);
case 'b': return (sbyte)data[startIndex];
case 'h': return (short)BitConverter.ToUInt16(data, startIndex);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

whats the intent here?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I was getting -1 warping to int max. This matches the return types from here:

byte uint8_value { get { return data[0]; } }
sbyte int8_value { get { return (sbyte)data[0]; } }
ushort uint16_value { get { return BitConverter.ToUInt16(data, 0); } }
short int16_value { get { return BitConverter.ToInt16(data, 0); } }
UInt32 uint32_value { get { return BitConverter.ToUInt32(data, 0); } }
Int32 int32_value { get { return BitConverter.ToInt32(data, 0); } }
[IgnoreDataMember]
public float float_value { get { return BitConverter.ToSingle(data, 0); } }

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

should we be casting? or reading in the correct format? ie ToUint16 vs ToInt16 ?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Your right, it looks like I just have the wrong conversion. Copy and paste fail on my part.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Changed to use correct types.

@@ -97,6 +100,16 @@ public static MAVLink.MAVLinkParamList unpack(byte[] data)
Array.Copy(data, dataPointer, vdata, 0, mapped.type_len);
dataPointer += mapped.type_len;

double default_value = Double.NaN;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

can we change this to "decimal" from double. the reason being a recent rounding issue, and decimal internally deals with this better.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

changed to a nullable decimal decimal?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

sure. makes sence

@IamPete1 IamPete1 marked this pull request as ready for review July 20, 2022 08:34
@IamPete1
Copy link
Member Author

IamPete1 commented Jul 20, 2022

AP support for this just got merged, I have also just retested with stable AP 4.2 and it still works with this change.

@meee1
Copy link
Contributor

meee1 commented Jul 20, 2022

final confirmation. you happy with this now?

@IamPete1
Copy link
Member Author

@meee1 yep, I think so. Thanks.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

2 participants