floathdg;///< Compass heading in degrees, 0..360 degrees
uint8_tfix_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.
uint8_tsatellites_visible;///< Number of satellites visible
uint64_tusec;///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
int32_tlat;///< Latitude in 1E7 degrees
int32_tlon;///< Longitude in 1E7 degrees
int32_talt;///< Altitude in 1E3 meters (millimeters)
floateph;///< GPS HDOP
floatepv;///< GPS VDOP
floatv;///< GPS ground speed (m/s)
floathdg;///< Compass heading in degrees, 0..360 degrees
int32_talt;///< Altitude in 1E3 meters (millimeters) above MSL
uint16_teph;///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
uint16_tepv;///< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
uint16_tvel;///< GPS ground speed (m/s * 100). If unknown, set to: 65535
uint16_thdg;///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
uint8_tfix_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.
uint8_tsatellites_visible;///< Number of satellites visible. If unknown, set to 255
* @param 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.
* @param lat Latitude in 1E7 degrees
* @param lon Longitude in 1E7 degrees
* @param alt Altitude in 1E3 meters (millimeters)
* @param eph GPS HDOP
* @param epv GPS VDOP
* @param v GPS ground speed (m/s)
* @param hdg Compass heading in degrees, 0..360 degrees
* @param alt Altitude in 1E3 meters (millimeters) above MSL
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
* @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @return length of the message in bytes (excluding serial stream start sign)
p->fix_type=fix_type;// uint8_t: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.
p->lat=lat;// int32_t:Latitude in 1E7 degrees
p->lon=lon;// int32_t:Longitude in 1E7 degrees
p->alt=alt;// int32_t:Altitude in 1E3 meters (millimeters)
p->eph=eph;// float:GPS HDOP
p->epv=epv;// float:GPS VDOP
p->v=v;// float:GPS ground speed (m/s)
p->hdg=hdg;// float:Compass heading in degrees, 0..360 degrees
p->alt=alt;// int32_t:Altitude in 1E3 meters (millimeters) above MSL
p->eph=eph;// uint16_t:GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
p->epv=epv;// uint16_t:GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
p->vel=vel;// uint16_t:GPS ground speed (m/s * 100). If unknown, set to: 65535
p->hdg=hdg;// uint16_t:Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
p->satellites_visible=satellites_visible;// uint8_t:Number of satellites visible. If unknown, set to 255
* @param 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.
* @param lat Latitude in 1E7 degrees
* @param lon Longitude in 1E7 degrees
* @param alt Altitude in 1E3 meters (millimeters)
* @param eph GPS HDOP
* @param epv GPS VDOP
* @param v GPS ground speed (m/s)
* @param hdg Compass heading in degrees, 0..360 degrees
* @param alt Altitude in 1E3 meters (millimeters) above MSL
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
* @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @return length of the message in bytes (excluding serial stream start sign)
p->fix_type=fix_type;// uint8_t: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.
p->lat=lat;// int32_t:Latitude in 1E7 degrees
p->lon=lon;// int32_t:Longitude in 1E7 degrees
p->alt=alt;// int32_t:Altitude in 1E3 meters (millimeters)
p->eph=eph;// float:GPS HDOP
p->epv=epv;// float:GPS VDOP
p->v=v;// float:GPS ground speed (m/s)
p->hdg=hdg;// float:Compass heading in degrees, 0..360 degrees
p->alt=alt;// int32_t:Altitude in 1E3 meters (millimeters) above MSL
p->eph=eph;// uint16_t:GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
p->epv=epv;// uint16_t:GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
p->vel=vel;// uint16_t:GPS ground speed (m/s * 100). If unknown, set to: 65535
p->hdg=hdg;// uint16_t:Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
p->satellites_visible=satellites_visible;// uint8_t:Number of satellites visible. If unknown, set to 255
* @param 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.
* @param lat Latitude in 1E7 degrees
* @param lon Longitude in 1E7 degrees
* @param alt Altitude in 1E3 meters (millimeters)
* @param eph GPS HDOP
* @param epv GPS VDOP
* @param v GPS ground speed (m/s)
* @param hdg Compass heading in degrees, 0..360 degrees
* @param alt Altitude in 1E3 meters (millimeters) above MSL
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
* @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
* @param satellites_visible Number of satellites visible. If unknown, set to 255
p->fix_type=fix_type;// uint8_t: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.
p->lat=lat;// int32_t:Latitude in 1E7 degrees
p->lon=lon;// int32_t:Longitude in 1E7 degrees
p->alt=alt;// int32_t:Altitude in 1E3 meters (millimeters)
p->eph=eph;// float:GPS HDOP
p->epv=epv;// float:GPS VDOP
p->v=v;// float:GPS ground speed (m/s)
p->hdg=hdg;// float:Compass heading in degrees, 0..360 degrees
p->alt=alt;// int32_t:Altitude in 1E3 meters (millimeters) above MSL
p->eph=eph;// uint16_t:GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
p->epv=epv;// uint16_t:GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
p->vel=vel;// uint16_t:GPS ground speed (m/s * 100). If unknown, set to: 65535
p->hdg=hdg;// uint16_t:Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
p->satellites_visible=satellites_visible;// uint8_t:Number of satellites visible. If unknown, set to 255
hdr.STX=MAVLINK_STX;
hdr.len=MAVLINK_MSG_ID_GPS_RAW_INT_LEN;
...
...
@@ -204,7 +211,7 @@ static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* m
/**
* @brief Get field alt from gps_raw_int message
*
* @return Altitude in 1E3 meters (millimeters)
* @return Altitude in 1E3 meters (millimeters) above MSL
<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="int32_t"name="lat">Latitude in 1E7 degrees</field>
<fieldtype="int32_t"name="lon">Longitude in 1E7 degrees</field>
<fieldtype="int32_t"name="alt">Altitude in 1E3 meters (millimeters)</field>
<fieldtype="float"name="hdg">Compass heading in degrees, 0..360 degrees</field>
<fieldtype="int32_t"name="alt">Altitude in 1E3 meters (millimeters) above MSL</field>
<fieldtype="uint16_t"name="eph">GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535</field>
<fieldtype="uint16_t"name="epv">GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535</field>
<fieldtype="uint16_t"name="vel">GPS ground speed (m/s * 100). If unknown, set to: 65535</field>
<fieldtype="uint16_t"name="hdg">Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535</field>
<fieldtype="uint8_t"name="satellites_visible">Number of satellites visible. If unknown, set to 255</field>
</message>
<messageid="26"name="SCALED_IMU">
<description>The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units</description>
...
...
@@ -812,7 +813,7 @@
<fieldtype="float"name="vz">Z Speed (in Altitude direction, positive: going up)</field>
</message>
<messageid="32"name="GPS_RAW">
<description>The global position, as returned by the Global Positioning System (GPS). This is
<description>IMPORTANT: Please use GPS_RAW_INT for maximum precision. The max FLOAT resolution limits the resolution to about 1.8 m on some places on the earth. 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>
<fieldtype="uint64_t"name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<fieldtype="float"name="hdg">Compass heading in degrees, 0..360 degrees</field>
<fieldtype="uint8_t"name="satellites_visible">Number of satellites visible</field>
</message>
<messageid="34"name="SYS_STATUS">
<description>The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.</description>
...
...
@@ -1117,10 +1119,11 @@
<description>The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up)</description>
<fieldtype="int32_t"name="lat">Latitude, expressed as * 1E7</field>
<fieldtype="int32_t"name="lon">Longitude, expressed as * 1E7</field>
<fieldtype="int32_t"name="alt">Altitude in meters, expressed as * 1000 (millimeters)</field>
<fieldtype="int32_t"name="alt">Altitude in meters, expressed as * 1000 (millimeters), above MSL</field>
<fieldtype="int16_t"name="vx">Ground X Speed (Latitude), expressed as m/s * 100</field>
<fieldtype="int16_t"name="vy">Ground Y Speed (Longitude), expressed as m/s * 100</field>
<fieldtype="int16_t"name="vz">Ground Z Speed (Altitude), expressed as m/s * 100</field>
<fieldtype="uint16_t"name="hdg">Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535</field>
</message>
<messageid="74"name="VFR_HUD">
<description>Metrics typically displayed on a HUD for fixed wing aircraft</description>
...
...
@@ -1147,7 +1150,14 @@
<fieldtype="float"name="command">Current airspeed in m/s</field>
<!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files -->
<!-- MESSAGE IDs 80 - 249: Space for custom messages in individual projectname_messages.xml files -->
<messageid="250"name="MEMORY_VECT">
<description>Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description>
<fieldtype="uint16_t"name="address">Starting address of the debug variables</field>
<fieldtype="uint8_t"name="ver">Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below</field>
<fieldtype="uint8_t"name="type">Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14</field>
<fieldtype="int8_t[32]"name="value">Memory contents at specified address</field>