Commit ca5da2a6 authored by PX4BuildBot's avatar PX4BuildBot

autogenerated headers for rev...

autogenerated headers for rev https://github.com/mavlink/mavlink/tree/c72087cef9193535c19de959c33b128ec067524d
parent 47d2375d
......@@ -6,8 +6,8 @@
MAVPACKED(
typedef struct __mavlink_gps_raw_int_t {
uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/
int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/
int32_t lat; /*< Latitude (WGS84, EGM96 ellipsoid), in degrees * 1E7*/
int32_t lon; /*< Longitude (WGS84, EGM96 ellipsoid), in degrees * 1E7*/
int32_t alt; /*< Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.*/
uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/
uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/
......@@ -15,11 +15,16 @@ typedef struct __mavlink_gps_raw_int_t {
uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
uint8_t fix_type; /*< See the GPS_FIX_TYPE enum.*/
uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/
int32_t alt_ellipsoid; /*< Altitude (above WGS84, EGM96 ellipsoid), in meters * 1000 (positive for up).*/
uint32_t h_acc; /*< Position uncertainty in meters * 1000 (positive for up).*/
uint32_t v_acc; /*< Altitude uncertainty in meters * 1000 (positive for up).*/
uint32_t vel_acc; /*< Speed uncertainty in meters * 1000 (positive for up).*/
uint32_t hdg_acc; /*< Heading / track uncertainty in degrees * 1e5.*/
}) mavlink_gps_raw_int_t;
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 50
#define MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN 30
#define MAVLINK_MSG_ID_24_LEN 30
#define MAVLINK_MSG_ID_24_LEN 50
#define MAVLINK_MSG_ID_24_MIN_LEN 30
#define MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24
......@@ -31,7 +36,7 @@ typedef struct __mavlink_gps_raw_int_t {
#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
24, \
"GPS_RAW_INT", \
10, \
15, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
......@@ -42,12 +47,17 @@ typedef struct __mavlink_gps_raw_int_t {
{ "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
{ "alt_ellipsoid", NULL, MAVLINK_TYPE_INT32_T, 0, 30, offsetof(mavlink_gps_raw_int_t, alt_ellipsoid) }, \
{ "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 34, offsetof(mavlink_gps_raw_int_t, h_acc) }, \
{ "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 38, offsetof(mavlink_gps_raw_int_t, v_acc) }, \
{ "vel_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 42, offsetof(mavlink_gps_raw_int_t, vel_acc) }, \
{ "hdg_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 46, offsetof(mavlink_gps_raw_int_t, hdg_acc) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
"GPS_RAW_INT", \
10, \
15, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
......@@ -58,6 +68,11 @@ typedef struct __mavlink_gps_raw_int_t {
{ "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
{ "alt_ellipsoid", NULL, MAVLINK_TYPE_INT32_T, 0, 30, offsetof(mavlink_gps_raw_int_t, alt_ellipsoid) }, \
{ "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 34, offsetof(mavlink_gps_raw_int_t, h_acc) }, \
{ "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 38, offsetof(mavlink_gps_raw_int_t, v_acc) }, \
{ "vel_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 42, offsetof(mavlink_gps_raw_int_t, vel_acc) }, \
{ "hdg_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 46, offsetof(mavlink_gps_raw_int_t, hdg_acc) }, \
} \
}
#endif
......@@ -70,18 +85,23 @@ typedef struct __mavlink_gps_raw_int_t {
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type See the GPS_FIX_TYPE enum.
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param lat Latitude (WGS84, EGM96 ellipsoid), in degrees * 1E7
* @param lon Longitude (WGS84, EGM96 ellipsoid), in degrees * 1E7
* @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
* @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @param alt_ellipsoid Altitude (above WGS84, EGM96 ellipsoid), in meters * 1000 (positive for up).
* @param h_acc Position uncertainty in meters * 1000 (positive for up).
* @param v_acc Altitude uncertainty in meters * 1000 (positive for up).
* @param vel_acc Speed uncertainty in meters * 1000 (positive for up).
* @param hdg_acc Heading / track uncertainty in degrees * 1e5.
* @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 time_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 cog, uint8_t satellites_visible)
uint64_t time_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 cog, uint8_t satellites_visible, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
......@@ -95,6 +115,11 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c
_mav_put_uint16_t(buf, 26, cog);
_mav_put_uint8_t(buf, 28, fix_type);
_mav_put_uint8_t(buf, 29, satellites_visible);
_mav_put_int32_t(buf, 30, alt_ellipsoid);
_mav_put_uint32_t(buf, 34, h_acc);
_mav_put_uint32_t(buf, 38, v_acc);
_mav_put_uint32_t(buf, 42, vel_acc);
_mav_put_uint32_t(buf, 46, hdg_acc);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#else
......@@ -109,6 +134,11 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.alt_ellipsoid = alt_ellipsoid;
packet.h_acc = h_acc;
packet.v_acc = v_acc;
packet.vel_acc = vel_acc;
packet.hdg_acc = hdg_acc;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#endif
......@@ -125,19 +155,24 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type See the GPS_FIX_TYPE enum.
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param lat Latitude (WGS84, EGM96 ellipsoid), in degrees * 1E7
* @param lon Longitude (WGS84, EGM96 ellipsoid), in degrees * 1E7
* @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
* @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @param alt_ellipsoid Altitude (above WGS84, EGM96 ellipsoid), in meters * 1000 (positive for up).
* @param h_acc Position uncertainty in meters * 1000 (positive for up).
* @param v_acc Altitude uncertainty in meters * 1000 (positive for up).
* @param vel_acc Speed uncertainty in meters * 1000 (positive for up).
* @param hdg_acc Heading / track uncertainty in degrees * 1e5.
* @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 time_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 cog,uint8_t satellites_visible)
uint64_t time_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 cog,uint8_t satellites_visible,int32_t alt_ellipsoid,uint32_t h_acc,uint32_t v_acc,uint32_t vel_acc,uint32_t hdg_acc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
......@@ -151,6 +186,11 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint
_mav_put_uint16_t(buf, 26, cog);
_mav_put_uint8_t(buf, 28, fix_type);
_mav_put_uint8_t(buf, 29, satellites_visible);
_mav_put_int32_t(buf, 30, alt_ellipsoid);
_mav_put_uint32_t(buf, 34, h_acc);
_mav_put_uint32_t(buf, 38, v_acc);
_mav_put_uint32_t(buf, 42, vel_acc);
_mav_put_uint32_t(buf, 46, hdg_acc);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#else
......@@ -165,6 +205,11 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.alt_ellipsoid = alt_ellipsoid;
packet.h_acc = h_acc;
packet.v_acc = v_acc;
packet.vel_acc = vel_acc;
packet.hdg_acc = hdg_acc;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#endif
......@@ -183,7 +228,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->time_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->cog, gps_raw_int->satellites_visible);
return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->time_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->cog, gps_raw_int->satellites_visible, gps_raw_int->alt_ellipsoid, gps_raw_int->h_acc, gps_raw_int->v_acc, gps_raw_int->vel_acc, gps_raw_int->hdg_acc);
}
/**
......@@ -197,7 +242,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t
*/
static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int)
{
return mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, chan, msg, gps_raw_int->time_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->cog, gps_raw_int->satellites_visible);
return mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, chan, msg, gps_raw_int->time_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->cog, gps_raw_int->satellites_visible, gps_raw_int->alt_ellipsoid, gps_raw_int->h_acc, gps_raw_int->v_acc, gps_raw_int->vel_acc, gps_raw_int->hdg_acc);
}
/**
......@@ -206,18 +251,23 @@ static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, ui
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type See the GPS_FIX_TYPE enum.
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param lat Latitude (WGS84, EGM96 ellipsoid), in degrees * 1E7
* @param lon Longitude (WGS84, EGM96 ellipsoid), in degrees * 1E7
* @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
* @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @param alt_ellipsoid Altitude (above WGS84, EGM96 ellipsoid), in meters * 1000 (positive for up).
* @param h_acc Position uncertainty in meters * 1000 (positive for up).
* @param v_acc Altitude uncertainty in meters * 1000 (positive for up).
* @param vel_acc Speed uncertainty in meters * 1000 (positive for up).
* @param hdg_acc Heading / track uncertainty in degrees * 1e5.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t time_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 cog, uint8_t satellites_visible)
static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t time_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 cog, uint8_t satellites_visible, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
......@@ -231,6 +281,11 @@ static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t
_mav_put_uint16_t(buf, 26, cog);
_mav_put_uint8_t(buf, 28, fix_type);
_mav_put_uint8_t(buf, 29, satellites_visible);
_mav_put_int32_t(buf, 30, alt_ellipsoid);
_mav_put_uint32_t(buf, 34, h_acc);
_mav_put_uint32_t(buf, 38, v_acc);
_mav_put_uint32_t(buf, 42, vel_acc);
_mav_put_uint32_t(buf, 46, hdg_acc);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#else
......@@ -245,6 +300,11 @@ static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.alt_ellipsoid = alt_ellipsoid;
packet.h_acc = h_acc;
packet.v_acc = v_acc;
packet.vel_acc = vel_acc;
packet.hdg_acc = hdg_acc;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#endif
......@@ -258,7 +318,7 @@ static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t
static inline void mavlink_msg_gps_raw_int_send_struct(mavlink_channel_t chan, const mavlink_gps_raw_int_t* gps_raw_int)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gps_raw_int_send(chan, gps_raw_int->time_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->cog, gps_raw_int->satellites_visible);
mavlink_msg_gps_raw_int_send(chan, gps_raw_int->time_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->cog, gps_raw_int->satellites_visible, gps_raw_int->alt_ellipsoid, gps_raw_int->h_acc, gps_raw_int->v_acc, gps_raw_int->vel_acc, gps_raw_int->hdg_acc);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)gps_raw_int, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#endif
......@@ -272,7 +332,7 @@ static inline void mavlink_msg_gps_raw_int_send_struct(mavlink_channel_t chan, c
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_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 cog, uint8_t satellites_visible)
static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_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 cog, uint8_t satellites_visible, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
......@@ -286,6 +346,11 @@ static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, m
_mav_put_uint16_t(buf, 26, cog);
_mav_put_uint8_t(buf, 28, fix_type);
_mav_put_uint8_t(buf, 29, satellites_visible);
_mav_put_int32_t(buf, 30, alt_ellipsoid);
_mav_put_uint32_t(buf, 34, h_acc);
_mav_put_uint32_t(buf, 38, v_acc);
_mav_put_uint32_t(buf, 42, vel_acc);
_mav_put_uint32_t(buf, 46, hdg_acc);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#else
......@@ -300,6 +365,11 @@ static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, m
packet->cog = cog;
packet->fix_type = fix_type;
packet->satellites_visible = satellites_visible;
packet->alt_ellipsoid = alt_ellipsoid;
packet->h_acc = h_acc;
packet->v_acc = v_acc;
packet->vel_acc = vel_acc;
packet->hdg_acc = hdg_acc;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#endif
......@@ -334,7 +404,7 @@ static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message
/**
* @brief Get field lat from gps_raw_int message
*
* @return Latitude (WGS84), in degrees * 1E7
* @return Latitude (WGS84, EGM96 ellipsoid), in degrees * 1E7
*/
static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg)
{
......@@ -344,7 +414,7 @@ static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* m
/**
* @brief Get field lon from gps_raw_int message
*
* @return Longitude (WGS84), in degrees * 1E7
* @return Longitude (WGS84, EGM96 ellipsoid), in degrees * 1E7
*/
static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg)
{
......@@ -411,6 +481,56 @@ static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavli
return _MAV_RETURN_uint8_t(msg, 29);
}
/**
* @brief Get field alt_ellipsoid from gps_raw_int message
*
* @return Altitude (above WGS84, EGM96 ellipsoid), in meters * 1000 (positive for up).
*/
static inline int32_t mavlink_msg_gps_raw_int_get_alt_ellipsoid(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 30);
}
/**
* @brief Get field h_acc from gps_raw_int message
*
* @return Position uncertainty in meters * 1000 (positive for up).
*/
static inline uint32_t mavlink_msg_gps_raw_int_get_h_acc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 34);
}
/**
* @brief Get field v_acc from gps_raw_int message
*
* @return Altitude uncertainty in meters * 1000 (positive for up).
*/
static inline uint32_t mavlink_msg_gps_raw_int_get_v_acc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 38);
}
/**
* @brief Get field vel_acc from gps_raw_int message
*
* @return Speed uncertainty in meters * 1000 (positive for up).
*/
static inline uint32_t mavlink_msg_gps_raw_int_get_vel_acc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 42);
}
/**
* @brief Get field hdg_acc from gps_raw_int message
*
* @return Heading / track uncertainty in degrees * 1e5.
*/
static inline uint32_t mavlink_msg_gps_raw_int_get_hdg_acc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 46);
}
/**
* @brief Decode a gps_raw_int message into a struct
*
......@@ -430,6 +550,11 @@ static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg,
gps_raw_int->cog = mavlink_msg_gps_raw_int_get_cog(msg);
gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg);
gps_raw_int->satellites_visible = mavlink_msg_gps_raw_int_get_satellites_visible(msg);
gps_raw_int->alt_ellipsoid = mavlink_msg_gps_raw_int_get_alt_ellipsoid(msg);
gps_raw_int->h_acc = mavlink_msg_gps_raw_int_get_h_acc(msg);
gps_raw_int->v_acc = mavlink_msg_gps_raw_int_get_v_acc(msg);
gps_raw_int->vel_acc = mavlink_msg_gps_raw_int_get_vel_acc(msg);
gps_raw_int->hdg_acc = mavlink_msg_gps_raw_int_get_hdg_acc(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_RAW_INT_LEN? msg->len : MAVLINK_MSG_ID_GPS_RAW_INT_LEN;
memset(gps_raw_int, 0, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
......
......@@ -725,7 +725,7 @@ static void mavlink_test_gps_raw_int(uint8_t system_id, uint8_t component_id, ma
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps_raw_int_t packet_in = {
93372036854775807ULL,963497880,963498088,963498296,18275,18379,18483,18587,89,156
93372036854775807ULL,963497880,963498088,963498296,18275,18379,18483,18587,89,156,963499024,963499232,963499440,963499648,963499856
};
mavlink_gps_raw_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
......@@ -739,6 +739,11 @@ static void mavlink_test_gps_raw_int(uint8_t system_id, uint8_t component_id, ma
packet1.cog = packet_in.cog;
packet1.fix_type = packet_in.fix_type;
packet1.satellites_visible = packet_in.satellites_visible;
packet1.alt_ellipsoid = packet_in.alt_ellipsoid;
packet1.h_acc = packet_in.h_acc;
packet1.v_acc = packet_in.v_acc;
packet1.vel_acc = packet_in.vel_acc;
packet1.hdg_acc = packet_in.hdg_acc;
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
......@@ -753,12 +758,12 @@ static void mavlink_test_gps_raw_int(uint8_t system_id, uint8_t component_id, ma
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_raw_int_pack(system_id, component_id, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible );
mavlink_msg_gps_raw_int_pack(system_id, component_id, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible , packet1.alt_ellipsoid , packet1.h_acc , packet1.v_acc , packet1.vel_acc , packet1.hdg_acc );
mavlink_msg_gps_raw_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible );
mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible , packet1.alt_ellipsoid , packet1.h_acc , packet1.v_acc , packet1.vel_acc , packet1.hdg_acc );
mavlink_msg_gps_raw_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
......@@ -771,7 +776,7 @@ static void mavlink_test_gps_raw_int(uint8_t system_id, uint8_t component_id, ma
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_raw_int_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible );
mavlink_msg_gps_raw_int_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible , packet1.alt_ellipsoid , packet1.h_acc , packet1.v_acc , packet1.vel_acc , packet1.hdg_acc );
mavlink_msg_gps_raw_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
......
......@@ -2710,14 +2710,20 @@
NOT the global position estimate of the system, 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="time_usec" units="us">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="uint8_t" name="fix_type" enum="GPS_FIX_TYPE">See the GPS_FIX_TYPE enum.</field>
<field type="int32_t" name="lat" units="degE7">Latitude (WGS84), in degrees * 1E7</field>
<field type="int32_t" name="lon" units="degE7">Longitude (WGS84), in degrees * 1E7</field>
<field type="int32_t" name="lat" units="degE7">Latitude (WGS84, EGM96 ellipsoid), in degrees * 1E7</field>
<field type="int32_t" name="lon" units="degE7">Longitude (WGS84, EGM96 ellipsoid), in degrees * 1E7</field>
<field type="int32_t" name="alt" units="mm">Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.</field>
<field type="uint16_t" name="eph">GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX</field>
<field type="uint16_t" name="epv">GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX</field>
<field type="uint16_t" name="vel" units="cm/s">GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX</field>
<field type="uint16_t" name="cog" units="cdeg">Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX</field>
<field type="uint8_t" name="satellites_visible">Number of satellites visible. If unknown, set to 255</field>
<extensions/>
<field type="int32_t" name="alt_ellipsoid" units="mm">Altitude (above WGS84, EGM96 ellipsoid), in meters * 1000 (positive for up).</field>
<field type="uint32_t" name="h_acc" units="mm">Position uncertainty in meters * 1000 (positive for up).</field>
<field type="uint32_t" name="v_acc" units="mm">Altitude uncertainty in meters * 1000 (positive for up).</field>
<field type="uint32_t" name="vel_acc" units="mm">Speed uncertainty in meters * 1000 (positive for up).</field>
<field type="uint32_t" name="hdg_acc" units="mm">Heading / track uncertainty in degrees * 1e5.</field>
</message>
<message id="25" name="GPS_STATUS">
<description>The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites.</description>
......
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