Skip to content

Conversation

@IamPete1
Copy link
Contributor

@IamPete1 IamPete1 commented May 30, 2025

This fixes to issues one minor and one more complicated.

Firstly the easy one, I forgot the AIS_NAV prefix on the UNDER_WAY value in the AIS_NAV_STATUS enum.

The second one is more complicated. I chose a bad type/unit for the turn rate value. I picked a int8, I guess because its sent as a int8 in the AIVDM protocol. However, there its sent as deg/min with this formula:

image
https://gpsd.gitlab.io/gpsd/AIVDM.html#_types_1_2_and_3_position_report_class_a

We need to represent a max value of 708 degrees per minute. That is 11.8 degrees per second or 1180 centi-degrees per second.

1180 will not fit in a int8, we only get upto 127.

There are two solutions.

  • Increase the size of the field, a int16 will hold up to 32767 so we would be fine with centi-degrees per second. However that would change the shape of the message.

  • The second solution is to change the unit and keep the existing size. If we were to go to deci-degrees we can now represent up to 12.7 degrees per second, larger than the 11.8 we need. This is the change I have proposed in this PR. Deci-degrees is a nasty unit, we could go to degrees but with a max value of 11 we would be loosing lots of resolution.

If anyone has any better ideas they would be very welcome.

This second look at the AIS stuff is a result of AP getting AIS avoidance ArduPilot/ardupilot#30185.

@IamPete1
Copy link
Contributor Author

I have done a pymavlink PR to add the new unit to the schema so this will pass checks. ArduPilot/pymavlink#1053

<field type="uint16_t" name="heading" units="cdeg">True heading</field>
<field type="uint16_t" name="velocity" units="cm/s">Speed over ground</field>
<field type="int8_t" name="turn_rate" units="cdeg/s">Turn rate</field>
<field type="int8_t" name="turn_rate" units="ddeg/s">Turn rate, 0.1 degrees per second</field>
Copy link
Collaborator

@hamishwillee hamishwillee Jun 4, 2025

Choose a reason for hiding this comment

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

@IamPete1 I have no problem with this technically but my assumption is that you need no rate higher than 12.7 degrees per second and that you also need both positive and negative directions.

I don't think that the units are checked in the CRCC extra - so this change could happen without the message being discarded.
It is therefore better than trying to change the size of the type if you don't want to break consumers "visibly"

BUT consumers won't know about it and non-updated systems will assume they are getting cdeg/s. Do you know who will be bitten by this change? How many releases of their software will be broken? Can they updates?

The only other alternative is to add a new turn rate field with the right size and deprecate the old one.

IN any case, will need to wait on XSD.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

my assumption is that you need no rate higher than 12.7 degrees per second and that you also need both positive and negative directions.

That is correct, the ADVIM AIS protocol maxes out at 11.8 degrees per second. I'm not sure what is actually sent over the air, but I guess it would be similar. ADVIM is certainly the industry standard.

BUT consumers won't know about it and non-updated systems will assume they are getting cdeg/s. Do you know who will be bitten by this change? How many releases of their software will be broken? Can they updates?

As far as I know there are no existing consumers doing anything important, Mission planner plots AIS vessels with turn rate, but only as feedback to the user. AP is the only publisher of these messages as far as I know, it has been faithfully filling in the value in cdeg/second and overflowing the int8. So anyone trying to use the data for anything would currently be having a bad time in anycase.

@IamPete1
Copy link
Contributor Author

I have added a update of the pymavlink sub module to latest, this includes the schema changes this needs.

<enum name="AIS_NAV_STATUS">
<description>Navigational status of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html</description>
<entry value="0" name="UNDER_WAY">
<entry value="0" name="AIS_NAV_UNDER_WAY">
Copy link
Collaborator

@hamishwillee hamishwillee Jun 18, 2025

Choose a reason for hiding this comment

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

Should we fix up the whole enum while we are here? (enum values are supposed to use enum prefix)

Suggested change
<entry value="0" name="AIS_NAV_UNDER_WAY">
<entry value="0" name="AIS_NAV_STATUS_UNDER_WAY">

Copy link
Collaborator

