<description>The global position, as returned by the Global Positioning System (GPS). This is
<description>The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame).</description>
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame).</description>
<fieldtype="uint64_t"name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<fieldtype="uint64_t"name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<fieldtype="uint8_t"name="fix_type">0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field>
<fieldtype="uint8_t"name="fix_type">0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field>
<fieldtype="int32_t"name="lat">Latitude (WGS84), in degrees * 1E7</field>
<fieldtype="int32_t"name="lat">Latitude (WGS84), in degrees * 1E7</field>
<fieldtype="int32_t"name="lon">Longitude (WGS84), in degrees * 1E7</field>
<fieldtype="int32_t"name="lon">Longitude (WGS84), in degrees * 1E7</field>
<fieldtype="int32_t"name="alt">Altitude (WGS84), in meters * 1000 (positive for up)</field>
<fieldtype="int32_t"name="alt">Altitude (WGS84), in meters * 1000 (positive for up)</field>
@ -2087,7 +2087,7 @@
<messageid="124"name="GPS2_RAW">
<messageid="124"name="GPS2_RAW">
<description>Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS frame).</description>
<description>Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS frame).</description>
<fieldtype="uint64_t"name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<fieldtype="uint64_t"name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<fieldtype="uint8_t"name="fix_type">0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field>
<fieldtype="uint8_t"name="fix_type">0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field>
<fieldtype="int32_t"name="lat">Latitude (WGS84), in degrees * 1E7</field>
<fieldtype="int32_t"name="lat">Latitude (WGS84), in degrees * 1E7</field>
<fieldtype="int32_t"name="lon">Longitude (WGS84), in degrees * 1E7</field>
<fieldtype="int32_t"name="lon">Longitude (WGS84), in degrees * 1E7</field>
<fieldtype="int32_t"name="alt">Altitude (WGS84), in meters * 1000 (positive for up)</field>
<fieldtype="int32_t"name="alt">Altitude (WGS84), in meters * 1000 (positive for up)</field>
@ -2113,6 +2113,38 @@
<fieldtype="uint32_t"name="baudrate">Baudrate of transfer. Zero means no change.</field>
<fieldtype="uint32_t"name="baudrate">Baudrate of transfer. Zero means no change.</field>
<fieldtype="uint8_t"name="count">how many bytes in this transfer</field>
<fieldtype="uint8_t"name="count">how many bytes in this transfer</field>