1 // MESSAGE GPS_INJECT_DATA PACKING
3 #define MAVLINK_MSG_ID_GPS_INJECT_DATA 123
5 typedef struct __mavlink_gps_inject_data_t
7 uint8_t target_system
; ///< System ID
8 uint8_t target_component
; ///< Component ID
9 uint8_t len
; ///< data length
10 uint8_t data
[110]; ///< raw data (110 is enough for 12 satellites of RTCMv2)
11 } mavlink_gps_inject_data_t
;
13 #define MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113
14 #define MAVLINK_MSG_ID_123_LEN 113
16 #define MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC 250
17 #define MAVLINK_MSG_ID_123_CRC 250
19 #define MAVLINK_MSG_GPS_INJECT_DATA_FIELD_DATA_LEN 110
21 #define MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA { \
24 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_inject_data_t, target_system) }, \
25 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_inject_data_t, target_component) }, \
26 { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gps_inject_data_t, len) }, \
27 { "data", NULL, MAVLINK_TYPE_UINT8_T, 110, 3, offsetof(mavlink_gps_inject_data_t, data) }, \
33 * @brief Pack a gps_inject_data message
34 * @param system_id ID of this system
35 * @param component_id ID of this component (e.g. 200 for IMU)
36 * @param msg The MAVLink message to compress the data into
38 * @param target_system System ID
39 * @param target_component Component ID
40 * @param len data length
41 * @param data raw data (110 is enough for 12 satellites of RTCMv2)
42 * @return length of the message in bytes (excluding serial stream start sign)
44 static inline uint16_t mavlink_msg_gps_inject_data_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
45 uint8_t target_system
, uint8_t target_component
, uint8_t len
, const uint8_t *data
)
47 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
48 char buf
[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
];
49 _mav_put_uint8_t(buf
, 0, target_system
);
50 _mav_put_uint8_t(buf
, 1, target_component
);
51 _mav_put_uint8_t(buf
, 2, len
);
52 _mav_put_uint8_t_array(buf
, 3, data
, 110);
53 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
);
55 mavlink_gps_inject_data_t packet
;
56 packet
.target_system
= target_system
;
57 packet
.target_component
= target_component
;
59 mav_array_memcpy(packet
.data
, data
, sizeof(uint8_t)*110);
60 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
);
63 msg
->msgid
= MAVLINK_MSG_ID_GPS_INJECT_DATA
;
65 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC
);
67 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
);
72 * @brief Pack a gps_inject_data message on a channel
73 * @param system_id ID of this system
74 * @param component_id ID of this component (e.g. 200 for IMU)
75 * @param chan The MAVLink channel this message will be sent over
76 * @param msg The MAVLink message to compress the data into
77 * @param target_system System ID
78 * @param target_component Component ID
79 * @param len data length
80 * @param data raw data (110 is enough for 12 satellites of RTCMv2)
81 * @return length of the message in bytes (excluding serial stream start sign)
83 static inline uint16_t mavlink_msg_gps_inject_data_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
84 mavlink_message_t
* msg
,
85 uint8_t target_system
,uint8_t target_component
,uint8_t len
,const uint8_t *data
)
87 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
88 char buf
[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
];
89 _mav_put_uint8_t(buf
, 0, target_system
);
90 _mav_put_uint8_t(buf
, 1, target_component
);
91 _mav_put_uint8_t(buf
, 2, len
);
92 _mav_put_uint8_t_array(buf
, 3, data
, 110);
93 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
);
95 mavlink_gps_inject_data_t packet
;
96 packet
.target_system
= target_system
;
97 packet
.target_component
= target_component
;
99 mav_array_memcpy(packet
.data
, data
, sizeof(uint8_t)*110);
100 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
);
103 msg
->msgid
= MAVLINK_MSG_ID_GPS_INJECT_DATA
;
104 #if MAVLINK_CRC_EXTRA
105 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC
);
107 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
);
112 * @brief Encode a gps_inject_data struct
114 * @param system_id ID of this system
115 * @param component_id ID of this component (e.g. 200 for IMU)
116 * @param msg The MAVLink message to compress the data into
117 * @param gps_inject_data C-struct to read the message contents from
119 static inline uint16_t mavlink_msg_gps_inject_data_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_gps_inject_data_t
* gps_inject_data
)
121 return mavlink_msg_gps_inject_data_pack(system_id
, component_id
, msg
, gps_inject_data
->target_system
, gps_inject_data
->target_component
, gps_inject_data
->len
, gps_inject_data
->data
);
125 * @brief Encode a gps_inject_data struct on a channel
127 * @param system_id ID of this system
128 * @param component_id ID of this component (e.g. 200 for IMU)
129 * @param chan The MAVLink channel this message will be sent over
130 * @param msg The MAVLink message to compress the data into
131 * @param gps_inject_data C-struct to read the message contents from
133 static inline uint16_t mavlink_msg_gps_inject_data_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_gps_inject_data_t
* gps_inject_data
)
135 return mavlink_msg_gps_inject_data_pack_chan(system_id
, component_id
, chan
, msg
, gps_inject_data
->target_system
, gps_inject_data
->target_component
, gps_inject_data
->len
, gps_inject_data
->data
);
139 * @brief Send a gps_inject_data message
140 * @param chan MAVLink channel to send the message
142 * @param target_system System ID
143 * @param target_component Component ID
144 * @param len data length
145 * @param data raw data (110 is enough for 12 satellites of RTCMv2)
147 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
149 static inline void mavlink_msg_gps_inject_data_send(mavlink_channel_t chan
, uint8_t target_system
, uint8_t target_component
, uint8_t len
, const uint8_t *data
)
151 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
152 char buf
[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
];
153 _mav_put_uint8_t(buf
, 0, target_system
);
154 _mav_put_uint8_t(buf
, 1, target_component
);
155 _mav_put_uint8_t(buf
, 2, len
);
156 _mav_put_uint8_t_array(buf
, 3, data
, 110);
157 #if MAVLINK_CRC_EXTRA
158 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_INJECT_DATA
, buf
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC
);
160 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_INJECT_DATA
, buf
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
);
163 mavlink_gps_inject_data_t packet
;
164 packet
.target_system
= target_system
;
165 packet
.target_component
= target_component
;
167 mav_array_memcpy(packet
.data
, data
, sizeof(uint8_t)*110);
168 #if MAVLINK_CRC_EXTRA
169 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_INJECT_DATA
, (const char *)&packet
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC
);
171 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_INJECT_DATA
, (const char *)&packet
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
);
176 #if MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
178 This varient of _send() can be used to save stack space by re-using
179 memory from the receive buffer. The caller provides a
180 mavlink_message_t which is the size of a full mavlink message. This
181 is usually the receive buffer for the channel, and allows a reply to an
182 incoming message with minimum stack space usage.
184 static inline void mavlink_msg_gps_inject_data_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint8_t target_system
, uint8_t target_component
, uint8_t len
, const uint8_t *data
)
186 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
187 char *buf
= (char *)msgbuf
;
188 _mav_put_uint8_t(buf
, 0, target_system
);
189 _mav_put_uint8_t(buf
, 1, target_component
);
190 _mav_put_uint8_t(buf
, 2, len
);
191 _mav_put_uint8_t_array(buf
, 3, data
, 110);
192 #if MAVLINK_CRC_EXTRA
193 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_INJECT_DATA
, buf
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC
);
195 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_INJECT_DATA
, buf
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
);
198 mavlink_gps_inject_data_t
*packet
= (mavlink_gps_inject_data_t
*)msgbuf
;
199 packet
->target_system
= target_system
;
200 packet
->target_component
= target_component
;
202 mav_array_memcpy(packet
->data
, data
, sizeof(uint8_t)*110);
203 #if MAVLINK_CRC_EXTRA
204 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_INJECT_DATA
, (const char *)packet
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC
);
206 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_INJECT_DATA
, (const char *)packet
, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
);
214 // MESSAGE GPS_INJECT_DATA UNPACKING
218 * @brief Get field target_system from gps_inject_data message
222 static inline uint8_t mavlink_msg_gps_inject_data_get_target_system(const mavlink_message_t
* msg
)
224 return _MAV_RETURN_uint8_t(msg
, 0);
228 * @brief Get field target_component from gps_inject_data message
230 * @return Component ID
232 static inline uint8_t mavlink_msg_gps_inject_data_get_target_component(const mavlink_message_t
* msg
)
234 return _MAV_RETURN_uint8_t(msg
, 1);
238 * @brief Get field len from gps_inject_data message
240 * @return data length
242 static inline uint8_t mavlink_msg_gps_inject_data_get_len(const mavlink_message_t
* msg
)
244 return _MAV_RETURN_uint8_t(msg
, 2);
248 * @brief Get field data from gps_inject_data message
250 * @return raw data (110 is enough for 12 satellites of RTCMv2)
252 static inline uint16_t mavlink_msg_gps_inject_data_get_data(const mavlink_message_t
* msg
, uint8_t *data
)
254 return _MAV_RETURN_uint8_t_array(msg
, data
, 110, 3);
258 * @brief Decode a gps_inject_data message into a struct
260 * @param msg The message to decode
261 * @param gps_inject_data C-struct to decode the message contents into
263 static inline void mavlink_msg_gps_inject_data_decode(const mavlink_message_t
* msg
, mavlink_gps_inject_data_t
* gps_inject_data
)
265 #if MAVLINK_NEED_BYTE_SWAP
266 gps_inject_data
->target_system
= mavlink_msg_gps_inject_data_get_target_system(msg
);
267 gps_inject_data
->target_component
= mavlink_msg_gps_inject_data_get_target_component(msg
);
268 gps_inject_data
->len
= mavlink_msg_gps_inject_data_get_len(msg
);
269 mavlink_msg_gps_inject_data_get_data(msg
, gps_inject_data
->data
);
271 memcpy(gps_inject_data
, _MAV_PAYLOAD(msg
), MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN
);