4#define MAVLINK_MSG_ID_SET_MAG_OFFSETS 151
7typedef struct __mavlink_set_mag_offsets_t {
11 uint8_t target_system;
12 uint8_t target_component;
13}) mavlink_set_mag_offsets_t;
15#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN 8
16#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN 8
17#define MAVLINK_MSG_ID_151_LEN 8
18#define MAVLINK_MSG_ID_151_MIN_LEN 8
20#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC 219
21#define MAVLINK_MSG_ID_151_CRC 219
25#if MAVLINK_COMMAND_24BIT
26#define MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS { \
30 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_set_mag_offsets_t, target_system) }, \
31 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_set_mag_offsets_t, target_component) }, \
32 { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_set_mag_offsets_t, mag_ofs_x) }, \
33 { "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_set_mag_offsets_t, mag_ofs_y) }, \
34 { "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_set_mag_offsets_t, mag_ofs_z) }, \
38#define MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS { \
41 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_set_mag_offsets_t, target_system) }, \
42 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_set_mag_offsets_t, target_component) }, \
43 { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_set_mag_offsets_t, mag_ofs_x) }, \
44 { "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_set_mag_offsets_t, mag_ofs_y) }, \
45 { "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_set_mag_offsets_t, mag_ofs_z) }, \
63static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
64 uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
66#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
67 char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN];
68 _mav_put_int16_t(buf, 0, mag_ofs_x);
69 _mav_put_int16_t(buf, 2, mag_ofs_y);
70 _mav_put_int16_t(buf, 4, mag_ofs_z);
71 _mav_put_uint8_t(buf, 6, target_system);
72 _mav_put_uint8_t(buf, 7, target_component);
74 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
76 mavlink_set_mag_offsets_t packet;
77 packet.mag_ofs_x = mag_ofs_x;
78 packet.mag_ofs_y = mag_ofs_y;
79 packet.mag_ofs_z = mag_ofs_z;
80 packet.target_system = target_system;
81 packet.target_component = target_component;
83 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
86 msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
87 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
103static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
104 mavlink_message_t* msg,
105 uint8_t target_system,uint8_t target_component,int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z)
107#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
108 char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN];
109 _mav_put_int16_t(buf, 0, mag_ofs_x);
110 _mav_put_int16_t(buf, 2, mag_ofs_y);
111 _mav_put_int16_t(buf, 4, mag_ofs_z);
112 _mav_put_uint8_t(buf, 6, target_system);
113 _mav_put_uint8_t(buf, 7, target_component);
115 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
117 mavlink_set_mag_offsets_t packet;
118 packet.mag_ofs_x = mag_ofs_x;
119 packet.mag_ofs_y = mag_ofs_y;
120 packet.mag_ofs_z = mag_ofs_z;
121 packet.target_system = target_system;
122 packet.target_component = target_component;
124 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
127 msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
128 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
139static inline uint16_t mavlink_msg_set_mag_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_set_mag_offsets_t* set_mag_offsets)
141 return mavlink_msg_set_mag_offsets_pack(system_id, component_id, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
153static inline uint16_t mavlink_msg_set_mag_offsets_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_set_mag_offsets_t* set_mag_offsets)
155 return mavlink_msg_set_mag_offsets_pack_chan(system_id, component_id, chan, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
168#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
170static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
172#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
173 char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN];
174 _mav_put_int16_t(buf, 0, mag_ofs_x);
175 _mav_put_int16_t(buf, 2, mag_ofs_y);
176 _mav_put_int16_t(buf, 4, mag_ofs_z);
177 _mav_put_uint8_t(buf, 6, target_system);
178 _mav_put_uint8_t(buf, 7, target_component);
180 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
182 mavlink_set_mag_offsets_t packet;
183 packet.mag_ofs_x = mag_ofs_x;
184 packet.mag_ofs_y = mag_ofs_y;
185 packet.mag_ofs_z = mag_ofs_z;
186 packet.target_system = target_system;
187 packet.target_component = target_component;
189 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (
const char *)&packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
198static inline void mavlink_msg_set_mag_offsets_send_struct(mavlink_channel_t chan,
const mavlink_set_mag_offsets_t* set_mag_offsets)
200#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
201 mavlink_msg_set_mag_offsets_send(chan, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
203 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (
const char *)set_mag_offsets, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
207#if MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
215static inline void mavlink_msg_set_mag_offsets_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
217#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
218 char *buf = (
char *)msgbuf;
219 _mav_put_int16_t(buf, 0, mag_ofs_x);
220 _mav_put_int16_t(buf, 2, mag_ofs_y);
221 _mav_put_int16_t(buf, 4, mag_ofs_z);
222 _mav_put_uint8_t(buf, 6, target_system);
223 _mav_put_uint8_t(buf, 7, target_component);
225 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
227 mavlink_set_mag_offsets_t *packet = (mavlink_set_mag_offsets_t *)msgbuf;
228 packet->mag_ofs_x = mag_ofs_x;
229 packet->mag_ofs_y = mag_ofs_y;
230 packet->mag_ofs_z = mag_ofs_z;
231 packet->target_system = target_system;
232 packet->target_component = target_component;
234 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (
const char *)packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
249static inline uint8_t mavlink_msg_set_mag_offsets_get_target_system(
const mavlink_message_t* msg)
251 return _MAV_RETURN_uint8_t(msg, 6);
259static inline uint8_t mavlink_msg_set_mag_offsets_get_target_component(
const mavlink_message_t* msg)
261 return _MAV_RETURN_uint8_t(msg, 7);
269static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_x(
const mavlink_message_t* msg)
271 return _MAV_RETURN_int16_t(msg, 0);
279static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_y(
const mavlink_message_t* msg)
281 return _MAV_RETURN_int16_t(msg, 2);
289static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_z(
const mavlink_message_t* msg)
291 return _MAV_RETURN_int16_t(msg, 4);
300static inline void mavlink_msg_set_mag_offsets_decode(
const mavlink_message_t* msg, mavlink_set_mag_offsets_t* set_mag_offsets)
302#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
303 set_mag_offsets->mag_ofs_x = mavlink_msg_set_mag_offsets_get_mag_ofs_x(msg);
304 set_mag_offsets->mag_ofs_y = mavlink_msg_set_mag_offsets_get_mag_ofs_y(msg);
305 set_mag_offsets->mag_ofs_z = mavlink_msg_set_mag_offsets_get_mag_ofs_z(msg);
306 set_mag_offsets->target_system = mavlink_msg_set_mag_offsets_get_target_system(msg);
307 set_mag_offsets->target_component = mavlink_msg_set_mag_offsets_get_target_component(msg);
309 uint8_t len = msg->len < MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN? msg->len : MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN;
310 memset(set_mag_offsets, 0, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
311 memcpy(set_mag_offsets, _MAV_PAYLOAD(msg), len);