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

common.xml: deprecate the _INT frames #2092

Merged
merged 8 commits into from
Mar 21, 2024

Conversation

peterbarker
Copy link
Contributor

@peterbarker peterbarker commented Mar 7, 2024

the frame of an altitude is not dependent on how the altitude is being transported (how other fields in the same message are being transported).

ArduPilot has treated these frames to be the same as the non-_INT equivalents in most places for a very long time.

We can save some confusion and perhaps a small amount of flash space if we remove the _INT frames


HamishW Edit

This marks MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT as deprecated in favour of using their non-_INT alternatives, and simplifies the descriptions of scaling in the various messages.

The _INT variants were clearly created to allow specification of frames where the values of lat/lon are scaled, to go with the corresponding ones that don't make any statements about scaling. However these are used mainly in COMMAND_INT which explicitly specifies the scaling anyway - so the two values are synonyms (also true elsewhere these are used).

ArduPilot and MAVSDK, and presumably PX4 tend to implement code such that the INT versions are just synonyms. But sometimes one option or the other is forgotten, and this results in bugs. The idea here is to deprecate the pointless options, and eventually stop them being sent by GCS.

the frame of an altitude is not dependent on how the altitude is being transported (how other fields in the same message are being transported).

ArduPilot has treated these frames to be the same as the non-_INT equivalents in most places for a very long time.

We can save some confusion and perhaps a small amount of flash space if we remove the _INT frames
@peterbarker
Copy link
Contributor Author

I've created a PR on the ArduPilot repository for discussion at our next DevCall.

@peterbarker
Copy link
Contributor Author

We discussed at our DevCall and we think this is a good change. Just waiting for some discussion upstream.

@hamishwillee
Copy link
Collaborator

The _INT cases explicitly specify that lat/lon are scaled 1E7, while the others imply they are not. PX4 handles the case to make the decision about the way to decode the values.

I'll raise in the meeting this evening.

@nexton-winjeel
Copy link
Contributor

I wasn't in the ArduPilot dev call, but my assumption is the problem is:

  • the frame is independent from the types used to transport the position fields in a message.
  • the latitude/longitude scaling should be determined from the type of the field:
    • no scaling if the field is a float;
    • 1E7 scaling if the field is int32_t.

@peterbarker
Copy link
Contributor Author

peterbarker commented Mar 13, 2024 via email

@hamishwillee
Copy link
Collaborator

OK, so I think I get this.

You're basically always scaling when sending in a COMMAND_INT irrespective of the _INT type, possibly because that command says what the scaling of lat/lon should be and otherwise the frames are the same. You're also saying that in the other places MAV_FRAME is used, the differences specified in _INT are irrelevant. Right?

This made sense to @julianoes who has implemented this and treated those frames as synonymous.

  1. I'm wondering if we should remove the field mappings in the frame definitions, as it is "by comparison" that they are confusing.
    So for example we currently have for the non-INT type:

    Global (WGS84) coordinate frame + altitude relative to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home position.

    I read that as "the values are unscaled" if you're using this frame when I compare to the _INT version.

    Could we reasonably have:

    Global (WGS84) coordinate frame + altitude relative to the home position (altitudes are positive and 0 is the altitude of the home position).

    In any command that uses this we'd need to make sure the scaling was specified or implied.

  2. If we're going to do this, there are numerous places where we recommend the _INT variants. We should also:

Sorry if I'm being dim. I'm a bit worried about touching frames - it always ends badly.

@peterbarker
Copy link
Contributor Author

You're basically always scaling when sending in a COMMAND_INT irrespective of the _INT type, possibly because that command says what the scaling of lat/lon should be and otherwise the frames are the same.

Correct. COMMAND_INT specifying the values as being 1e7 and the frame specifying a multiplier leads to a natural conundrum of which to trust. So rely on the message (in this case COMMAND_INT) to specify the multiplier as it knows what the storage for the data looks like.

You're also saying that in the other places MAV_FRAME is used, the differences specified in _INT are irrelevant. Right?

Yes. Many years ago we found many bugs in the way we treat these frames - leading to a lack of correct multiplication or incorrect application thereof.

commit b0ea662c9b72d1db4ab74ba83eb8b80611c87881
Author: Peter Barker <pbarker@barker.dropbear.id.au>
Date:   Tue Dec 3 17:11:22 2019 +1100

    AP_Mission: consider _INT frames equivalent to non _INT variants
    
    AP_Mission: consider TERRAIN_ALT_INT equivalent to TERRAIN_ALT
    
    AP_Mission: consider RELATIVE_ALT_INT equivalent to RELATIVE_ALT
    
    AP_Mission: consider GLOBAL_INT equivalent to GLOBAL

This made sense to @julianoes who has implemented this and treated those frames as synonymous.

Nice!

1. I'm wondering if we should remove the field mappings in the frame definitions, as it is "by comparison" that they are confusing.
   So for example we currently have for the non-INT type:
   > Global (WGS84) coordinate frame + altitude relative to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home position.
   
   
   I read that as "the values are unscaled" if you're using this frame when I compare to the `_INT` version.
   Could we reasonably have:
   > Global (WGS84) coordinate frame + altitude relative to the home position (altitudes are positive and 0 is the altitude of the home position).

I agree.

   In any command that uses this we'd need to make sure the scaling was specified or implied.

