Commit 738a310e authored by LM's avatar LM

Updated a few messages

parent 11b3e471
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Tuesday, August 9 2011, 16:49 UTC
* Generated on Wednesday, August 10 2011, 09:07 UTC
*/
#ifndef COMMON_H
#define COMMON_H
......@@ -289,6 +289,7 @@ enum MAV_CMD
#include "./mavlink_msg_vfr_hud.h"
#include "./mavlink_msg_command.h"
#include "./mavlink_msg_command_ack.h"
#include "./mavlink_msg_memory_vect.h"
#include "./mavlink_msg_debug_vect.h"
#include "./mavlink_msg_named_value_float.h"
#include "./mavlink_msg_named_value_int.h"
......@@ -299,7 +300,7 @@ enum MAV_CMD
// MESSAGE CRC KEYS
#undef MAVLINK_MESSAGE_KEYS
#define MAVLINK_MESSAGE_KEYS { 71, 249, 232, 226, 76, 126, 117, 186, 0, 144, 0, 249, 133, 0, 0, 0, 0, 0, 0, 0, 33, 34, 163, 45, 0, 223, 28, 99, 28, 21, 243, 240, 204, 21, 111, 43, 192, 234, 22, 197, 192, 192, 166, 34, 233, 34, 166, 158, 142, 60, 10, 75, 249, 247, 234, 157, 125, 0, 0, 0, 85, 211, 62, 75, 185, 18, 42, 38, 0, 127, 200, 0, 0, 53, 251, 20, 22, 0, 0, 0, 0, 0, 0, 0, 0, 127, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 8, 238, 165, 0, 0, 0, 0, 0, 0, 0, 218, 218, 235, 0, 0, 0, 0, 0, 0, 225, 114, 0, 0, 0, 0, 0, 0, 0, 0, 221, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 171, 122, 0, 0, 0, 0, 0, 0, 0, 92, 99, 4, 169, 10, 0, 0, 0, 0, 0, 52, 163, 16, 0, 0, 0, 0, 0, 0, 0, 200, 135, 217, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 43, 141, 211, 144 }
#define MAVLINK_MESSAGE_KEYS { 71, 249, 232, 226, 76, 126, 117, 186, 0, 144, 0, 249, 133, 0, 0, 0, 0, 0, 0, 0, 33, 34, 163, 45, 127, 166, 28, 99, 28, 21, 243, 240, 91, 21, 111, 43, 192, 234, 22, 197, 192, 192, 166, 34, 233, 34, 166, 158, 142, 60, 10, 75, 249, 247, 234, 157, 125, 0, 0, 0, 85, 211, 62, 75, 185, 18, 42, 38, 0, 127, 200, 0, 0, 212, 251, 20, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 138, 43, 141, 211, 144 }
#ifdef __cplusplus
}
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, August 9 2011, 16:49 UTC
* Generated on Wednesday, August 10 2011, 09:07 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
// MESSAGE GLOBAL_POSITION_INT PACKING
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 73
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 18
#define MAVLINK_MSG_73_LEN 18
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 20
#define MAVLINK_MSG_73_LEN 20
typedef struct __mavlink_global_position_int_t
{
int32_t lat; ///< Latitude, expressed as * 1E7
int32_t lon; ///< Longitude, expressed as * 1E7
int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters)
int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters), above MSL
int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
uint16_t hdg; ///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
} mavlink_global_position_int_t;
......@@ -23,23 +24,25 @@ typedef struct __mavlink_global_position_int_t
*
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
{
mavlink_global_position_int_t *p = (mavlink_global_position_int_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
p->lat = lat; // int32_t:Latitude, expressed as * 1E7
p->lon = lon; // int32_t:Longitude, expressed as * 1E7
p->alt = alt; // int32_t:Altitude in meters, expressed as * 1000 (millimeters)
p->alt = alt; // int32_t:Altitude in meters, expressed as * 1000 (millimeters), above MSL
p->vx = vx; // int16_t:Ground X Speed (Latitude), expressed as m/s * 100
p->vy = vy; // int16_t:Ground Y Speed (Longitude), expressed as m/s * 100
p->vz = vz; // int16_t:Ground Z Speed (Altitude), expressed as m/s * 100
p->hdg = hdg; // uint16_t:Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
}
......@@ -52,23 +55,25 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u
* @param msg The MAVLink message to compress the data into
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
{
mavlink_global_position_int_t *p = (mavlink_global_position_int_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
p->lat = lat; // int32_t:Latitude, expressed as * 1E7
p->lon = lon; // int32_t:Longitude, expressed as * 1E7
p->alt = alt; // int32_t:Altitude in meters, expressed as * 1000 (millimeters)
p->alt = alt; // int32_t:Altitude in meters, expressed as * 1000 (millimeters), above MSL
p->vx = vx; // int16_t:Ground X Speed (Latitude), expressed as m/s * 100
p->vy = vy; // int16_t:Ground Y Speed (Longitude), expressed as m/s * 100
p->vz = vz; // int16_t:Ground Z Speed (Altitude), expressed as m/s * 100
p->hdg = hdg; // uint16_t:Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
}
......@@ -83,7 +88,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_
*/
static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
{
return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->vx, global_position_int->vy, global_position_int->vz);
return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg);
}
/**
......@@ -92,15 +97,16 @@ static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id,
*
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
{
mavlink_header_t hdr;
mavlink_global_position_int_t payload;
......@@ -109,10 +115,11 @@ static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan,
p->lat = lat; // int32_t:Latitude, expressed as * 1E7
p->lon = lon; // int32_t:Longitude, expressed as * 1E7
p->alt = alt; // int32_t:Altitude in meters, expressed as * 1000 (millimeters)
p->alt = alt; // int32_t:Altitude in meters, expressed as * 1000 (millimeters), above MSL
p->vx = vx; // int16_t:Ground X Speed (Latitude), expressed as m/s * 100
p->vy = vy; // int16_t:Ground Y Speed (Longitude), expressed as m/s * 100
p->vz = vz; // int16_t:Ground Z Speed (Altitude), expressed as m/s * 100
p->hdg = hdg; // uint16_t:Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN;
......@@ -161,7 +168,7 @@ static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_mess
/**
* @brief Get field alt from global_position_int message
*
* @return Altitude in meters, expressed as * 1000 (millimeters)
* @return Altitude in meters, expressed as * 1000 (millimeters), above MSL
*/
static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
{
......@@ -202,6 +209,17 @@ static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_messa
return (int16_t)(p->vz);
}
/**
* @brief Get field hdg from global_position_int message
*
* @return Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
*/
static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg)
{
mavlink_global_position_int_t *p = (mavlink_global_position_int_t *)&msg->payload[0];
return (uint16_t)(p->hdg);
}
/**
* @brief Decode a global_position_int message into a struct
*
......
// MESSAGE GPS_RAW PACKING
#define MAVLINK_MSG_ID_GPS_RAW 32
#define MAVLINK_MSG_ID_GPS_RAW_LEN 37
#define MAVLINK_MSG_32_LEN 37
#define MAVLINK_MSG_ID_GPS_RAW_LEN 38
#define MAVLINK_MSG_32_LEN 38
typedef struct __mavlink_gps_raw_t
{
......@@ -15,6 +15,7 @@ typedef struct __mavlink_gps_raw_t
float v; ///< GPS ground speed
float hdg; ///< Compass heading in degrees, 0..360 degrees
uint8_t 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.
uint8_t satellites_visible; ///< Number of satellites visible
} mavlink_gps_raw_t;
......@@ -33,9 +34,10 @@ typedef struct __mavlink_gps_raw_t
* @param epv GPS VDOP
* @param v GPS ground speed
* @param hdg Compass heading in degrees, 0..360 degrees
* @param satellites_visible Number of satellites visible
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg, uint8_t satellites_visible)
{
mavlink_gps_raw_t *p = (mavlink_gps_raw_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
......@@ -49,6 +51,7 @@ static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t compo
p->epv = epv; // float:GPS VDOP
p->v = v; // float:GPS ground speed
p->hdg = hdg; // float:Compass heading in degrees, 0..360 degrees
p->satellites_visible = satellites_visible; // uint8_t:Number of satellites visible
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_LEN);
}
......@@ -68,9 +71,10 @@ static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t compo
* @param epv GPS VDOP
* @param v GPS ground speed
* @param hdg Compass heading in degrees, 0..360 degrees
* @param satellites_visible Number of satellites visible
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg, uint8_t satellites_visible)
{
mavlink_gps_raw_t *p = (mavlink_gps_raw_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
......@@ -84,6 +88,7 @@ static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t
p->epv = epv; // float:GPS VDOP
p->v = v; // float:GPS ground speed
p->hdg = hdg; // float:Compass heading in degrees, 0..360 degrees
p->satellites_visible = satellites_visible; // uint8_t:Number of satellites visible
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_LEN);
}
......@@ -98,7 +103,7 @@ static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t
*/
static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_t* gps_raw)
{
return mavlink_msg_gps_raw_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->alt, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg);
return mavlink_msg_gps_raw_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->alt, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg, gps_raw->satellites_visible);
}
/**
......@@ -114,11 +119,12 @@ static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t com
* @param epv GPS VDOP
* @param v GPS ground speed
* @param hdg Compass heading in degrees, 0..360 degrees
* @param satellites_visible Number of satellites visible
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_raw_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
static inline void mavlink_msg_gps_raw_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg, uint8_t satellites_visible)
{
mavlink_header_t hdr;
mavlink_gps_raw_t payload;
......@@ -134,6 +140,7 @@ static inline void mavlink_msg_gps_raw_send(mavlink_channel_t chan, uint64_t use
p->epv = epv; // float:GPS VDOP
p->v = v; // float:GPS ground speed
p->hdg = hdg; // float:Compass heading in degrees, 0..360 degrees
p->satellites_visible = satellites_visible; // uint8_t:Number of satellites visible
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_GPS_RAW_LEN;
......@@ -256,6 +263,17 @@ static inline float mavlink_msg_gps_raw_get_hdg(const mavlink_message_t* msg)
return (float)(p->hdg);
}
/**
* @brief Get field satellites_visible from gps_raw message
*
* @return Number of satellites visible
*/
static inline uint8_t mavlink_msg_gps_raw_get_satellites_visible(const mavlink_message_t* msg)
{
mavlink_gps_raw_t *p = (mavlink_gps_raw_t *)&msg->payload[0];
return (uint8_t)(p->satellites_visible);
}
/**
* @brief Decode a gps_raw message into a struct
*
......
// MESSAGE GPS_RAW_INT PACKING
#define MAVLINK_MSG_ID_GPS_RAW_INT 25
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 37
#define MAVLINK_MSG_25_LEN 37
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30
#define MAVLINK_MSG_25_LEN 30
typedef struct __mavlink_gps_raw_int_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
int32_t lat; ///< Latitude in 1E7 degrees
int32_t lon; ///< Longitude in 1E7 degrees
int32_t alt; ///< Altitude in 1E3 meters (millimeters)
float eph; ///< GPS HDOP
float epv; ///< GPS VDOP
float v; ///< GPS ground speed (m/s)
float hdg; ///< Compass heading in degrees, 0..360 degrees
int32_t alt; ///< Altitude in 1E3 meters (millimeters) above MSL
uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
uint16_t epv; ///< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: 65535
uint16_t hdg; ///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
uint8_t 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.
uint8_t satellites_visible; ///< Number of satellites visible. If unknown, set to 255
} mavlink_gps_raw_int_t;
......@@ -28,14 +29,15 @@ typedef struct __mavlink_gps_raw_int_t
* @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)
*/
static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, float eph, float epv, float v, float hdg)
static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t hdg, uint8_t satellites_visible)
{
mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
......@@ -44,11 +46,12 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c
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
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
}
......@@ -63,14 +66,15 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c
* @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)
*/
static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, float eph, float epv, float v, float hdg)
static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t hdg, uint8_t satellites_visible)
{
mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
......@@ -79,11 +83,12 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint
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
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
}
......@@ -98,7 +103,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint
*/
static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int)
{
return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->v, gps_raw_int->hdg);
return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->hdg, gps_raw_int->satellites_visible);
}
/**
......@@ -109,16 +114,17 @@ static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t
* @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
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, float eph, float epv, float v, float hdg)
static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t hdg, uint8_t satellites_visible)
{
mavlink_header_t hdr;
mavlink_gps_raw_int_t payload;
......@@ -129,11 +135,12 @@ static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t
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
*/
static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg)
{
......@@ -215,45 +222,56 @@ static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* m
/**
* @brief Get field eph from gps_raw_int message
*
* @return GPS HDOP
* @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
*/
static inline float mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg)
static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg)
{
mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
return (float)(p->eph);
return (uint16_t)(p->eph);
}
/**
* @brief Get field epv from gps_raw_int message
*
* @return GPS VDOP
* @return GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
*/
static inline float mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg)
static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg)
{
mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
return (float)(p->epv);
return (uint16_t)(p->epv);
}
/**
* @brief Get field v from gps_raw_int message
* @brief Get field vel from gps_raw_int message
*
* @return GPS ground speed (m/s)
* @return GPS ground speed (m/s * 100). If unknown, set to: 65535
*/
static inline float mavlink_msg_gps_raw_int_get_v(const mavlink_message_t* msg)
static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg)
{
mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
return (float)(p->v);
return (uint16_t)(p->vel);
}
/**
* @brief Get field hdg from gps_raw_int message
*
* @return Compass heading in degrees, 0..360 degrees
* @return Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
*/
static inline float mavlink_msg_gps_raw_int_get_hdg(const mavlink_message_t* msg)
static inline uint16_t mavlink_msg_gps_raw_int_get_hdg(const mavlink_message_t* msg)
{
mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
return (float)(p->hdg);
return (uint16_t)(p->hdg);
}
/**
* @brief Get field satellites_visible from gps_raw_int message
*
* @return Number of satellites visible. If unknown, set to 255
*/
static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg)
{
mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
return (uint8_t)(p->satellites_visible);
}
/**
......
// MESSAGE MEMORY_VECT PACKING
#define MAVLINK_MSG_ID_MEMORY_VECT 250
#define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36
#define MAVLINK_MSG_250_LEN 36
typedef struct __mavlink_memory_vect_t
{
uint16_t address; ///< Starting address of the debug variables
uint8_t ver; ///< Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
uint8_t 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
int8_t value[32]; ///< Memory contents at specified address
} mavlink_memory_vect_t;
#define MAVLINK_MSG_MEMORY_VECT_FIELD_VALUE_LEN 32
/**
* @brief Pack a memory_vect message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param address Starting address of the debug variables
* @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
* @param 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
* @param value Memory contents at specified address
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t address, uint8_t ver, uint8_t type, const int8_t* value)
{
mavlink_memory_vect_t *p = (mavlink_memory_vect_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT;
p->address = address; // uint16_t:Starting address of the debug variables
p->ver = ver; // uint8_t:Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
p->type = type; // uint8_t: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
memcpy(p->value, value, sizeof(p->value)); // int8_t[32]:Memory contents at specified address
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
}
/**
* @brief Pack a memory_vect message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param address Starting address of the debug variables
* @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
* @param 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
* @param value Memory contents at specified address
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t address, uint8_t ver, uint8_t type, const int8_t* value)
{
mavlink_memory_vect_t *p = (mavlink_memory_vect_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT;
p->address = address; // uint16_t:Starting address of the debug variables
p->ver = ver; // uint8_t:Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
p->type = type; // uint8_t: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
memcpy(p->value, value, sizeof(p->value)); // int8_t[32]:Memory contents at specified address
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
}
/**
* @brief Encode a memory_vect struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param memory_vect C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_memory_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect)
{
return mavlink_msg_memory_vect_pack(system_id, component_id, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value);
}
/**
* @brief Send a memory_vect message
* @param chan MAVLink channel to send the message
*
* @param address Starting address of the debug variables
* @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
* @param 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
* @param value Memory contents at specified address
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_memory_vect_send(mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t* value)
{
mavlink_header_t hdr;
mavlink_memory_vect_t payload;
uint16_t checksum;
mavlink_memory_vect_t *p = &payload;
p->address = address; // uint16_t:Starting address of the debug variables
p->ver = ver; // uint8_t:Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
p->type = type; // uint8_t: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
memcpy(p->value, value, sizeof(p->value)); // int8_t[32]:Memory contents at specified address
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_MEMORY_VECT_LEN;
hdr.msgid = MAVLINK_MSG_ID_MEMORY_VECT;
hdr.sysid = mavlink_system.sysid;
hdr.compid = mavlink_system.compid;
hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );
crc_init(&checksum);
checksum = crc_calculate_mem((uint8_t *)&hdr.len, &checksum, MAVLINK_CORE_HEADER_LEN);
checksum = crc_calculate_mem((uint8_t *)&payload, &checksum, hdr.len );
hdr.ck_a = (uint8_t)(checksum & 0xFF); ///< Low byte
hdr.ck_b = (uint8_t)(checksum >> 8); ///< High byte
mavlink_send_mem(chan, (uint8_t *)&payload, hdr.len);
mavlink_send_mem(chan, (uint8_t *)&hdr.ck_a, MAVLINK_NUM_CHECKSUM_BYTES);
}
#endif
// MESSAGE MEMORY_VECT UNPACKING
/**
* @brief Get field address from memory_vect message
*
* @return Starting address of the debug variables
*/
static inline uint16_t mavlink_msg_memory_vect_get_address(const mavlink_message_t* msg)
{
mavlink_memory_vect_t *p = (mavlink_memory_vect_t *)&msg->payload[0];
return (uint16_t)(p->address);
}
/**
* @brief Get field ver from memory_vect message
*
* @return Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
*/
static inline uint8_t mavlink_msg_memory_vect_get_ver(const mavlink_message_t* msg)
{
mavlink_memory_vect_t *p = (mavlink_memory_vect_t *)&msg->payload[0];
return (uint8_t)(p->ver);
}
/**
* @brief Get field type from memory_vect message
*
* @return 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
*/
static inline uint8_t mavlink_msg_memory_vect_get_type(const mavlink_message_t* msg)
{
mavlink_memory_vect_t *p = (mavlink_memory_vect_t *)&msg->payload[0];
return (uint8_t)(p->type);
}
/**
* @brief Get field value from memory_vect message
*
* @return Memory contents at specified address
*/
static inline uint16_t mavlink_msg_memory_vect_get_value(const mavlink_message_t* msg, int8_t* value)
{
mavlink_memory_vect_t *p = (mavlink_memory_vect_t *)&msg->payload[0];
memcpy(value, p->value, sizeof(p->value));
return sizeof(p->value);
}
/**
* @brief Decode a memory_vect message into a struct
*
* @param msg The message to decode
* @param memory_vect C-struct to decode the message contents into
*/
static inline void mavlink_msg_memory_vect_decode(const mavlink_message_t* msg, mavlink_memory_vect_t* memory_vect)
{
memcpy( memory_vect, msg->payload, sizeof(mavlink_memory_vect_t));
}
......@@ -725,11 +725,12 @@
<field type="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>
<field type="int32_t" name="lat">Latitude in 1E7 degrees</field>
<field type="int32_t" name="lon">Longitude in 1E7 degrees</field>
<field type="int32_t" name="alt">Altitude in 1E3 meters (millimeters)</field>
<field type="float" name="eph">GPS HDOP</field>
<field type="float" name="epv">GPS VDOP</field>
<field type="float" name="v">GPS ground speed (m/s)</field>
<field type="float" name="hdg">Compass heading in degrees, 0..360 degrees</field>
<field type="int32_t" name="alt">Altitude in 1E3 meters (millimeters) above MSL</field>
<field type="uint16_t" name="eph">GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535</field>
<field type="uint16_t" name="epv">GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535</field>
<field type="uint16_t" name="vel">GPS ground speed (m/s * 100). If unknown, set to: 65535</field>
<field type="uint16_t" name="hdg">Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535</field>
<field type="uint8_t" name="satellites_visible">Number of satellites visible. If unknown, set to 255</field>
</message>
<message id="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 @@
<field type="float" name="vz">Z Speed (in Altitude direction, positive: going up)</field>
</message>
<message id="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>
<field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
......@@ -824,6 +825,7 @@
<field type="float" name="epv">GPS VDOP</field>
<field type="float" name="v">GPS ground speed</field>
<field type="float" name="hdg">Compass heading in degrees, 0..360 degrees</field>
<field type="uint8_t" name="satellites_visible">Number of satellites visible</field>
</message>
<message id="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>
<field type="int32_t" name="lat">Latitude, expressed as * 1E7</field>
<field type="int32_t" name="lon">Longitude, expressed as * 1E7</field>
<field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters)</field>
<field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters), above MSL</field>
<field type="int16_t" name="vx">Ground X Speed (Latitude), expressed as m/s * 100</field>
<field type="int16_t" name="vy">Ground Y Speed (Longitude), expressed as m/s * 100</field>
<field type="int16_t" name="vz">Ground Z Speed (Altitude), expressed as m/s * 100</field>
<field type="uint16_t" name="hdg">Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535</field>
</message>
<message id="74" name="VFR_HUD">
<description>Metrics typically displayed on a HUD for fixed wing aircraft</description>
......@@ -1147,7 +1150,14 @@
<field type="float" name="command">Current airspeed in m/s</field>
<field type="float" name="result">1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION</field>
</message>
<!-- 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 -->
<message id="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>
<field type="uint16_t" name="address">Starting address of the debug variables</field>
<field type="uint8_t" name="ver">Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below</field>
<field type="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>
<field type="int8_t[32]" name="value">Memory contents at specified address</field>
</message>
<message id="251" name="DEBUG_VECT">
<field type="char[10]" name="name">Name</field>
<field type="uint64_t" name="usec">Timestamp</field>
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment