3 #define MAVLINK_MSG_ID_GPS2_RTK 128
22 #define MAVLINK_MSG_ID_GPS2_RTK_LEN 35
23 #define MAVLINK_MSG_ID_128_LEN 35
25 #define MAVLINK_MSG_ID_GPS2_RTK_CRC 226
26 #define MAVLINK_MSG_ID_128_CRC 226
30 #define MAVLINK_MESSAGE_INFO_GPS2_RTK { \
33 { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \
34 { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \
35 { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \
36 { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \
37 { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \
38 { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \
39 { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \
40 { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \
41 { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \
42 { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \
43 { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \
44 { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \
45 { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \
71 static inline uint16_t mavlink_msg_gps2_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
72 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)
74 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
75 char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN];
76 _mav_put_uint32_t(buf, 0, time_last_baseline_ms);
77 _mav_put_uint32_t(buf, 4, tow);
78 _mav_put_int32_t(buf, 8, baseline_a_mm);
79 _mav_put_int32_t(buf, 12, baseline_b_mm);
80 _mav_put_int32_t(buf, 16, baseline_c_mm);
81 _mav_put_uint32_t(buf, 20, accuracy);
82 _mav_put_int32_t(buf, 24, iar_num_hypotheses);
83 _mav_put_uint16_t(buf, 28, wn);
84 _mav_put_uint8_t(buf, 30, rtk_receiver_id);
85 _mav_put_uint8_t(buf, 31, rtk_health);
86 _mav_put_uint8_t(buf, 32, rtk_rate);
87 _mav_put_uint8_t(buf, 33, nsats);
88 _mav_put_uint8_t(buf, 34, baseline_coords_type);
90 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN);
104 packet.
nsats = nsats;
107 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN);
110 msg->msgid = MAVLINK_MSG_ID_GPS2_RTK;
111 #if MAVLINK_CRC_EXTRA
112 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
114 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_LEN);
139 static inline uint16_t mavlink_msg_gps2_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
140 mavlink_message_t* msg,
141 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)
143 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
144 char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN];
145 _mav_put_uint32_t(buf, 0, time_last_baseline_ms);
146 _mav_put_uint32_t(buf, 4, tow);
147 _mav_put_int32_t(buf, 8, baseline_a_mm);
148 _mav_put_int32_t(buf, 12, baseline_b_mm);
149 _mav_put_int32_t(buf, 16, baseline_c_mm);
150 _mav_put_uint32_t(buf, 20, accuracy);
151 _mav_put_int32_t(buf, 24, iar_num_hypotheses);
152 _mav_put_uint16_t(buf, 28, wn);
153 _mav_put_uint8_t(buf, 30, rtk_receiver_id);
154 _mav_put_uint8_t(buf, 31, rtk_health);
155 _mav_put_uint8_t(buf, 32, rtk_rate);
156 _mav_put_uint8_t(buf, 33, nsats);
157 _mav_put_uint8_t(buf, 34, baseline_coords_type);
159 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN);
173 packet.
nsats = nsats;
176 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN);
179 msg->msgid = MAVLINK_MSG_ID_GPS2_RTK;
180 #if MAVLINK_CRC_EXTRA
181 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
183 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_LEN);
195 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)
197 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);
209 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)
211 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);
232 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
234 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)
236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
237 char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN];
238 _mav_put_uint32_t(buf, 0, time_last_baseline_ms);
239 _mav_put_uint32_t(buf, 4, tow);
240 _mav_put_int32_t(buf, 8, baseline_a_mm);
241 _mav_put_int32_t(buf, 12, baseline_b_mm);
242 _mav_put_int32_t(buf, 16, baseline_c_mm);
243 _mav_put_uint32_t(buf, 20, accuracy);
244 _mav_put_int32_t(buf, 24, iar_num_hypotheses);
245 _mav_put_uint16_t(buf, 28, wn);
246 _mav_put_uint8_t(buf, 30, rtk_receiver_id);
247 _mav_put_uint8_t(buf, 31, rtk_health);
248 _mav_put_uint8_t(buf, 32, rtk_rate);
249 _mav_put_uint8_t(buf, 33, nsats);
250 _mav_put_uint8_t(buf, 34, baseline_coords_type);
252 #if MAVLINK_CRC_EXTRA
253 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
255 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN);
270 packet.
nsats = nsats;
273 #if MAVLINK_CRC_EXTRA
274 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (
const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
276 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (
const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_LEN);
281 #if MAVLINK_MSG_ID_GPS2_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
289 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)
291 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
292 char *buf = (
char *)msgbuf;
293 _mav_put_uint32_t(buf, 0, time_last_baseline_ms);
294 _mav_put_uint32_t(buf, 4, tow);
295 _mav_put_int32_t(buf, 8, baseline_a_mm);
296 _mav_put_int32_t(buf, 12, baseline_b_mm);
297 _mav_put_int32_t(buf, 16, baseline_c_mm);
298 _mav_put_uint32_t(buf, 20, accuracy);
299 _mav_put_int32_t(buf, 24, iar_num_hypotheses);
300 _mav_put_uint16_t(buf, 28, wn);
301 _mav_put_uint8_t(buf, 30, rtk_receiver_id);
302 _mav_put_uint8_t(buf, 31, rtk_health);
303 _mav_put_uint8_t(buf, 32, rtk_rate);
304 _mav_put_uint8_t(buf, 33, nsats);
305 _mav_put_uint8_t(buf, 34, baseline_coords_type);
307 #if MAVLINK_CRC_EXTRA
308 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
310 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN);
325 packet->
nsats = nsats;
328 #if MAVLINK_CRC_EXTRA
329 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (
const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
331 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (
const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_LEN);
347 static inline uint32_t mavlink_msg_gps2_rtk_get_time_last_baseline_ms(
const mavlink_message_t* msg)
349 return _MAV_RETURN_uint32_t(msg, 0);
357 static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_receiver_id(
const mavlink_message_t* msg)
359 return _MAV_RETURN_uint8_t(msg, 30);
367 static inline uint16_t mavlink_msg_gps2_rtk_get_wn(
const mavlink_message_t* msg)
369 return _MAV_RETURN_uint16_t(msg, 28);
377 static inline uint32_t mavlink_msg_gps2_rtk_get_tow(
const mavlink_message_t* msg)
379 return _MAV_RETURN_uint32_t(msg, 4);
387 static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_health(
const mavlink_message_t* msg)
389 return _MAV_RETURN_uint8_t(msg, 31);
397 static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_rate(
const mavlink_message_t* msg)
399 return _MAV_RETURN_uint8_t(msg, 32);
407 static inline uint8_t mavlink_msg_gps2_rtk_get_nsats(
const mavlink_message_t* msg)
409 return _MAV_RETURN_uint8_t(msg, 33);
417 static inline uint8_t mavlink_msg_gps2_rtk_get_baseline_coords_type(
const mavlink_message_t* msg)
419 return _MAV_RETURN_uint8_t(msg, 34);
427 static inline int32_t mavlink_msg_gps2_rtk_get_baseline_a_mm(
const mavlink_message_t* msg)
429 return _MAV_RETURN_int32_t(msg, 8);
437 static inline int32_t mavlink_msg_gps2_rtk_get_baseline_b_mm(
const mavlink_message_t* msg)
439 return _MAV_RETURN_int32_t(msg, 12);
447 static inline int32_t mavlink_msg_gps2_rtk_get_baseline_c_mm(
const mavlink_message_t* msg)
449 return _MAV_RETURN_int32_t(msg, 16);
457 static inline uint32_t mavlink_msg_gps2_rtk_get_accuracy(
const mavlink_message_t* msg)
459 return _MAV_RETURN_uint32_t(msg, 20);
467 static inline int32_t mavlink_msg_gps2_rtk_get_iar_num_hypotheses(
const mavlink_message_t* msg)
469 return _MAV_RETURN_int32_t(msg, 24);
478 static inline void mavlink_msg_gps2_rtk_decode(
const mavlink_message_t* msg,
mavlink_gps2_rtk_t* gps2_rtk)
480 #if MAVLINK_NEED_BYTE_SWAP
482 gps2_rtk->
tow = mavlink_msg_gps2_rtk_get_tow(msg);
483 gps2_rtk->
baseline_a_mm = mavlink_msg_gps2_rtk_get_baseline_a_mm(msg);
484 gps2_rtk->
baseline_b_mm = mavlink_msg_gps2_rtk_get_baseline_b_mm(msg);
485 gps2_rtk->
baseline_c_mm = mavlink_msg_gps2_rtk_get_baseline_c_mm(msg);
486 gps2_rtk->
accuracy = mavlink_msg_gps2_rtk_get_accuracy(msg);
488 gps2_rtk->
wn = mavlink_msg_gps2_rtk_get_wn(msg);
489 gps2_rtk->
rtk_receiver_id = mavlink_msg_gps2_rtk_get_rtk_receiver_id(msg);
490 gps2_rtk->
rtk_health = mavlink_msg_gps2_rtk_get_rtk_health(msg);
491 gps2_rtk->
rtk_rate = mavlink_msg_gps2_rtk_get_rtk_rate(msg);
492 gps2_rtk->
nsats = mavlink_msg_gps2_rtk_get_nsats(msg);
495 memcpy(gps2_rtk, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS2_RTK_LEN);
uint16_t wn
GPS Week Number of last baseline.
Definition: mavlink_msg_gps2_rtk.h:14
int32_t baseline_b_mm
Current baseline in ECEF y or NED east component in mm.
Definition: mavlink_msg_gps2_rtk.h:10
uint8_t rtk_rate
Rate of baseline messages being received by GPS, in HZ.
Definition: mavlink_msg_gps2_rtk.h:17
uint32_t accuracy
Current estimate of baseline accuracy.
Definition: mavlink_msg_gps2_rtk.h:12
uint8_t baseline_coords_type
Coordinate system of baseline. 0 == ECEF, 1 == NED.
Definition: mavlink_msg_gps2_rtk.h:19
uint8_t nsats
Current number of sats used for RTK calculation.
Definition: mavlink_msg_gps2_rtk.h:18
int32_t iar_num_hypotheses
Current number of integer ambiguity hypotheses.
Definition: mavlink_msg_gps2_rtk.h:13
int32_t baseline_a_mm
Current baseline in ECEF x or NED north component in mm.
Definition: mavlink_msg_gps2_rtk.h:9
uint8_t rtk_receiver_id
Identification of connected RTK receiver.
Definition: mavlink_msg_gps2_rtk.h:15
uint32_t tow
GPS Time of Week of last baseline.
Definition: mavlink_msg_gps2_rtk.h:8
uint8_t rtk_health
GPS-specific health report for RTK data.
Definition: mavlink_msg_gps2_rtk.h:16
Definition: mavlink_msg_gps2_rtk.h:5
uint32_t time_last_baseline_ms
Time since boot of last baseline message received in ms.
Definition: mavlink_msg_gps2_rtk.h:7
int32_t baseline_c_mm
Current baseline in ECEF z or NED down component in mm.
Definition: mavlink_msg_gps2_rtk.h:11