@hamishwillee hamishwillee Jun 18, 2025

Choose a reason for hiding this comment

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

Note, you would have to update the things that use these - but its a build time break, not a runtime break, so IMO makes sense for consistency. If you're fixing one you might as well fix them all up to the right prefxi.

Copy link
Collaborator

Choose a reason for hiding this comment

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

Rationale for proposed changed (prefix AIS_NAV_STATUS to enums) is to comply with pattern of using enum name in each enum value. This prevents clashes and is a good pattern.
I suggest leaving to Pete - it's good practice but I don't see it as a blocker in this case.

Copy link
Collaborator

Choose a reason for hiding this comment

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

@IamPete1 What are your thoughts on this?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I have added the STATUS, I would guess there are no current users of the individual enum values. This enum is the same as the AVIDM AIS one, so in AP we just use the incoming value directly without having to do any conversion.

Copy link
Collaborator

@hamishwillee hamishwillee left a comment

Choose a reason for hiding this comment

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

I think this makes sense. Am adding to the dev call for discussion.

@hamishwillee hamishwillee self-requested a review June 18, 2025 08:29
@hamishwillee
Copy link
Collaborator

Can you also drop the last commit and rebase. If we need to I'll pull the latest pymavlink

@IamPete1
Copy link
Contributor Author

Dropped the pymavlink change, added the STATUS and rebased.

Copy link
Collaborator

@hamishwillee hamishwillee left a comment

Choose a reason for hiding this comment

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

@peterbarker We intend to merge this. Note enum name changes. Will you be affected.

@hamishwillee
Copy link
Collaborator

hamishwillee commented Jul 31, 2025

@IamPete1 I'm just checking in with Auterion, who might also use this - as a courtesy. If I haven't merged this by next week feel free to ping me and I will do so.

Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

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

The problem here is that any pymavlink-based scripts which are using this enumeration will break at runtime, not compile-time. (And other mavlink bindings which use the enumeration names for run-time symbols)

Admittedly I don't think that's likely, but its still rude to do this to people.

Same reason we have the compatiblity code for the tailsitter enumerations.

@TomasTwardzik
Copy link

Thank you @IamPete1 and @hamishwillee for looking into the issues with AIS_VESSEL message. I fully agree that centi-degree unit, with 8bit integer range is cursed at best.
The proposed change to deci-degrees while suitable for your exact use case, does not resolve the issue for many boats, it just pushes the bar for breaking the message to higher signal value, without resolving the underlying problem. I understand that you suggested this to fit the constraint of 8 bits, but given what @peterbarker said about breaking runtime, maybe we could actually make a lasting change, since breaking of compatibility is already at play. Float16 would probably give all future users good enough base to build on top of.

@IamPete1
Copy link
Contributor Author

IamPete1 commented Aug 4, 2025

The proposed change to deci-degrees while suitable for your exact use case, does not resolve the issue for many boats, it just pushes the bar for breaking the message to higher signal value, without resolving the underlying problem.

I disagree, the problem is solved, with the change we cover the whole range specified in the AIS spec. We will never get a larger value. The only use case for more range would be if your generating vessels from some other method and re-using this MAVLink message.

For reference this is the spec for rate of turn (https://www.navcen.uscg.gov/ais-class-a-reports):
image

So the maximum value we will ever see is 708 deg per min. This is 11.8 deg per second. Deci-degrees int8 gets us 12.7 deg per second.

@TomasTwardzik
Copy link

@IamPete1 My bad I did not read thoroughly enough the spec, there is saturation value for turning at rates higher than 10deg/min, which the proposed deci-degrees cover fully. As this is the case, the issue is solved.

@hamishwillee hamishwillee merged commit 8384e90 into mavlink:master Aug 5, 2025
19 checks passed
hamishwillee pushed a commit to hamishwillee/mavlink that referenced this pull request Aug 5, 2025
@hamishwillee
Copy link
Collaborator

Thanks for resolving that @IamPete1 and @TomasTwardzik .

OK, this is going in. Both of you will need to update the enum values if you reference them once the mavlink/mavlink fork goes into your respective flight stack trees - (Pete, see ArduPilot#417)

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.

5 participants