Yes.

Sorry if I'm being dim. I'm a bit worried about touching frames - it always ends badly.

:-)

@Maarrk
Copy link
Contributor

Maarrk commented Mar 19, 2024

We can save some confusion

I guess I am the confused person 😄

If I can chip in as mostly a user, and a very rare and novice contributor to either project, this would make my life easier. Recently we were trying to use a new feature of ArduPilot and ran exactly into the issue this change would prevent.

This is my current understanding, relying mostly on documentation:

I assume that MAV_FRAME sent in COMMAND_INT should behave the same way for MAV_FRAME_GLOBAL and MAV_FRAME_GLOBAL_INT (a search of the repo shows them together), but only the first one was accepted in the check.

quoted from ArduPilot/ardupilot#26387

@hamishwillee
Copy link
Collaborator

@Maarrk Yes. The theory is that these two frames should always be synonymous when used in a COMMAND_INT. However because they both exist and this is not always obvious, not every usage correctly allows either frame to be used.

Peter wants to clarify this. I'm supportive. I just know that frame definitions have historically caused much pain to modify.

@Maarrk
Copy link
Contributor

Maarrk commented Mar 20, 2024

Do you think there could be a mention of that in the command microservice documentation? Especially since it explicitly forbids using an unexpected frame:

Note that it is an error to ignore the specified frame and use some other arbitrary frame.

Proposed addition (I can make the PR to devguide if you think it's OK):

The message type COMMAND_INT implies encoding of global location as integers, deprecating separate frames ending with _INT. For backwards compatibility, flight stacks are advised to support the deprecated _INT frames and treat them the same as the MAV_FRAME_GLOBAL and MAV_FRAME_GLOBAL_RELATIVE_ALT counterpart.

I hope it's not too verbose, but past me would appreciate it.

Thank you both for taking this on and for your commitment to stability!

@hamishwillee
Copy link
Collaborator

Thanks @Maarrk
Yes, if this goes in we will need to update the devguide - thanks for pointing that out. However I want this PR to get merged before we make any changes in the guide. When that happens I will make some changes, using your words as inspriration.

@peterbarker
Copy link
Contributor Author

peterbarker commented Mar 20, 2024 via email

@@ -280,10 +280,11 @@
<description>This is the same as MAV_FRAME_BODY_FRD.</description>
</entry>
<entry value="10" name="MAV_FRAME_GLOBAL_TERRAIN_ALT">
<description>Global (WGS84) coordinate frame with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model.</description>
<description>Global (WGS84) coordinate frame with AGL altitude (altitude at ground level).</description>
Copy link
Collaborator

Choose a reason for hiding this comment

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

Note, I have removed mention of waypoint because the location depends on context - it doesn't have to be a waypoint.

I removed the mention of terrain map because again, this depends on context - it might come from a LIDAR or similar.

@hamishwillee
Copy link
Collaborator

@julianoes Can you sanity check this one too? As part of that, can you check whether PX4 does indeed use these as synonyms and support either in the cases where the command is sent?

I'll ping in Auterion too.

@julianoes
Copy link
Collaborator

I doubt PX4 does it correct yet, we'll have to fix that.

@hamishwillee
Copy link
Collaborator

@auturgy @peterbarker Any final words on this one? If not, I'll merge (probably next week). Feedback from Silvan and Alessandro in Auterion positive.

@peterbarker
Copy link
Contributor Author

@auturgy @peterbarker Any final words on this one? If not, I'll merge (probably next week). Feedback from Silvan and Alessandro in Auterion positive.

LGTM, thanks!

Perhaps fewer commits would be nice, but that's it.

@auturgy
Copy link
Collaborator

auturgy commented Mar 21, 2024

Commits will get squashed on merge. Probably no need to wait until next week.

@hamishwillee
Copy link
Collaborator

OK. I'm feeling brave.,

@hamishwillee hamishwillee merged commit fabfb1d into mavlink:master Mar 21, 2024
13 checks passed
peterbarker added a commit to peterbarker/mavlink that referenced this pull request Mar 23, 2024
* common.xml: deprecate the _INT frames

the frame of an altitude is not dependent on how the altitude is being transported (how other fields in the same message are being transported).

ArduPilot has treated these frames to be the same as the non-_INT equivalents in most places for a very long time.

We can save some confusion and perhaps a small amount of flash space if we remove the _INT frames

* Replace the deprecated types where they are used

* Rename lat/lon from X pos/Y pos in WGS84 frame

* Update message_definitions/v1.0/common.xml

* simply the global frames

* Apply suggestions from code review

* Apply suggestions from code review

* Update common.xml

---------

Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
peterbarker added a commit to ArduPilot/mavlink that referenced this pull request Mar 23, 2024
* common.xml: deprecate the _INT frames

the frame of an altitude is not dependent on how the altitude is being transported (how other fields in the same message are being transported).

ArduPilot has treated these frames to be the same as the non-_INT equivalents in most places for a very long time.

We can save some confusion and perhaps a small amount of flash space if we remove the _INT frames

* Replace the deprecated types where they are used

* Rename lat/lon from X pos/Y pos in WGS84 frame

* Update message_definitions/v1.0/common.xml

* simply the global frames

* Apply suggestions from code review

* Apply suggestions from code review

* Update common.xml

---------

Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
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

6 participants