Skip to content

Commit

Permalink
Rename lat/lon from X pos/Y pos in WGS84 frame
Browse files Browse the repository at this point in the history
  • Loading branch information
hamishwillee committed Mar 20, 2024
1 parent 72fc107 commit 57632d7
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -5803,8 +5803,8 @@
<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 = 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 @@ -5820,8 +5820,8 @@
<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 = 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 57632d7

Please sign in to comment.