Skip to content

Commit

Permalink
common.xml: deprecate the _INT frames (mavlink#2092)
Browse files Browse the repository at this point in the history
* 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>
  • Loading branch information
peterbarker and hamishwillee committed Mar 23, 2024
1 parent 1e04d8b commit fb5d56c
Showing 1 changed file with 17 additions and 12 deletions.
29 changes: 17 additions & 12 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -233,7 +233,7 @@
Some deprecated frames do not follow these conventions (e.g. MAV_FRAME_BODY_NED and MAV_FRAME_BODY_OFFSET_NED).
</description>
<entry value="0" name="MAV_FRAME_GLOBAL">
<description>Global (WGS84) coordinate frame + MSL altitude. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL).</description>
<description>Global (WGS84) coordinate frame + altitude relative to mean sea level (MSL).</description>
</entry>
<entry value="1" name="MAV_FRAME_LOCAL_NED">
<description>NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth.</description>
Expand All @@ -242,16 +242,20 @@
<description>NOT a coordinate frame, indicates a mission command.</description>
</entry>
<entry value="3" name="MAV_FRAME_GLOBAL_RELATIVE_ALT">
<description>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 location.</description>
<description>
Global (WGS84) coordinate frame + altitude relative to the home position.
</description>
</entry>
<entry value="4" name="MAV_FRAME_LOCAL_ENU">
<description>ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth.</description>
</entry>
<entry value="5" name="MAV_FRAME_GLOBAL_INT">
<description>Global (WGS84) coordinate frame (scaled) + MSL altitude. First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude over mean sea level (MSL).</description>
<deprecated since="2024-03" replaced_by="MAV_FRAME_GLOBAL">Use MAV_FRAME_GLOBAL in COMMAND_INT (and elsewhere) as a synonymous replacement.</deprecated>
<description>Global (WGS84) coordinate frame (scaled) + altitude relative to mean sea level (MSL).</description>
</entry>
<entry value="6" name="MAV_FRAME_GLOBAL_RELATIVE_ALT_INT">
<description>Global (WGS84) coordinate frame (scaled) + altitude relative to the home position. First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude with 0 being at the altitude of the home location.</description>
<deprecated since="2024-03" replaced_by="MAV_FRAME_GLOBAL_RELATIVE_ALT">Use MAV_FRAME_GLOBAL_RELATIVE_ALT in COMMAND_INT (and elsewhere) as a synonymous replacement.</deprecated>
<description>Global (WGS84) coordinate frame (scaled) + altitude relative to the home position. </description>
</entry>
<entry value="7" name="MAV_FRAME_LOCAL_OFFSET_NED">
<description>NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle.</description>
Expand All @@ -265,10 +269,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>
</entry>
<entry value="11" name="MAV_FRAME_GLOBAL_TERRAIN_ALT_INT">
<description>Global (WGS84) coordinate frame (scaled) with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.</description>
<deprecated since="2024-03" replaced_by="MAV_FRAME_GLOBAL_TERRAIN_ALT">Use MAV_FRAME_GLOBAL_TERRAIN_ALT in COMMAND_INT (and elsewhere) as a synonymous replacement.</deprecated>
<description>Global (WGS84) coordinate frame (scaled) with AGL altitude (altitude at ground level).</description>
</entry>
<entry value="12" name="MAV_FRAME_BODY_FRD">
<description>FRD local tangent frame (x: Forward, y: Right, z: Down) with origin that travels with vehicle. The forward axis is aligned to the front of the vehicle in the horizontal plane.</description>
Expand Down Expand Up @@ -4894,10 +4899,10 @@
<field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.</field>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="coordinate_frame" enum="MAV_FRAME">Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11</field>
<field type="uint8_t" name="coordinate_frame" enum="MAV_FRAME">Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)</field>
<field type="uint16_t" name="type_mask" enum="POSITION_TARGET_TYPEMASK" display="bitmask">Bitmap to indicate which dimensions should be ignored by the vehicle.</field>
<field type="int32_t" name="lat_int" units="degE7">X Position in WGS84 frame</field>
<field type="int32_t" name="lon_int" units="degE7">Y Position in WGS84 frame</field>
<field type="int32_t" name="lat_int" units="degE7">Latitude in WGS84 frame</field>
<field type="int32_t" name="lon_int" units="degE7">Longitude in WGS84 frame</field>
<field type="float" name="alt" units="m">Altitude (MSL, Relative to home, or AGL - depending on frame)</field>
<field type="float" name="vx" units="m/s">X velocity in NED frame</field>
<field type="float" name="vy" units="m/s">Y velocity in NED frame</field>
Expand All @@ -4911,10 +4916,10 @@
<message id="87" name="POSITION_TARGET_GLOBAL_INT">
<description>Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way.</description>
<field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.</field>
<field type="uint8_t" name="coordinate_frame" enum="MAV_FRAME">Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11</field>
<field type="uint8_t" name="coordinate_frame" enum="MAV_FRAME">Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)</field>
<field type="uint16_t" name="type_mask" enum="POSITION_TARGET_TYPEMASK" display="bitmask">Bitmap to indicate which dimensions should be ignored by the vehicle.</field>
<field type="int32_t" name="lat_int" units="degE7">X Position in WGS84 frame</field>
<field type="int32_t" name="lon_int" units="degE7">Y Position in WGS84 frame</field>
<field type="int32_t" name="lat_int" units="degE7">Latitude in WGS84 frame</field>
<field type="int32_t" name="lon_int" units="degE7">Longitude in WGS84 frame</field>
<field type="float" name="alt" units="m">Altitude (MSL, AGL or relative to home altitude, depending on frame)</field>
<field type="float" name="vx" units="m/s">X velocity in NED frame</field>
<field type="float" name="vy" units="m/s">Y velocity in NED frame</field>
Expand Down

0 comments on commit fb5d56c

Please sign in to comment.