123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960 |
- #pragma once
- // MESSAGE VK_EXTERNAL_INS_NAV PACKING
- #define MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV 53023
- typedef struct __mavlink_vk_external_ins_nav_t {
- uint32_t timestamp; /*< [ms] timestamp from system boot*/
- int32_t lon; /*< [degE7] solved longitude*/
- int32_t lat; /*< [degE7] solved latitude*/
- float msl; /*< [m] solved latitude*/
- float ve; /*< [m/s] solved east speed*/
- float vn; /*< [m/s] solved north speed*/
- float vu; /*< [m/s] solved up speed*/
- float yaw; /*< [deg] yaw angle*/
- float pitch; /*< [deg] pitch angle*/
- float roll; /*< [deg] roll angle*/
- float gx; /*< [deg/s] roll angle*/
- float gy; /*< [deg/s] roll angle*/
- float gz; /*< [deg/s] roll angle*/
- float ax; /*< [m/s/s] roll angle*/
- float ay; /*< [m/s/s] roll angle*/
- float az; /*< [m/s/s] roll angle*/
- int32_t sat_lon; /*< [degE7] gps longitude*/
- int32_t sat_lat; /*< [degE7] gps latitude*/
- float sat_msl; /*< [m] gps altitude*/
- float sat_ve; /*< [m/s] gps east speed*/
- float sat_vn; /*< [m/s] gps north speed*/
- float sat_vu; /*< [m/s] gps up speed*/
- uint8_t sat_pfix; /*< gps position fix*/
- uint8_t sat_hfix; /*< gps heading fix*/
- uint8_t wk_state; /*< work state*/
- uint8_t err_code; /*< error code*/
- } mavlink_vk_external_ins_nav_t;
- #define MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN 92
- #define MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN 92
- #define MAVLINK_MSG_ID_53023_LEN 92
- #define MAVLINK_MSG_ID_53023_MIN_LEN 92
- #define MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC 115
- #define MAVLINK_MSG_ID_53023_CRC 115
- #if MAVLINK_COMMAND_24BIT
- #define MAVLINK_MESSAGE_INFO_VK_EXTERNAL_INS_NAV { \
- 53023, \
- "VK_EXTERNAL_INS_NAV", \
- 26, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_external_ins_nav_t, timestamp) }, \
- { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_vk_external_ins_nav_t, lon) }, \
- { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_vk_external_ins_nav_t, lat) }, \
- { "msl", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vk_external_ins_nav_t, msl) }, \
- { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vk_external_ins_nav_t, ve) }, \
- { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vk_external_ins_nav_t, vn) }, \
- { "vu", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vk_external_ins_nav_t, vu) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vk_external_ins_nav_t, yaw) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_vk_external_ins_nav_t, pitch) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_vk_external_ins_nav_t, roll) }, \
- { "gx", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_vk_external_ins_nav_t, gx) }, \
- { "gy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_vk_external_ins_nav_t, gy) }, \
- { "gz", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_vk_external_ins_nav_t, gz) }, \
- { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_vk_external_ins_nav_t, ax) }, \
- { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_vk_external_ins_nav_t, ay) }, \
- { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_vk_external_ins_nav_t, az) }, \
- { "sat_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 64, offsetof(mavlink_vk_external_ins_nav_t, sat_lon) }, \
- { "sat_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 68, offsetof(mavlink_vk_external_ins_nav_t, sat_lat) }, \
- { "sat_msl", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_vk_external_ins_nav_t, sat_msl) }, \
- { "sat_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_vk_external_ins_nav_t, sat_ve) }, \
- { "sat_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_vk_external_ins_nav_t, sat_vn) }, \
- { "sat_vu", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_vk_external_ins_nav_t, sat_vu) }, \
- { "sat_pfix", NULL, MAVLINK_TYPE_UINT8_T, 0, 88, offsetof(mavlink_vk_external_ins_nav_t, sat_pfix) }, \
- { "sat_hfix", NULL, MAVLINK_TYPE_UINT8_T, 0, 89, offsetof(mavlink_vk_external_ins_nav_t, sat_hfix) }, \
- { "wk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 90, offsetof(mavlink_vk_external_ins_nav_t, wk_state) }, \
- { "err_code", NULL, MAVLINK_TYPE_UINT8_T, 0, 91, offsetof(mavlink_vk_external_ins_nav_t, err_code) }, \
- } \
- }
- #else
- #define MAVLINK_MESSAGE_INFO_VK_EXTERNAL_INS_NAV { \
- "VK_EXTERNAL_INS_NAV", \
- 26, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_external_ins_nav_t, timestamp) }, \
- { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_vk_external_ins_nav_t, lon) }, \
- { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_vk_external_ins_nav_t, lat) }, \
- { "msl", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vk_external_ins_nav_t, msl) }, \
- { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vk_external_ins_nav_t, ve) }, \
- { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vk_external_ins_nav_t, vn) }, \
- { "vu", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vk_external_ins_nav_t, vu) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vk_external_ins_nav_t, yaw) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_vk_external_ins_nav_t, pitch) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_vk_external_ins_nav_t, roll) }, \
- { "gx", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_vk_external_ins_nav_t, gx) }, \
- { "gy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_vk_external_ins_nav_t, gy) }, \
- { "gz", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_vk_external_ins_nav_t, gz) }, \
- { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_vk_external_ins_nav_t, ax) }, \
- { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_vk_external_ins_nav_t, ay) }, \
- { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_vk_external_ins_nav_t, az) }, \
- { "sat_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 64, offsetof(mavlink_vk_external_ins_nav_t, sat_lon) }, \
- { "sat_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 68, offsetof(mavlink_vk_external_ins_nav_t, sat_lat) }, \
- { "sat_msl", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_vk_external_ins_nav_t, sat_msl) }, \
- { "sat_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_vk_external_ins_nav_t, sat_ve) }, \
- { "sat_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_vk_external_ins_nav_t, sat_vn) }, \
- { "sat_vu", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_vk_external_ins_nav_t, sat_vu) }, \
- { "sat_pfix", NULL, MAVLINK_TYPE_UINT8_T, 0, 88, offsetof(mavlink_vk_external_ins_nav_t, sat_pfix) }, \
- { "sat_hfix", NULL, MAVLINK_TYPE_UINT8_T, 0, 89, offsetof(mavlink_vk_external_ins_nav_t, sat_hfix) }, \
- { "wk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 90, offsetof(mavlink_vk_external_ins_nav_t, wk_state) }, \
- { "err_code", NULL, MAVLINK_TYPE_UINT8_T, 0, 91, offsetof(mavlink_vk_external_ins_nav_t, err_code) }, \
- } \
- }
- #endif
- /**
- * @brief Pack a vk_external_ins_nav 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 timestamp [ms] timestamp from system boot
- * @param lon [degE7] solved longitude
- * @param lat [degE7] solved latitude
- * @param msl [m] solved latitude
- * @param ve [m/s] solved east speed
- * @param vn [m/s] solved north speed
- * @param vu [m/s] solved up speed
- * @param yaw [deg] yaw angle
- * @param pitch [deg] pitch angle
- * @param roll [deg] roll angle
- * @param gx [deg/s] roll angle
- * @param gy [deg/s] roll angle
- * @param gz [deg/s] roll angle
- * @param ax [m/s/s] roll angle
- * @param ay [m/s/s] roll angle
- * @param az [m/s/s] roll angle
- * @param sat_lon [degE7] gps longitude
- * @param sat_lat [degE7] gps latitude
- * @param sat_msl [m] gps altitude
- * @param sat_ve [m/s] gps east speed
- * @param sat_vn [m/s] gps north speed
- * @param sat_vu [m/s] gps up speed
- * @param sat_pfix gps position fix
- * @param sat_hfix gps heading fix
- * @param wk_state work state
- * @param err_code error code
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_vk_external_ins_nav_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint32_t timestamp, int32_t lon, int32_t lat, float msl, float ve, float vn, float vu, float yaw, float pitch, float roll, float gx, float gy, float gz, float ax, float ay, float az, int32_t sat_lon, int32_t sat_lat, float sat_msl, float sat_ve, float sat_vn, float sat_vu, uint8_t sat_pfix, uint8_t sat_hfix, uint8_t wk_state, uint8_t err_code)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN];
- _mav_put_uint32_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 4, lon);
- _mav_put_int32_t(buf, 8, lat);
- _mav_put_float(buf, 12, msl);
- _mav_put_float(buf, 16, ve);
- _mav_put_float(buf, 20, vn);
- _mav_put_float(buf, 24, vu);
- _mav_put_float(buf, 28, yaw);
- _mav_put_float(buf, 32, pitch);
- _mav_put_float(buf, 36, roll);
- _mav_put_float(buf, 40, gx);
- _mav_put_float(buf, 44, gy);
- _mav_put_float(buf, 48, gz);
- _mav_put_float(buf, 52, ax);
- _mav_put_float(buf, 56, ay);
- _mav_put_float(buf, 60, az);
- _mav_put_int32_t(buf, 64, sat_lon);
- _mav_put_int32_t(buf, 68, sat_lat);
- _mav_put_float(buf, 72, sat_msl);
- _mav_put_float(buf, 76, sat_ve);
- _mav_put_float(buf, 80, sat_vn);
- _mav_put_float(buf, 84, sat_vu);
- _mav_put_uint8_t(buf, 88, sat_pfix);
- _mav_put_uint8_t(buf, 89, sat_hfix);
- _mav_put_uint8_t(buf, 90, wk_state);
- _mav_put_uint8_t(buf, 91, err_code);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
- #else
- mavlink_vk_external_ins_nav_t packet;
- packet.timestamp = timestamp;
- packet.lon = lon;
- packet.lat = lat;
- packet.msl = msl;
- packet.ve = ve;
- packet.vn = vn;
- packet.vu = vu;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
- packet.gx = gx;
- packet.gy = gy;
- packet.gz = gz;
- packet.ax = ax;
- packet.ay = ay;
- packet.az = az;
- packet.sat_lon = sat_lon;
- packet.sat_lat = sat_lat;
- packet.sat_msl = sat_msl;
- packet.sat_ve = sat_ve;
- packet.sat_vn = sat_vn;
- packet.sat_vu = sat_vu;
- packet.sat_pfix = sat_pfix;
- packet.sat_hfix = sat_hfix;
- packet.wk_state = wk_state;
- packet.err_code = err_code;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
- }
- /**
- * @brief Pack a vk_external_ins_nav message
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param status MAVLink status structure
- * @param msg The MAVLink message to compress the data into
- *
- * @param timestamp [ms] timestamp from system boot
- * @param lon [degE7] solved longitude
- * @param lat [degE7] solved latitude
- * @param msl [m] solved latitude
- * @param ve [m/s] solved east speed
- * @param vn [m/s] solved north speed
- * @param vu [m/s] solved up speed
- * @param yaw [deg] yaw angle
- * @param pitch [deg] pitch angle
- * @param roll [deg] roll angle
- * @param gx [deg/s] roll angle
- * @param gy [deg/s] roll angle
- * @param gz [deg/s] roll angle
- * @param ax [m/s/s] roll angle
- * @param ay [m/s/s] roll angle
- * @param az [m/s/s] roll angle
- * @param sat_lon [degE7] gps longitude
- * @param sat_lat [degE7] gps latitude
- * @param sat_msl [m] gps altitude
- * @param sat_ve [m/s] gps east speed
- * @param sat_vn [m/s] gps north speed
- * @param sat_vu [m/s] gps up speed
- * @param sat_pfix gps position fix
- * @param sat_hfix gps heading fix
- * @param wk_state work state
- * @param err_code error code
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_vk_external_ins_nav_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
- uint32_t timestamp, int32_t lon, int32_t lat, float msl, float ve, float vn, float vu, float yaw, float pitch, float roll, float gx, float gy, float gz, float ax, float ay, float az, int32_t sat_lon, int32_t sat_lat, float sat_msl, float sat_ve, float sat_vn, float sat_vu, uint8_t sat_pfix, uint8_t sat_hfix, uint8_t wk_state, uint8_t err_code)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN];
- _mav_put_uint32_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 4, lon);
- _mav_put_int32_t(buf, 8, lat);
- _mav_put_float(buf, 12, msl);
- _mav_put_float(buf, 16, ve);
- _mav_put_float(buf, 20, vn);
- _mav_put_float(buf, 24, vu);
- _mav_put_float(buf, 28, yaw);
- _mav_put_float(buf, 32, pitch);
- _mav_put_float(buf, 36, roll);
- _mav_put_float(buf, 40, gx);
- _mav_put_float(buf, 44, gy);
- _mav_put_float(buf, 48, gz);
- _mav_put_float(buf, 52, ax);
- _mav_put_float(buf, 56, ay);
- _mav_put_float(buf, 60, az);
- _mav_put_int32_t(buf, 64, sat_lon);
- _mav_put_int32_t(buf, 68, sat_lat);
- _mav_put_float(buf, 72, sat_msl);
- _mav_put_float(buf, 76, sat_ve);
- _mav_put_float(buf, 80, sat_vn);
- _mav_put_float(buf, 84, sat_vu);
- _mav_put_uint8_t(buf, 88, sat_pfix);
- _mav_put_uint8_t(buf, 89, sat_hfix);
- _mav_put_uint8_t(buf, 90, wk_state);
- _mav_put_uint8_t(buf, 91, err_code);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
- #else
- mavlink_vk_external_ins_nav_t packet;
- packet.timestamp = timestamp;
- packet.lon = lon;
- packet.lat = lat;
- packet.msl = msl;
- packet.ve = ve;
- packet.vn = vn;
- packet.vu = vu;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
- packet.gx = gx;
- packet.gy = gy;
- packet.gz = gz;
- packet.ax = ax;
- packet.ay = ay;
- packet.az = az;
- packet.sat_lon = sat_lon;
- packet.sat_lat = sat_lat;
- packet.sat_msl = sat_msl;
- packet.sat_ve = sat_ve;
- packet.sat_vn = sat_vn;
- packet.sat_vu = sat_vu;
- packet.sat_pfix = sat_pfix;
- packet.sat_hfix = sat_hfix;
- packet.wk_state = wk_state;
- packet.err_code = err_code;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV;
- #if MAVLINK_CRC_EXTRA
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
- #else
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
- #endif
- }
- /**
- * @brief Pack a vk_external_ins_nav message on a channel
- * @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 will be sent over
- * @param msg The MAVLink message to compress the data into
- * @param timestamp [ms] timestamp from system boot
- * @param lon [degE7] solved longitude
- * @param lat [degE7] solved latitude
- * @param msl [m] solved latitude
- * @param ve [m/s] solved east speed
- * @param vn [m/s] solved north speed
- * @param vu [m/s] solved up speed
- * @param yaw [deg] yaw angle
- * @param pitch [deg] pitch angle
- * @param roll [deg] roll angle
- * @param gx [deg/s] roll angle
- * @param gy [deg/s] roll angle
- * @param gz [deg/s] roll angle
- * @param ax [m/s/s] roll angle
- * @param ay [m/s/s] roll angle
- * @param az [m/s/s] roll angle
- * @param sat_lon [degE7] gps longitude
- * @param sat_lat [degE7] gps latitude
- * @param sat_msl [m] gps altitude
- * @param sat_ve [m/s] gps east speed
- * @param sat_vn [m/s] gps north speed
- * @param sat_vu [m/s] gps up speed
- * @param sat_pfix gps position fix
- * @param sat_hfix gps heading fix
- * @param wk_state work state
- * @param err_code error code
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_vk_external_ins_nav_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint32_t timestamp,int32_t lon,int32_t lat,float msl,float ve,float vn,float vu,float yaw,float pitch,float roll,float gx,float gy,float gz,float ax,float ay,float az,int32_t sat_lon,int32_t sat_lat,float sat_msl,float sat_ve,float sat_vn,float sat_vu,uint8_t sat_pfix,uint8_t sat_hfix,uint8_t wk_state,uint8_t err_code)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN];
- _mav_put_uint32_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 4, lon);
- _mav_put_int32_t(buf, 8, lat);
- _mav_put_float(buf, 12, msl);
- _mav_put_float(buf, 16, ve);
- _mav_put_float(buf, 20, vn);
- _mav_put_float(buf, 24, vu);
- _mav_put_float(buf, 28, yaw);
- _mav_put_float(buf, 32, pitch);
- _mav_put_float(buf, 36, roll);
- _mav_put_float(buf, 40, gx);
- _mav_put_float(buf, 44, gy);
- _mav_put_float(buf, 48, gz);
- _mav_put_float(buf, 52, ax);
- _mav_put_float(buf, 56, ay);
- _mav_put_float(buf, 60, az);
- _mav_put_int32_t(buf, 64, sat_lon);
- _mav_put_int32_t(buf, 68, sat_lat);
- _mav_put_float(buf, 72, sat_msl);
- _mav_put_float(buf, 76, sat_ve);
- _mav_put_float(buf, 80, sat_vn);
- _mav_put_float(buf, 84, sat_vu);
- _mav_put_uint8_t(buf, 88, sat_pfix);
- _mav_put_uint8_t(buf, 89, sat_hfix);
- _mav_put_uint8_t(buf, 90, wk_state);
- _mav_put_uint8_t(buf, 91, err_code);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
- #else
- mavlink_vk_external_ins_nav_t packet;
- packet.timestamp = timestamp;
- packet.lon = lon;
- packet.lat = lat;
- packet.msl = msl;
- packet.ve = ve;
- packet.vn = vn;
- packet.vu = vu;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
- packet.gx = gx;
- packet.gy = gy;
- packet.gz = gz;
- packet.ax = ax;
- packet.ay = ay;
- packet.az = az;
- packet.sat_lon = sat_lon;
- packet.sat_lat = sat_lat;
- packet.sat_msl = sat_msl;
- packet.sat_ve = sat_ve;
- packet.sat_vn = sat_vn;
- packet.sat_vu = sat_vu;
- packet.sat_pfix = sat_pfix;
- packet.sat_hfix = sat_hfix;
- packet.wk_state = wk_state;
- packet.err_code = err_code;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
- }
- /**
- * @brief Encode a vk_external_ins_nav struct
- *
- * @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 vk_external_ins_nav C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_vk_external_ins_nav_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vk_external_ins_nav_t* vk_external_ins_nav)
- {
- return mavlink_msg_vk_external_ins_nav_pack(system_id, component_id, msg, vk_external_ins_nav->timestamp, vk_external_ins_nav->lon, vk_external_ins_nav->lat, vk_external_ins_nav->msl, vk_external_ins_nav->ve, vk_external_ins_nav->vn, vk_external_ins_nav->vu, vk_external_ins_nav->yaw, vk_external_ins_nav->pitch, vk_external_ins_nav->roll, vk_external_ins_nav->gx, vk_external_ins_nav->gy, vk_external_ins_nav->gz, vk_external_ins_nav->ax, vk_external_ins_nav->ay, vk_external_ins_nav->az, vk_external_ins_nav->sat_lon, vk_external_ins_nav->sat_lat, vk_external_ins_nav->sat_msl, vk_external_ins_nav->sat_ve, vk_external_ins_nav->sat_vn, vk_external_ins_nav->sat_vu, vk_external_ins_nav->sat_pfix, vk_external_ins_nav->sat_hfix, vk_external_ins_nav->wk_state, vk_external_ins_nav->err_code);
- }
- /**
- * @brief Encode a vk_external_ins_nav struct on a channel
- *
- * @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 will be sent over
- * @param msg The MAVLink message to compress the data into
- * @param vk_external_ins_nav C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_vk_external_ins_nav_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vk_external_ins_nav_t* vk_external_ins_nav)
- {
- return mavlink_msg_vk_external_ins_nav_pack_chan(system_id, component_id, chan, msg, vk_external_ins_nav->timestamp, vk_external_ins_nav->lon, vk_external_ins_nav->lat, vk_external_ins_nav->msl, vk_external_ins_nav->ve, vk_external_ins_nav->vn, vk_external_ins_nav->vu, vk_external_ins_nav->yaw, vk_external_ins_nav->pitch, vk_external_ins_nav->roll, vk_external_ins_nav->gx, vk_external_ins_nav->gy, vk_external_ins_nav->gz, vk_external_ins_nav->ax, vk_external_ins_nav->ay, vk_external_ins_nav->az, vk_external_ins_nav->sat_lon, vk_external_ins_nav->sat_lat, vk_external_ins_nav->sat_msl, vk_external_ins_nav->sat_ve, vk_external_ins_nav->sat_vn, vk_external_ins_nav->sat_vu, vk_external_ins_nav->sat_pfix, vk_external_ins_nav->sat_hfix, vk_external_ins_nav->wk_state, vk_external_ins_nav->err_code);
- }
- /**
- * @brief Encode a vk_external_ins_nav struct with provided status structure
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param status MAVLink status structure
- * @param msg The MAVLink message to compress the data into
- * @param vk_external_ins_nav C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_vk_external_ins_nav_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vk_external_ins_nav_t* vk_external_ins_nav)
- {
- return mavlink_msg_vk_external_ins_nav_pack_status(system_id, component_id, _status, msg, vk_external_ins_nav->timestamp, vk_external_ins_nav->lon, vk_external_ins_nav->lat, vk_external_ins_nav->msl, vk_external_ins_nav->ve, vk_external_ins_nav->vn, vk_external_ins_nav->vu, vk_external_ins_nav->yaw, vk_external_ins_nav->pitch, vk_external_ins_nav->roll, vk_external_ins_nav->gx, vk_external_ins_nav->gy, vk_external_ins_nav->gz, vk_external_ins_nav->ax, vk_external_ins_nav->ay, vk_external_ins_nav->az, vk_external_ins_nav->sat_lon, vk_external_ins_nav->sat_lat, vk_external_ins_nav->sat_msl, vk_external_ins_nav->sat_ve, vk_external_ins_nav->sat_vn, vk_external_ins_nav->sat_vu, vk_external_ins_nav->sat_pfix, vk_external_ins_nav->sat_hfix, vk_external_ins_nav->wk_state, vk_external_ins_nav->err_code);
- }
- /**
- * @brief Send a vk_external_ins_nav message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] timestamp from system boot
- * @param lon [degE7] solved longitude
- * @param lat [degE7] solved latitude
- * @param msl [m] solved latitude
- * @param ve [m/s] solved east speed
- * @param vn [m/s] solved north speed
- * @param vu [m/s] solved up speed
- * @param yaw [deg] yaw angle
- * @param pitch [deg] pitch angle
- * @param roll [deg] roll angle
- * @param gx [deg/s] roll angle
- * @param gy [deg/s] roll angle
- * @param gz [deg/s] roll angle
- * @param ax [m/s/s] roll angle
- * @param ay [m/s/s] roll angle
- * @param az [m/s/s] roll angle
- * @param sat_lon [degE7] gps longitude
- * @param sat_lat [degE7] gps latitude
- * @param sat_msl [m] gps altitude
- * @param sat_ve [m/s] gps east speed
- * @param sat_vn [m/s] gps north speed
- * @param sat_vu [m/s] gps up speed
- * @param sat_pfix gps position fix
- * @param sat_hfix gps heading fix
- * @param wk_state work state
- * @param err_code error code
- */
- #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
- static inline void mavlink_msg_vk_external_ins_nav_send(mavlink_channel_t chan, uint32_t timestamp, int32_t lon, int32_t lat, float msl, float ve, float vn, float vu, float yaw, float pitch, float roll, float gx, float gy, float gz, float ax, float ay, float az, int32_t sat_lon, int32_t sat_lat, float sat_msl, float sat_ve, float sat_vn, float sat_vu, uint8_t sat_pfix, uint8_t sat_hfix, uint8_t wk_state, uint8_t err_code)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN];
- _mav_put_uint32_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 4, lon);
- _mav_put_int32_t(buf, 8, lat);
- _mav_put_float(buf, 12, msl);
- _mav_put_float(buf, 16, ve);
- _mav_put_float(buf, 20, vn);
- _mav_put_float(buf, 24, vu);
- _mav_put_float(buf, 28, yaw);
- _mav_put_float(buf, 32, pitch);
- _mav_put_float(buf, 36, roll);
- _mav_put_float(buf, 40, gx);
- _mav_put_float(buf, 44, gy);
- _mav_put_float(buf, 48, gz);
- _mav_put_float(buf, 52, ax);
- _mav_put_float(buf, 56, ay);
- _mav_put_float(buf, 60, az);
- _mav_put_int32_t(buf, 64, sat_lon);
- _mav_put_int32_t(buf, 68, sat_lat);
- _mav_put_float(buf, 72, sat_msl);
- _mav_put_float(buf, 76, sat_ve);
- _mav_put_float(buf, 80, sat_vn);
- _mav_put_float(buf, 84, sat_vu);
- _mav_put_uint8_t(buf, 88, sat_pfix);
- _mav_put_uint8_t(buf, 89, sat_hfix);
- _mav_put_uint8_t(buf, 90, wk_state);
- _mav_put_uint8_t(buf, 91, err_code);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV, buf, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
- #else
- mavlink_vk_external_ins_nav_t packet;
- packet.timestamp = timestamp;
- packet.lon = lon;
- packet.lat = lat;
- packet.msl = msl;
- packet.ve = ve;
- packet.vn = vn;
- packet.vu = vu;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
- packet.gx = gx;
- packet.gy = gy;
- packet.gz = gz;
- packet.ax = ax;
- packet.ay = ay;
- packet.az = az;
- packet.sat_lon = sat_lon;
- packet.sat_lat = sat_lat;
- packet.sat_msl = sat_msl;
- packet.sat_ve = sat_ve;
- packet.sat_vn = sat_vn;
- packet.sat_vu = sat_vu;
- packet.sat_pfix = sat_pfix;
- packet.sat_hfix = sat_hfix;
- packet.wk_state = wk_state;
- packet.err_code = err_code;
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV, (const char *)&packet, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
- #endif
- }
- /**
- * @brief Send a vk_external_ins_nav message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
- static inline void mavlink_msg_vk_external_ins_nav_send_struct(mavlink_channel_t chan, const mavlink_vk_external_ins_nav_t* vk_external_ins_nav)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_vk_external_ins_nav_send(chan, vk_external_ins_nav->timestamp, vk_external_ins_nav->lon, vk_external_ins_nav->lat, vk_external_ins_nav->msl, vk_external_ins_nav->ve, vk_external_ins_nav->vn, vk_external_ins_nav->vu, vk_external_ins_nav->yaw, vk_external_ins_nav->pitch, vk_external_ins_nav->roll, vk_external_ins_nav->gx, vk_external_ins_nav->gy, vk_external_ins_nav->gz, vk_external_ins_nav->ax, vk_external_ins_nav->ay, vk_external_ins_nav->az, vk_external_ins_nav->sat_lon, vk_external_ins_nav->sat_lat, vk_external_ins_nav->sat_msl, vk_external_ins_nav->sat_ve, vk_external_ins_nav->sat_vn, vk_external_ins_nav->sat_vu, vk_external_ins_nav->sat_pfix, vk_external_ins_nav->sat_hfix, vk_external_ins_nav->wk_state, vk_external_ins_nav->err_code);
- #else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV, (const char *)vk_external_ins_nav, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
- #endif
- }
- #if MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
- /*
- This variant of _send() can be used to save stack space by re-using
- memory from the receive buffer. The caller provides a
- mavlink_message_t which is the size of a full mavlink message. This
- 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_vk_external_ins_nav_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t timestamp, int32_t lon, int32_t lat, float msl, float ve, float vn, float vu, float yaw, float pitch, float roll, float gx, float gy, float gz, float ax, float ay, float az, int32_t sat_lon, int32_t sat_lat, float sat_msl, float sat_ve, float sat_vn, float sat_vu, uint8_t sat_pfix, uint8_t sat_hfix, uint8_t wk_state, uint8_t err_code)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint32_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 4, lon);
- _mav_put_int32_t(buf, 8, lat);
- _mav_put_float(buf, 12, msl);
- _mav_put_float(buf, 16, ve);
- _mav_put_float(buf, 20, vn);
- _mav_put_float(buf, 24, vu);
- _mav_put_float(buf, 28, yaw);
- _mav_put_float(buf, 32, pitch);
- _mav_put_float(buf, 36, roll);
- _mav_put_float(buf, 40, gx);
- _mav_put_float(buf, 44, gy);
- _mav_put_float(buf, 48, gz);
- _mav_put_float(buf, 52, ax);
- _mav_put_float(buf, 56, ay);
- _mav_put_float(buf, 60, az);
- _mav_put_int32_t(buf, 64, sat_lon);
- _mav_put_int32_t(buf, 68, sat_lat);
- _mav_put_float(buf, 72, sat_msl);
- _mav_put_float(buf, 76, sat_ve);
- _mav_put_float(buf, 80, sat_vn);
- _mav_put_float(buf, 84, sat_vu);
- _mav_put_uint8_t(buf, 88, sat_pfix);
- _mav_put_uint8_t(buf, 89, sat_hfix);
- _mav_put_uint8_t(buf, 90, wk_state);
- _mav_put_uint8_t(buf, 91, err_code);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV, buf, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
- #else
- mavlink_vk_external_ins_nav_t *packet = (mavlink_vk_external_ins_nav_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->lon = lon;
- packet->lat = lat;
- packet->msl = msl;
- packet->ve = ve;
- packet->vn = vn;
- packet->vu = vu;
- packet->yaw = yaw;
- packet->pitch = pitch;
- packet->roll = roll;
- packet->gx = gx;
- packet->gy = gy;
- packet->gz = gz;
- packet->ax = ax;
- packet->ay = ay;
- packet->az = az;
- packet->sat_lon = sat_lon;
- packet->sat_lat = sat_lat;
- packet->sat_msl = sat_msl;
- packet->sat_ve = sat_ve;
- packet->sat_vn = sat_vn;
- packet->sat_vu = sat_vu;
- packet->sat_pfix = sat_pfix;
- packet->sat_hfix = sat_hfix;
- packet->wk_state = wk_state;
- packet->err_code = err_code;
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV, (const char *)packet, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
- #endif
- }
- #endif
- #endif
- // MESSAGE VK_EXTERNAL_INS_NAV UNPACKING
- /**
- * @brief Get field timestamp from vk_external_ins_nav message
- *
- * @return [ms] timestamp from system boot
- */
- static inline uint32_t mavlink_msg_vk_external_ins_nav_get_timestamp(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint32_t(msg, 0);
- }
- /**
- * @brief Get field lon from vk_external_ins_nav message
- *
- * @return [degE7] solved longitude
- */
- static inline int32_t mavlink_msg_vk_external_ins_nav_get_lon(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_int32_t(msg, 4);
- }
- /**
- * @brief Get field lat from vk_external_ins_nav message
- *
- * @return [degE7] solved latitude
- */
- static inline int32_t mavlink_msg_vk_external_ins_nav_get_lat(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_int32_t(msg, 8);
- }
- /**
- * @brief Get field msl from vk_external_ins_nav message
- *
- * @return [m] solved latitude
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_msl(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 12);
- }
- /**
- * @brief Get field ve from vk_external_ins_nav message
- *
- * @return [m/s] solved east speed
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_ve(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 16);
- }
- /**
- * @brief Get field vn from vk_external_ins_nav message
- *
- * @return [m/s] solved north speed
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_vn(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 20);
- }
- /**
- * @brief Get field vu from vk_external_ins_nav message
- *
- * @return [m/s] solved up speed
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_vu(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 24);
- }
- /**
- * @brief Get field yaw from vk_external_ins_nav message
- *
- * @return [deg] yaw angle
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_yaw(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 28);
- }
- /**
- * @brief Get field pitch from vk_external_ins_nav message
- *
- * @return [deg] pitch angle
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_pitch(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 32);
- }
- /**
- * @brief Get field roll from vk_external_ins_nav message
- *
- * @return [deg] roll angle
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_roll(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 36);
- }
- /**
- * @brief Get field gx from vk_external_ins_nav message
- *
- * @return [deg/s] roll angle
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_gx(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 40);
- }
- /**
- * @brief Get field gy from vk_external_ins_nav message
- *
- * @return [deg/s] roll angle
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_gy(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 44);
- }
- /**
- * @brief Get field gz from vk_external_ins_nav message
- *
- * @return [deg/s] roll angle
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_gz(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 48);
- }
- /**
- * @brief Get field ax from vk_external_ins_nav message
- *
- * @return [m/s/s] roll angle
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_ax(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 52);
- }
- /**
- * @brief Get field ay from vk_external_ins_nav message
- *
- * @return [m/s/s] roll angle
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_ay(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 56);
- }
- /**
- * @brief Get field az from vk_external_ins_nav message
- *
- * @return [m/s/s] roll angle
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_az(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 60);
- }
- /**
- * @brief Get field sat_lon from vk_external_ins_nav message
- *
- * @return [degE7] gps longitude
- */
- static inline int32_t mavlink_msg_vk_external_ins_nav_get_sat_lon(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_int32_t(msg, 64);
- }
- /**
- * @brief Get field sat_lat from vk_external_ins_nav message
- *
- * @return [degE7] gps latitude
- */
- static inline int32_t mavlink_msg_vk_external_ins_nav_get_sat_lat(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_int32_t(msg, 68);
- }
- /**
- * @brief Get field sat_msl from vk_external_ins_nav message
- *
- * @return [m] gps altitude
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_sat_msl(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 72);
- }
- /**
- * @brief Get field sat_ve from vk_external_ins_nav message
- *
- * @return [m/s] gps east speed
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_sat_ve(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 76);
- }
- /**
- * @brief Get field sat_vn from vk_external_ins_nav message
- *
- * @return [m/s] gps north speed
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_sat_vn(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 80);
- }
- /**
- * @brief Get field sat_vu from vk_external_ins_nav message
- *
- * @return [m/s] gps up speed
- */
- static inline float mavlink_msg_vk_external_ins_nav_get_sat_vu(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 84);
- }
- /**
- * @brief Get field sat_pfix from vk_external_ins_nav message
- *
- * @return gps position fix
- */
- static inline uint8_t mavlink_msg_vk_external_ins_nav_get_sat_pfix(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint8_t(msg, 88);
- }
- /**
- * @brief Get field sat_hfix from vk_external_ins_nav message
- *
- * @return gps heading fix
- */
- static inline uint8_t mavlink_msg_vk_external_ins_nav_get_sat_hfix(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint8_t(msg, 89);
- }
- /**
- * @brief Get field wk_state from vk_external_ins_nav message
- *
- * @return work state
- */
- static inline uint8_t mavlink_msg_vk_external_ins_nav_get_wk_state(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint8_t(msg, 90);
- }
- /**
- * @brief Get field err_code from vk_external_ins_nav message
- *
- * @return error code
- */
- static inline uint8_t mavlink_msg_vk_external_ins_nav_get_err_code(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint8_t(msg, 91);
- }
- /**
- * @brief Decode a vk_external_ins_nav message into a struct
- *
- * @param msg The message to decode
- * @param vk_external_ins_nav C-struct to decode the message contents into
- */
- static inline void mavlink_msg_vk_external_ins_nav_decode(const mavlink_message_t* msg, mavlink_vk_external_ins_nav_t* vk_external_ins_nav)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- vk_external_ins_nav->timestamp = mavlink_msg_vk_external_ins_nav_get_timestamp(msg);
- vk_external_ins_nav->lon = mavlink_msg_vk_external_ins_nav_get_lon(msg);
- vk_external_ins_nav->lat = mavlink_msg_vk_external_ins_nav_get_lat(msg);
- vk_external_ins_nav->msl = mavlink_msg_vk_external_ins_nav_get_msl(msg);
- vk_external_ins_nav->ve = mavlink_msg_vk_external_ins_nav_get_ve(msg);
- vk_external_ins_nav->vn = mavlink_msg_vk_external_ins_nav_get_vn(msg);
- vk_external_ins_nav->vu = mavlink_msg_vk_external_ins_nav_get_vu(msg);
- vk_external_ins_nav->yaw = mavlink_msg_vk_external_ins_nav_get_yaw(msg);
- vk_external_ins_nav->pitch = mavlink_msg_vk_external_ins_nav_get_pitch(msg);
- vk_external_ins_nav->roll = mavlink_msg_vk_external_ins_nav_get_roll(msg);
- vk_external_ins_nav->gx = mavlink_msg_vk_external_ins_nav_get_gx(msg);
- vk_external_ins_nav->gy = mavlink_msg_vk_external_ins_nav_get_gy(msg);
- vk_external_ins_nav->gz = mavlink_msg_vk_external_ins_nav_get_gz(msg);
- vk_external_ins_nav->ax = mavlink_msg_vk_external_ins_nav_get_ax(msg);
- vk_external_ins_nav->ay = mavlink_msg_vk_external_ins_nav_get_ay(msg);
- vk_external_ins_nav->az = mavlink_msg_vk_external_ins_nav_get_az(msg);
- vk_external_ins_nav->sat_lon = mavlink_msg_vk_external_ins_nav_get_sat_lon(msg);
- vk_external_ins_nav->sat_lat = mavlink_msg_vk_external_ins_nav_get_sat_lat(msg);
- vk_external_ins_nav->sat_msl = mavlink_msg_vk_external_ins_nav_get_sat_msl(msg);
- vk_external_ins_nav->sat_ve = mavlink_msg_vk_external_ins_nav_get_sat_ve(msg);
- vk_external_ins_nav->sat_vn = mavlink_msg_vk_external_ins_nav_get_sat_vn(msg);
- vk_external_ins_nav->sat_vu = mavlink_msg_vk_external_ins_nav_get_sat_vu(msg);
- vk_external_ins_nav->sat_pfix = mavlink_msg_vk_external_ins_nav_get_sat_pfix(msg);
- vk_external_ins_nav->sat_hfix = mavlink_msg_vk_external_ins_nav_get_sat_hfix(msg);
- vk_external_ins_nav->wk_state = mavlink_msg_vk_external_ins_nav_get_wk_state(msg);
- vk_external_ins_nav->err_code = mavlink_msg_vk_external_ins_nav_get_err_code(msg);
- #else
- uint8_t len = msg->len < MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN? msg->len : MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN;
- memset(vk_external_ins_nav, 0, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
- memcpy(vk_external_ins_nav, _MAV_PAYLOAD(msg), len);
- #endif
- }
|