4#define MAVLINK_MSG_ID_GPS_RTCM_DATA 233
7typedef struct __mavlink_gps_rtcm_data_t {
11}) mavlink_gps_rtcm_data_t;
13#define MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN 182
14#define MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN 182
15#define MAVLINK_MSG_ID_233_LEN 182
16#define MAVLINK_MSG_ID_233_MIN_LEN 182
18#define MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC 35
19#define MAVLINK_MSG_ID_233_CRC 35
21#define MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN 180
23#if MAVLINK_COMMAND_24BIT
24#define MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA { \
28 { { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_rtcm_data_t, flags) }, \
29 { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_rtcm_data_t, len) }, \
30 { "data", NULL, MAVLINK_TYPE_UINT8_T, 180, 2, offsetof(mavlink_gps_rtcm_data_t, data) }, \
34#define MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA { \
37 { { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_rtcm_data_t, flags) }, \
38 { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_rtcm_data_t, len) }, \
39 { "data", NULL, MAVLINK_TYPE_UINT8_T, 180, 2, offsetof(mavlink_gps_rtcm_data_t, data) }, \
55static inline uint16_t mavlink_msg_gps_rtcm_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
56 uint8_t flags, uint8_t len,
const uint8_t *data)
58#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
59 char buf[MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN];
60 _mav_put_uint8_t(buf, 0, flags);
61 _mav_put_uint8_t(buf, 1, len);
62 _mav_put_uint8_t_array(buf, 2, data, 180);
63 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN);
65 mavlink_gps_rtcm_data_t packet;
68 mav_array_memcpy(packet.data, data,
sizeof(uint8_t)*180);
69 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN);
72 msg->msgid = MAVLINK_MSG_ID_GPS_RTCM_DATA;
73 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC);
87static inline uint16_t mavlink_msg_gps_rtcm_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
88 mavlink_message_t* msg,
89 uint8_t flags,uint8_t len,
const uint8_t *data)
91#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
92 char buf[MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN];
93 _mav_put_uint8_t(buf, 0, flags);
94 _mav_put_uint8_t(buf, 1, len);
95 _mav_put_uint8_t_array(buf, 2, data, 180);
96 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN);
98 mavlink_gps_rtcm_data_t packet;
101 mav_array_memcpy(packet.data, data,
sizeof(uint8_t)*180);
102 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN);
105 msg->msgid = MAVLINK_MSG_ID_GPS_RTCM_DATA;
106 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC);
117static inline uint16_t mavlink_msg_gps_rtcm_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_gps_rtcm_data_t* gps_rtcm_data)
119 return mavlink_msg_gps_rtcm_data_pack(system_id, component_id, msg, gps_rtcm_data->flags, gps_rtcm_data->len, gps_rtcm_data->data);
131static inline uint16_t mavlink_msg_gps_rtcm_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_gps_rtcm_data_t* gps_rtcm_data)
133 return mavlink_msg_gps_rtcm_data_pack_chan(system_id, component_id, chan, msg, gps_rtcm_data->flags, gps_rtcm_data->len, gps_rtcm_data->data);
144#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
146static inline void mavlink_msg_gps_rtcm_data_send(mavlink_channel_t chan, uint8_t flags, uint8_t len,
const uint8_t *data)
148#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
149 char buf[MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN];
150 _mav_put_uint8_t(buf, 0, flags);
151 _mav_put_uint8_t(buf, 1, len);
152 _mav_put_uint8_t_array(buf, 2, data, 180);
153 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC);
155 mavlink_gps_rtcm_data_t packet;
156 packet.flags = flags;
158 mav_array_memcpy(packet.data, data,
sizeof(uint8_t)*180);
159 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, (
const char *)&packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC);
168static inline void mavlink_msg_gps_rtcm_data_send_struct(mavlink_channel_t chan,
const mavlink_gps_rtcm_data_t* gps_rtcm_data)
170#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
171 mavlink_msg_gps_rtcm_data_send(chan, gps_rtcm_data->flags, gps_rtcm_data->len, gps_rtcm_data->data);
173 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, (
const char *)gps_rtcm_data, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC);
177#if MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
185static inline void mavlink_msg_gps_rtcm_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t flags, uint8_t len,
const uint8_t *data)
187#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
188 char *buf = (
char *)msgbuf;
189 _mav_put_uint8_t(buf, 0, flags);
190 _mav_put_uint8_t(buf, 1, len);
191 _mav_put_uint8_t_array(buf, 2, data, 180);
192 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC);
194 mavlink_gps_rtcm_data_t *packet = (mavlink_gps_rtcm_data_t *)msgbuf;
195 packet->flags = flags;
197 mav_array_memcpy(packet->data, data,
sizeof(uint8_t)*180);
198 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, (
const char *)packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC);
213static inline uint8_t mavlink_msg_gps_rtcm_data_get_flags(
const mavlink_message_t* msg)
215 return _MAV_RETURN_uint8_t(msg, 0);
223static inline uint8_t mavlink_msg_gps_rtcm_data_get_len(
const mavlink_message_t* msg)
225 return _MAV_RETURN_uint8_t(msg, 1);
233static inline uint16_t mavlink_msg_gps_rtcm_data_get_data(
const mavlink_message_t* msg, uint8_t *data)
235 return _MAV_RETURN_uint8_t_array(msg, data, 180, 2);
244static inline void mavlink_msg_gps_rtcm_data_decode(
const mavlink_message_t* msg, mavlink_gps_rtcm_data_t* gps_rtcm_data)
246#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
247 gps_rtcm_data->flags = mavlink_msg_gps_rtcm_data_get_flags(msg);
248 gps_rtcm_data->len = mavlink_msg_gps_rtcm_data_get_len(msg);
249 mavlink_msg_gps_rtcm_data_get_data(msg, gps_rtcm_data->data);
251 uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN? msg->len : MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN;
252 memset(gps_rtcm_data, 0, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN);
253 memcpy(gps_rtcm_data, _MAV_PAYLOAD(msg), len);