[88] | 1 | // MESSAGE GPS2_RTK PACKING
|
---|
| 2 |
|
---|
| 3 | #define MAVLINK_MSG_ID_GPS2_RTK 128
|
---|
| 4 |
|
---|
| 5 | typedef struct MAVLINK_PACKED __mavlink_gps2_rtk_t
|
---|
| 6 | {
|
---|
| 7 | uint32_t time_last_baseline_ms; /*< Time since boot of last baseline message received in ms.*/
|
---|
| 8 | uint32_t tow; /*< GPS Time of Week of last baseline*/
|
---|
| 9 | int32_t baseline_a_mm; /*< Current baseline in ECEF x or NED north component in mm.*/
|
---|
| 10 | int32_t baseline_b_mm; /*< Current baseline in ECEF y or NED east component in mm.*/
|
---|
| 11 | int32_t baseline_c_mm; /*< Current baseline in ECEF z or NED down component in mm.*/
|
---|
| 12 | uint32_t accuracy; /*< Current estimate of baseline accuracy.*/
|
---|
| 13 | int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/
|
---|
| 14 | uint16_t wn; /*< GPS Week Number of last baseline*/
|
---|
| 15 | uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/
|
---|
| 16 | uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/
|
---|
| 17 | uint8_t rtk_rate; /*< Rate of baseline messages being received by GPS, in HZ*/
|
---|
| 18 | uint8_t nsats; /*< Current number of sats used for RTK calculation.*/
|
---|
| 19 | uint8_t baseline_coords_type; /*< Coordinate system of baseline. 0 == ECEF, 1 == NED*/
|
---|
| 20 | } mavlink_gps2_rtk_t;
|
---|
| 21 |
|
---|
| 22 | #define MAVLINK_MSG_ID_GPS2_RTK_LEN 35
|
---|
| 23 | #define MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN 35
|
---|
| 24 | #define MAVLINK_MSG_ID_128_LEN 35
|
---|
| 25 | #define MAVLINK_MSG_ID_128_MIN_LEN 35
|
---|
| 26 |
|
---|
| 27 | #define MAVLINK_MSG_ID_GPS2_RTK_CRC 226
|
---|
| 28 | #define MAVLINK_MSG_ID_128_CRC 226
|
---|
| 29 |
|
---|
| 30 |
|
---|
| 31 |
|
---|
| 32 | #if MAVLINK_COMMAND_24BIT
|
---|
| 33 | #define MAVLINK_MESSAGE_INFO_GPS2_RTK { \
|
---|
| 34 | 128, \
|
---|
| 35 | "GPS2_RTK", \
|
---|
| 36 | 13, \
|
---|
| 37 | { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \
|
---|
| 38 | { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \
|
---|
| 39 | { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \
|
---|
| 40 | { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \
|
---|
| 41 | { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \
|
---|
| 42 | { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \
|
---|
| 43 | { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \
|
---|
| 44 | { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \
|
---|
| 45 | { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \
|
---|
| 46 | { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \
|
---|
| 47 | { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \
|
---|
| 48 | { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \
|
---|
| 49 | { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \
|
---|
| 50 | } \
|
---|
| 51 | }
|
---|
| 52 | #else
|
---|
| 53 | #define MAVLINK_MESSAGE_INFO_GPS2_RTK { \
|
---|
| 54 | "GPS2_RTK", \
|
---|
| 55 | 13, \
|
---|
| 56 | { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \
|
---|
| 57 | { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \
|
---|
| 58 | { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \
|
---|
| 59 | { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \
|
---|
| 60 | { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \
|
---|
| 61 | { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \
|
---|
| 62 | { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \
|
---|
| 63 | { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \
|
---|
| 64 | { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \
|
---|
| 65 | { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \
|
---|
| 66 | { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \
|
---|
| 67 | { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \
|
---|
| 68 | { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \
|
---|
| 69 | } \
|
---|
| 70 | }
|
---|
| 71 | #endif
|
---|
| 72 |
|
---|
| 73 | /**
|
---|
| 74 | * @brief Pack a gps2_rtk message
|
---|
| 75 | * @param system_id ID of this system
|
---|
| 76 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 77 | * @param msg The MAVLink message to compress the data into
|
---|
| 78 | *
|
---|
| 79 | * @param time_last_baseline_ms Time since boot of last baseline message received in ms.
|
---|
| 80 | * @param rtk_receiver_id Identification of connected RTK receiver.
|
---|
| 81 | * @param wn GPS Week Number of last baseline
|
---|
| 82 | * @param tow GPS Time of Week of last baseline
|
---|
| 83 | * @param rtk_health GPS-specific health report for RTK data.
|
---|
| 84 | * @param rtk_rate Rate of baseline messages being received by GPS, in HZ
|
---|
| 85 | * @param nsats Current number of sats used for RTK calculation.
|
---|
| 86 | * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED
|
---|
| 87 | * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm.
|
---|
| 88 | * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm.
|
---|
| 89 | * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm.
|
---|
| 90 | * @param accuracy Current estimate of baseline accuracy.
|
---|
| 91 | * @param iar_num_hypotheses Current number of integer ambiguity hypotheses.
|
---|
| 92 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
| 93 | */
|
---|
| 94 | static inline uint16_t mavlink_msg_gps2_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
---|
| 95 | uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses)
|
---|
| 96 | {
|
---|
| 97 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 98 | char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN];
|
---|
| 99 | _mav_put_uint32_t(buf, 0, time_last_baseline_ms);
|
---|
| 100 | _mav_put_uint32_t(buf, 4, tow);
|
---|
| 101 | _mav_put_int32_t(buf, 8, baseline_a_mm);
|
---|
| 102 | _mav_put_int32_t(buf, 12, baseline_b_mm);
|
---|
| 103 | _mav_put_int32_t(buf, 16, baseline_c_mm);
|
---|
| 104 | _mav_put_uint32_t(buf, 20, accuracy);
|
---|
| 105 | _mav_put_int32_t(buf, 24, iar_num_hypotheses);
|
---|
| 106 | _mav_put_uint16_t(buf, 28, wn);
|
---|
| 107 | _mav_put_uint8_t(buf, 30, rtk_receiver_id);
|
---|
| 108 | _mav_put_uint8_t(buf, 31, rtk_health);
|
---|
| 109 | _mav_put_uint8_t(buf, 32, rtk_rate);
|
---|
| 110 | _mav_put_uint8_t(buf, 33, nsats);
|
---|
| 111 | _mav_put_uint8_t(buf, 34, baseline_coords_type);
|
---|
| 112 |
|
---|
| 113 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN);
|
---|
| 114 | #else
|
---|
| 115 | mavlink_gps2_rtk_t packet;
|
---|
| 116 | packet.time_last_baseline_ms = time_last_baseline_ms;
|
---|
| 117 | packet.tow = tow;
|
---|
| 118 | packet.baseline_a_mm = baseline_a_mm;
|
---|
| 119 | packet.baseline_b_mm = baseline_b_mm;
|
---|
| 120 | packet.baseline_c_mm = baseline_c_mm;
|
---|
| 121 | packet.accuracy = accuracy;
|
---|
| 122 | packet.iar_num_hypotheses = iar_num_hypotheses;
|
---|
| 123 | packet.wn = wn;
|
---|
| 124 | packet.rtk_receiver_id = rtk_receiver_id;
|
---|
| 125 | packet.rtk_health = rtk_health;
|
---|
| 126 | packet.rtk_rate = rtk_rate;
|
---|
| 127 | packet.nsats = nsats;
|
---|
| 128 | packet.baseline_coords_type = baseline_coords_type;
|
---|
| 129 |
|
---|
| 130 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN);
|
---|
| 131 | #endif
|
---|
| 132 |
|
---|
| 133 | msg->msgid = MAVLINK_MSG_ID_GPS2_RTK;
|
---|
| 134 | return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
|
---|
| 135 | }
|
---|
| 136 |
|
---|
| 137 | /**
|
---|
| 138 | * @brief Pack a gps2_rtk message on a channel
|
---|
| 139 | * @param system_id ID of this system
|
---|
| 140 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 141 | * @param chan The MAVLink channel this message will be sent over
|
---|
| 142 | * @param msg The MAVLink message to compress the data into
|
---|
| 143 | * @param time_last_baseline_ms Time since boot of last baseline message received in ms.
|
---|
| 144 | * @param rtk_receiver_id Identification of connected RTK receiver.
|
---|
| 145 | * @param wn GPS Week Number of last baseline
|
---|
| 146 | * @param tow GPS Time of Week of last baseline
|
---|
| 147 | * @param rtk_health GPS-specific health report for RTK data.
|
---|
| 148 | * @param rtk_rate Rate of baseline messages being received by GPS, in HZ
|
---|
| 149 | * @param nsats Current number of sats used for RTK calculation.
|
---|
| 150 | * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED
|
---|
| 151 | * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm.
|
---|
| 152 | * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm.
|
---|
| 153 | * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm.
|
---|
| 154 | * @param accuracy Current estimate of baseline accuracy.
|
---|
| 155 | * @param iar_num_hypotheses Current number of integer ambiguity hypotheses.
|
---|
| 156 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
| 157 | */
|
---|
| 158 | static inline uint16_t mavlink_msg_gps2_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
---|
| 159 | mavlink_message_t* msg,
|
---|
| 160 | uint32_t time_last_baseline_ms,uint8_t rtk_receiver_id,uint16_t wn,uint32_t tow,uint8_t rtk_health,uint8_t rtk_rate,uint8_t nsats,uint8_t baseline_coords_type,int32_t baseline_a_mm,int32_t baseline_b_mm,int32_t baseline_c_mm,uint32_t accuracy,int32_t iar_num_hypotheses)
|
---|
| 161 | {
|
---|
| 162 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 163 | char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN];
|
---|
| 164 | _mav_put_uint32_t(buf, 0, time_last_baseline_ms);
|
---|
| 165 | _mav_put_uint32_t(buf, 4, tow);
|
---|
| 166 | _mav_put_int32_t(buf, 8, baseline_a_mm);
|
---|
| 167 | _mav_put_int32_t(buf, 12, baseline_b_mm);
|
---|
| 168 | _mav_put_int32_t(buf, 16, baseline_c_mm);
|
---|
| 169 | _mav_put_uint32_t(buf, 20, accuracy);
|
---|
| 170 | _mav_put_int32_t(buf, 24, iar_num_hypotheses);
|
---|
| 171 | _mav_put_uint16_t(buf, 28, wn);
|
---|
| 172 | _mav_put_uint8_t(buf, 30, rtk_receiver_id);
|
---|
| 173 | _mav_put_uint8_t(buf, 31, rtk_health);
|
---|
| 174 | _mav_put_uint8_t(buf, 32, rtk_rate);
|
---|
| 175 | _mav_put_uint8_t(buf, 33, nsats);
|
---|
| 176 | _mav_put_uint8_t(buf, 34, baseline_coords_type);
|
---|
| 177 |
|
---|
| 178 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN);
|
---|
| 179 | #else
|
---|
| 180 | mavlink_gps2_rtk_t packet;
|
---|
| 181 | packet.time_last_baseline_ms = time_last_baseline_ms;
|
---|
| 182 | packet.tow = tow;
|
---|
| 183 | packet.baseline_a_mm = baseline_a_mm;
|
---|
| 184 | packet.baseline_b_mm = baseline_b_mm;
|
---|
| 185 | packet.baseline_c_mm = baseline_c_mm;
|
---|
| 186 | packet.accuracy = accuracy;
|
---|
| 187 | packet.iar_num_hypotheses = iar_num_hypotheses;
|
---|
| 188 | packet.wn = wn;
|
---|
| 189 | packet.rtk_receiver_id = rtk_receiver_id;
|
---|
| 190 | packet.rtk_health = rtk_health;
|
---|
| 191 | packet.rtk_rate = rtk_rate;
|
---|
| 192 | packet.nsats = nsats;
|
---|
| 193 | packet.baseline_coords_type = baseline_coords_type;
|
---|
| 194 |
|
---|
| 195 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN);
|
---|
| 196 | #endif
|
---|
| 197 |
|
---|
| 198 | msg->msgid = MAVLINK_MSG_ID_GPS2_RTK;
|
---|
| 199 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
|
---|
| 200 | }
|
---|
| 201 |
|
---|
| 202 | /**
|
---|
| 203 | * @brief Encode a gps2_rtk struct
|
---|
| 204 | *
|
---|
| 205 | * @param system_id ID of this system
|
---|
| 206 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 207 | * @param msg The MAVLink message to compress the data into
|
---|
| 208 | * @param gps2_rtk C-struct to read the message contents from
|
---|
| 209 | */
|
---|
| 210 | static inline uint16_t mavlink_msg_gps2_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk)
|
---|
| 211 | {
|
---|
| 212 | return mavlink_msg_gps2_rtk_pack(system_id, component_id, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses);
|
---|
| 213 | }
|
---|
| 214 |
|
---|
| 215 | /**
|
---|
| 216 | * @brief Encode a gps2_rtk struct on a channel
|
---|
| 217 | *
|
---|
| 218 | * @param system_id ID of this system
|
---|
| 219 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 220 | * @param chan The MAVLink channel this message will be sent over
|
---|
| 221 | * @param msg The MAVLink message to compress the data into
|
---|
| 222 | * @param gps2_rtk C-struct to read the message contents from
|
---|
| 223 | */
|
---|
| 224 | static inline uint16_t mavlink_msg_gps2_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk)
|
---|
| 225 | {
|
---|
| 226 | return mavlink_msg_gps2_rtk_pack_chan(system_id, component_id, chan, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses);
|
---|
| 227 | }
|
---|
| 228 |
|
---|
| 229 | /**
|
---|
| 230 | * @brief Send a gps2_rtk message
|
---|
| 231 | * @param chan MAVLink channel to send the message
|
---|
| 232 | *
|
---|
| 233 | * @param time_last_baseline_ms Time since boot of last baseline message received in ms.
|
---|
| 234 | * @param rtk_receiver_id Identification of connected RTK receiver.
|
---|
| 235 | * @param wn GPS Week Number of last baseline
|
---|
| 236 | * @param tow GPS Time of Week of last baseline
|
---|
| 237 | * @param rtk_health GPS-specific health report for RTK data.
|
---|
| 238 | * @param rtk_rate Rate of baseline messages being received by GPS, in HZ
|
---|
| 239 | * @param nsats Current number of sats used for RTK calculation.
|
---|
| 240 | * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED
|
---|
| 241 | * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm.
|
---|
| 242 | * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm.
|
---|
| 243 | * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm.
|
---|
| 244 | * @param accuracy Current estimate of baseline accuracy.
|
---|
| 245 | * @param iar_num_hypotheses Current number of integer ambiguity hypotheses.
|
---|
| 246 | */
|
---|
| 247 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
---|
| 248 |
|
---|
| 249 | static inline void mavlink_msg_gps2_rtk_send(mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses)
|
---|
| 250 | {
|
---|
| 251 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 252 | char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN];
|
---|
| 253 | _mav_put_uint32_t(buf, 0, time_last_baseline_ms);
|
---|
| 254 | _mav_put_uint32_t(buf, 4, tow);
|
---|
| 255 | _mav_put_int32_t(buf, 8, baseline_a_mm);
|
---|
| 256 | _mav_put_int32_t(buf, 12, baseline_b_mm);
|
---|
| 257 | _mav_put_int32_t(buf, 16, baseline_c_mm);
|
---|
| 258 | _mav_put_uint32_t(buf, 20, accuracy);
|
---|
| 259 | _mav_put_int32_t(buf, 24, iar_num_hypotheses);
|
---|
| 260 | _mav_put_uint16_t(buf, 28, wn);
|
---|
| 261 | _mav_put_uint8_t(buf, 30, rtk_receiver_id);
|
---|
| 262 | _mav_put_uint8_t(buf, 31, rtk_health);
|
---|
| 263 | _mav_put_uint8_t(buf, 32, rtk_rate);
|
---|
| 264 | _mav_put_uint8_t(buf, 33, nsats);
|
---|
| 265 | _mav_put_uint8_t(buf, 34, baseline_coords_type);
|
---|
| 266 |
|
---|
| 267 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
|
---|
| 268 | #else
|
---|
| 269 | mavlink_gps2_rtk_t packet;
|
---|
| 270 | packet.time_last_baseline_ms = time_last_baseline_ms;
|
---|
| 271 | packet.tow = tow;
|
---|
| 272 | packet.baseline_a_mm = baseline_a_mm;
|
---|
| 273 | packet.baseline_b_mm = baseline_b_mm;
|
---|
| 274 | packet.baseline_c_mm = baseline_c_mm;
|
---|
| 275 | packet.accuracy = accuracy;
|
---|
| 276 | packet.iar_num_hypotheses = iar_num_hypotheses;
|
---|
| 277 | packet.wn = wn;
|
---|
| 278 | packet.rtk_receiver_id = rtk_receiver_id;
|
---|
| 279 | packet.rtk_health = rtk_health;
|
---|
| 280 | packet.rtk_rate = rtk_rate;
|
---|
| 281 | packet.nsats = nsats;
|
---|
| 282 | packet.baseline_coords_type = baseline_coords_type;
|
---|
| 283 |
|
---|
| 284 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
|
---|
| 285 | #endif
|
---|
| 286 | }
|
---|
| 287 |
|
---|
| 288 | /**
|
---|
| 289 | * @brief Send a gps2_rtk message
|
---|
| 290 | * @param chan MAVLink channel to send the message
|
---|
| 291 | * @param struct The MAVLink struct to serialize
|
---|
| 292 | */
|
---|
| 293 | static inline void mavlink_msg_gps2_rtk_send_struct(mavlink_channel_t chan, const mavlink_gps2_rtk_t* gps2_rtk)
|
---|
| 294 | {
|
---|
| 295 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 296 | mavlink_msg_gps2_rtk_send(chan, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses);
|
---|
| 297 | #else
|
---|
| 298 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)gps2_rtk, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
|
---|
| 299 | #endif
|
---|
| 300 | }
|
---|
| 301 |
|
---|
| 302 | #if MAVLINK_MSG_ID_GPS2_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
---|
| 303 | /*
|
---|
| 304 | This varient of _send() can be used to save stack space by re-using
|
---|
| 305 | memory from the receive buffer. The caller provides a
|
---|
| 306 | mavlink_message_t which is the size of a full mavlink message. This
|
---|
| 307 | is usually the receive buffer for the channel, and allows a reply to an
|
---|
| 308 | incoming message with minimum stack space usage.
|
---|
| 309 | */
|
---|
| 310 | static inline void mavlink_msg_gps2_rtk_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses)
|
---|
| 311 | {
|
---|
| 312 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 313 | char *buf = (char *)msgbuf;
|
---|
| 314 | _mav_put_uint32_t(buf, 0, time_last_baseline_ms);
|
---|
| 315 | _mav_put_uint32_t(buf, 4, tow);
|
---|
| 316 | _mav_put_int32_t(buf, 8, baseline_a_mm);
|
---|
| 317 | _mav_put_int32_t(buf, 12, baseline_b_mm);
|
---|
| 318 | _mav_put_int32_t(buf, 16, baseline_c_mm);
|
---|
| 319 | _mav_put_uint32_t(buf, 20, accuracy);
|
---|
| 320 | _mav_put_int32_t(buf, 24, iar_num_hypotheses);
|
---|
| 321 | _mav_put_uint16_t(buf, 28, wn);
|
---|
| 322 | _mav_put_uint8_t(buf, 30, rtk_receiver_id);
|
---|
| 323 | _mav_put_uint8_t(buf, 31, rtk_health);
|
---|
| 324 | _mav_put_uint8_t(buf, 32, rtk_rate);
|
---|
| 325 | _mav_put_uint8_t(buf, 33, nsats);
|
---|
| 326 | _mav_put_uint8_t(buf, 34, baseline_coords_type);
|
---|
| 327 |
|
---|
| 328 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
|
---|
| 329 | #else
|
---|
| 330 | mavlink_gps2_rtk_t *packet = (mavlink_gps2_rtk_t *)msgbuf;
|
---|
| 331 | packet->time_last_baseline_ms = time_last_baseline_ms;
|
---|
| 332 | packet->tow = tow;
|
---|
| 333 | packet->baseline_a_mm = baseline_a_mm;
|
---|
| 334 | packet->baseline_b_mm = baseline_b_mm;
|
---|
| 335 | packet->baseline_c_mm = baseline_c_mm;
|
---|
| 336 | packet->accuracy = accuracy;
|
---|
| 337 | packet->iar_num_hypotheses = iar_num_hypotheses;
|
---|
| 338 | packet->wn = wn;
|
---|
| 339 | packet->rtk_receiver_id = rtk_receiver_id;
|
---|
| 340 | packet->rtk_health = rtk_health;
|
---|
| 341 | packet->rtk_rate = rtk_rate;
|
---|
| 342 | packet->nsats = nsats;
|
---|
| 343 | packet->baseline_coords_type = baseline_coords_type;
|
---|
| 344 |
|
---|
| 345 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
|
---|
| 346 | #endif
|
---|
| 347 | }
|
---|
| 348 | #endif
|
---|
| 349 |
|
---|
| 350 | #endif
|
---|
| 351 |
|
---|
| 352 | // MESSAGE GPS2_RTK UNPACKING
|
---|
| 353 |
|
---|
| 354 |
|
---|
| 355 | /**
|
---|
| 356 | * @brief Get field time_last_baseline_ms from gps2_rtk message
|
---|
| 357 | *
|
---|
| 358 | * @return Time since boot of last baseline message received in ms.
|
---|
| 359 | */
|
---|
| 360 | static inline uint32_t mavlink_msg_gps2_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg)
|
---|
| 361 | {
|
---|
| 362 | return _MAV_RETURN_uint32_t(msg, 0);
|
---|
| 363 | }
|
---|
| 364 |
|
---|
| 365 | /**
|
---|
| 366 | * @brief Get field rtk_receiver_id from gps2_rtk message
|
---|
| 367 | *
|
---|
| 368 | * @return Identification of connected RTK receiver.
|
---|
| 369 | */
|
---|
| 370 | static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_receiver_id(const mavlink_message_t* msg)
|
---|
| 371 | {
|
---|
| 372 | return _MAV_RETURN_uint8_t(msg, 30);
|
---|
| 373 | }
|
---|
| 374 |
|
---|
| 375 | /**
|
---|
| 376 | * @brief Get field wn from gps2_rtk message
|
---|
| 377 | *
|
---|
| 378 | * @return GPS Week Number of last baseline
|
---|
| 379 | */
|
---|
| 380 | static inline uint16_t mavlink_msg_gps2_rtk_get_wn(const mavlink_message_t* msg)
|
---|
| 381 | {
|
---|
| 382 | return _MAV_RETURN_uint16_t(msg, 28);
|
---|
| 383 | }
|
---|
| 384 |
|
---|
| 385 | /**
|
---|
| 386 | * @brief Get field tow from gps2_rtk message
|
---|
| 387 | *
|
---|
| 388 | * @return GPS Time of Week of last baseline
|
---|
| 389 | */
|
---|
| 390 | static inline uint32_t mavlink_msg_gps2_rtk_get_tow(const mavlink_message_t* msg)
|
---|
| 391 | {
|
---|
| 392 | return _MAV_RETURN_uint32_t(msg, 4);
|
---|
| 393 | }
|
---|
| 394 |
|
---|
| 395 | /**
|
---|
| 396 | * @brief Get field rtk_health from gps2_rtk message
|
---|
| 397 | *
|
---|
| 398 | * @return GPS-specific health report for RTK data.
|
---|
| 399 | */
|
---|
| 400 | static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_health(const mavlink_message_t* msg)
|
---|
| 401 | {
|
---|
| 402 | return _MAV_RETURN_uint8_t(msg, 31);
|
---|
| 403 | }
|
---|
| 404 |
|
---|
| 405 | /**
|
---|
| 406 | * @brief Get field rtk_rate from gps2_rtk message
|
---|
| 407 | *
|
---|
| 408 | * @return Rate of baseline messages being received by GPS, in HZ
|
---|
| 409 | */
|
---|
| 410 | static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_rate(const mavlink_message_t* msg)
|
---|
| 411 | {
|
---|
| 412 | return _MAV_RETURN_uint8_t(msg, 32);
|
---|
| 413 | }
|
---|
| 414 |
|
---|
| 415 | /**
|
---|
| 416 | * @brief Get field nsats from gps2_rtk message
|
---|
| 417 | *
|
---|
| 418 | * @return Current number of sats used for RTK calculation.
|
---|
| 419 | */
|
---|
| 420 | static inline uint8_t mavlink_msg_gps2_rtk_get_nsats(const mavlink_message_t* msg)
|
---|
| 421 | {
|
---|
| 422 | return _MAV_RETURN_uint8_t(msg, 33);
|
---|
| 423 | }
|
---|
| 424 |
|
---|
| 425 | /**
|
---|
| 426 | * @brief Get field baseline_coords_type from gps2_rtk message
|
---|
| 427 | *
|
---|
| 428 | * @return Coordinate system of baseline. 0 == ECEF, 1 == NED
|
---|
| 429 | */
|
---|
| 430 | static inline uint8_t mavlink_msg_gps2_rtk_get_baseline_coords_type(const mavlink_message_t* msg)
|
---|
| 431 | {
|
---|
| 432 | return _MAV_RETURN_uint8_t(msg, 34);
|
---|
| 433 | }
|
---|
| 434 |
|
---|
| 435 | /**
|
---|
| 436 | * @brief Get field baseline_a_mm from gps2_rtk message
|
---|
| 437 | *
|
---|
| 438 | * @return Current baseline in ECEF x or NED north component in mm.
|
---|
| 439 | */
|
---|
| 440 | static inline int32_t mavlink_msg_gps2_rtk_get_baseline_a_mm(const mavlink_message_t* msg)
|
---|
| 441 | {
|
---|
| 442 | return _MAV_RETURN_int32_t(msg, 8);
|
---|
| 443 | }
|
---|
| 444 |
|
---|
| 445 | /**
|
---|
| 446 | * @brief Get field baseline_b_mm from gps2_rtk message
|
---|
| 447 | *
|
---|
| 448 | * @return Current baseline in ECEF y or NED east component in mm.
|
---|
| 449 | */
|
---|
| 450 | static inline int32_t mavlink_msg_gps2_rtk_get_baseline_b_mm(const mavlink_message_t* msg)
|
---|
| 451 | {
|
---|
| 452 | return _MAV_RETURN_int32_t(msg, 12);
|
---|
| 453 | }
|
---|
| 454 |
|
---|
| 455 | /**
|
---|
| 456 | * @brief Get field baseline_c_mm from gps2_rtk message
|
---|
| 457 | *
|
---|
| 458 | * @return Current baseline in ECEF z or NED down component in mm.
|
---|
| 459 | */
|
---|
| 460 | static inline int32_t mavlink_msg_gps2_rtk_get_baseline_c_mm(const mavlink_message_t* msg)
|
---|
| 461 | {
|
---|
| 462 | return _MAV_RETURN_int32_t(msg, 16);
|
---|
| 463 | }
|
---|
| 464 |
|
---|
| 465 | /**
|
---|
| 466 | * @brief Get field accuracy from gps2_rtk message
|
---|
| 467 | *
|
---|
| 468 | * @return Current estimate of baseline accuracy.
|
---|
| 469 | */
|
---|
| 470 | static inline uint32_t mavlink_msg_gps2_rtk_get_accuracy(const mavlink_message_t* msg)
|
---|
| 471 | {
|
---|
| 472 | return _MAV_RETURN_uint32_t(msg, 20);
|
---|
| 473 | }
|
---|
| 474 |
|
---|
| 475 | /**
|
---|
| 476 | * @brief Get field iar_num_hypotheses from gps2_rtk message
|
---|
| 477 | *
|
---|
| 478 | * @return Current number of integer ambiguity hypotheses.
|
---|
| 479 | */
|
---|
| 480 | static inline int32_t mavlink_msg_gps2_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg)
|
---|
| 481 | {
|
---|
| 482 | return _MAV_RETURN_int32_t(msg, 24);
|
---|
| 483 | }
|
---|
| 484 |
|
---|
| 485 | /**
|
---|
| 486 | * @brief Decode a gps2_rtk message into a struct
|
---|
| 487 | *
|
---|
| 488 | * @param msg The message to decode
|
---|
| 489 | * @param gps2_rtk C-struct to decode the message contents into
|
---|
| 490 | */
|
---|
| 491 | static inline void mavlink_msg_gps2_rtk_decode(const mavlink_message_t* msg, mavlink_gps2_rtk_t* gps2_rtk)
|
---|
| 492 | {
|
---|
| 493 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 494 | gps2_rtk->time_last_baseline_ms = mavlink_msg_gps2_rtk_get_time_last_baseline_ms(msg);
|
---|
| 495 | gps2_rtk->tow = mavlink_msg_gps2_rtk_get_tow(msg);
|
---|
| 496 | gps2_rtk->baseline_a_mm = mavlink_msg_gps2_rtk_get_baseline_a_mm(msg);
|
---|
| 497 | gps2_rtk->baseline_b_mm = mavlink_msg_gps2_rtk_get_baseline_b_mm(msg);
|
---|
| 498 | gps2_rtk->baseline_c_mm = mavlink_msg_gps2_rtk_get_baseline_c_mm(msg);
|
---|
| 499 | gps2_rtk->accuracy = mavlink_msg_gps2_rtk_get_accuracy(msg);
|
---|
| 500 | gps2_rtk->iar_num_hypotheses = mavlink_msg_gps2_rtk_get_iar_num_hypotheses(msg);
|
---|
| 501 | gps2_rtk->wn = mavlink_msg_gps2_rtk_get_wn(msg);
|
---|
| 502 | gps2_rtk->rtk_receiver_id = mavlink_msg_gps2_rtk_get_rtk_receiver_id(msg);
|
---|
| 503 | gps2_rtk->rtk_health = mavlink_msg_gps2_rtk_get_rtk_health(msg);
|
---|
| 504 | gps2_rtk->rtk_rate = mavlink_msg_gps2_rtk_get_rtk_rate(msg);
|
---|
| 505 | gps2_rtk->nsats = mavlink_msg_gps2_rtk_get_nsats(msg);
|
---|
| 506 | gps2_rtk->baseline_coords_type = mavlink_msg_gps2_rtk_get_baseline_coords_type(msg);
|
---|
| 507 | #else
|
---|
| 508 | uint8_t len = msg->len < MAVLINK_MSG_ID_GPS2_RTK_LEN? msg->len : MAVLINK_MSG_ID_GPS2_RTK_LEN;
|
---|
| 509 | memset(gps2_rtk, 0, MAVLINK_MSG_ID_GPS2_RTK_LEN);
|
---|
| 510 | memcpy(gps2_rtk, _MAV_PAYLOAD(msg), len);
|
---|
| 511 | #endif
|
---|
| 512 | }
|
---|