Skip to content

Commit 9b4f3a6

Browse files
hamishwilleermackay9
authored andcommitted
development.xml - frame for setting the position in MAV_CMD_DO_SET_GLOBAL_ORIGIN (mavlink#2252)
* development.xml - frame for setting the position in global origin * Apply suggestions from code review
1 parent ca2d0d6 commit 9b4f3a6

File tree

1 file changed

+4
-3
lines changed

1 file changed

+4
-3
lines changed

message_definitions/v1.0/development.xml

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -144,14 +144,15 @@
144144
Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed.
145145
This enables transform between the local coordinate frame and the global (GNSS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor.
146146
This command supersedes SET_GPS_GLOBAL_ORIGIN.
147+
Should be sent in a COMMAND_INT (Expected frame is MAV_FRAME_GLOBAL, and this should be assumed when sent in COMMAND_LONG).
147148
</description>
148149
<param index="1">Empty</param>
149150
<param index="2">Empty</param>
150151
<param index="3">Empty</param>
151152
<param index="4">Empty</param>
152-
<param index="5" label="Latitude" units="degE7">Latitude (WGS84)</param>
153-
<param index="6" label="Longitude" units="degE7">Longitude (WGS84)</param>
154-
<param index="7" label="Altitude" units="m">Altitude (MSL)</param>
153+
<param index="5" label="Latitude">Latitude</param>
154+
<param index="6" label="Longitude">Longitude</param>
155+
<param index="7" label="Altitude" units="m">Altitude</param>
155156
</entry>
156157
<entry value="43004" name="MAV_CMD_EXTERNAL_WIND_ESTIMATE" hasLocation="false" isDestination="false">
157158
<description>Set an external estimate of wind direction and speed.

0 commit comments

Comments
 (0)