3 #define MAVLINK_MSG_ID_SCALED_IMU 26
19 #define MAVLINK_MSG_ID_SCALED_IMU_LEN 22
20 #define MAVLINK_MSG_ID_26_LEN 22
22 #define MAVLINK_MSG_ID_SCALED_IMU_CRC 170
23 #define MAVLINK_MSG_ID_26_CRC 170
27 #define MAVLINK_MESSAGE_INFO_SCALED_IMU { \
30 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \
31 { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \
32 { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \
33 { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \
34 { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \
35 { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \
36 { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \
37 { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \
38 { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \
39 { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \
62 static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
63 uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
65 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
66 char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN];
67 _mav_put_uint32_t(buf, 0, time_boot_ms);
68 _mav_put_int16_t(buf, 4, xacc);
69 _mav_put_int16_t(buf, 6, yacc);
70 _mav_put_int16_t(buf, 8, zacc);
71 _mav_put_int16_t(buf, 10, xgyro);
72 _mav_put_int16_t(buf, 12, ygyro);
73 _mav_put_int16_t(buf, 14, zgyro);
74 _mav_put_int16_t(buf, 16, xmag);
75 _mav_put_int16_t(buf, 18, ymag);
76 _mav_put_int16_t(buf, 20, zmag);
78 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU_LEN);
92 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU_LEN);
95 msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
97 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
99 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU_LEN);
121 static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
122 mavlink_message_t* msg,
123 uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag)
125 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
126 char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN];
127 _mav_put_uint32_t(buf, 0, time_boot_ms);
128 _mav_put_int16_t(buf, 4, xacc);
129 _mav_put_int16_t(buf, 6, yacc);
130 _mav_put_int16_t(buf, 8, zacc);
131 _mav_put_int16_t(buf, 10, xgyro);
132 _mav_put_int16_t(buf, 12, ygyro);
133 _mav_put_int16_t(buf, 14, zgyro);
134 _mav_put_int16_t(buf, 16, xmag);
135 _mav_put_int16_t(buf, 18, ymag);
136 _mav_put_int16_t(buf, 20, zmag);
138 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU_LEN);
145 packet.
xgyro = xgyro;
146 packet.
ygyro = ygyro;
147 packet.
zgyro = zgyro;
152 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU_LEN);
155 msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
156 #if MAVLINK_CRC_EXTRA
157 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
159 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU_LEN);
171 static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_scaled_imu_t* scaled_imu)
173 return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->
time_boot_ms, scaled_imu->
xacc, scaled_imu->
yacc, scaled_imu->
zacc, scaled_imu->
xgyro, scaled_imu->
ygyro, scaled_imu->
zgyro, scaled_imu->
xmag, scaled_imu->
ymag, scaled_imu->
zmag);
185 static inline uint16_t mavlink_msg_scaled_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_scaled_imu_t* scaled_imu)
187 return mavlink_msg_scaled_imu_pack_chan(system_id, component_id, chan, msg, scaled_imu->
time_boot_ms, scaled_imu->
xacc, scaled_imu->
yacc, scaled_imu->
zacc, scaled_imu->
xgyro, scaled_imu->
ygyro, scaled_imu->
zgyro, scaled_imu->
xmag, scaled_imu->
ymag, scaled_imu->
zmag);
205 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
207 static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
209 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
210 char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN];
211 _mav_put_uint32_t(buf, 0, time_boot_ms);
212 _mav_put_int16_t(buf, 4, xacc);
213 _mav_put_int16_t(buf, 6, yacc);
214 _mav_put_int16_t(buf, 8, zacc);
215 _mav_put_int16_t(buf, 10, xgyro);
216 _mav_put_int16_t(buf, 12, ygyro);
217 _mav_put_int16_t(buf, 14, zgyro);
218 _mav_put_int16_t(buf, 16, xmag);
219 _mav_put_int16_t(buf, 18, ymag);
220 _mav_put_int16_t(buf, 20, zmag);
222 #if MAVLINK_CRC_EXTRA
223 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
225 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN);
233 packet.
xgyro = xgyro;
234 packet.
ygyro = ygyro;
235 packet.
zgyro = zgyro;
240 #if MAVLINK_CRC_EXTRA
241 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (
const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
243 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (
const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_LEN);
248 #if MAVLINK_MSG_ID_SCALED_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN
256 static inline void mavlink_msg_scaled_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
258 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
259 char *buf = (
char *)msgbuf;
260 _mav_put_uint32_t(buf, 0, time_boot_ms);
261 _mav_put_int16_t(buf, 4, xacc);
262 _mav_put_int16_t(buf, 6, yacc);
263 _mav_put_int16_t(buf, 8, zacc);
264 _mav_put_int16_t(buf, 10, xgyro);
265 _mav_put_int16_t(buf, 12, ygyro);
266 _mav_put_int16_t(buf, 14, zgyro);
267 _mav_put_int16_t(buf, 16, xmag);
268 _mav_put_int16_t(buf, 18, ymag);
269 _mav_put_int16_t(buf, 20, zmag);
271 #if MAVLINK_CRC_EXTRA
272 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
274 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN);
282 packet->
xgyro = xgyro;
283 packet->
ygyro = ygyro;
284 packet->
zgyro = zgyro;
289 #if MAVLINK_CRC_EXTRA
290 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (
const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
292 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (
const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_LEN);
308 static inline uint32_t mavlink_msg_scaled_imu_get_time_boot_ms(
const mavlink_message_t* msg)
310 return _MAV_RETURN_uint32_t(msg, 0);
318 static inline int16_t mavlink_msg_scaled_imu_get_xacc(
const mavlink_message_t* msg)
320 return _MAV_RETURN_int16_t(msg, 4);
328 static inline int16_t mavlink_msg_scaled_imu_get_yacc(
const mavlink_message_t* msg)
330 return _MAV_RETURN_int16_t(msg, 6);
338 static inline int16_t mavlink_msg_scaled_imu_get_zacc(
const mavlink_message_t* msg)
340 return _MAV_RETURN_int16_t(msg, 8);
348 static inline int16_t mavlink_msg_scaled_imu_get_xgyro(
const mavlink_message_t* msg)
350 return _MAV_RETURN_int16_t(msg, 10);
358 static inline int16_t mavlink_msg_scaled_imu_get_ygyro(
const mavlink_message_t* msg)
360 return _MAV_RETURN_int16_t(msg, 12);
368 static inline int16_t mavlink_msg_scaled_imu_get_zgyro(
const mavlink_message_t* msg)
370 return _MAV_RETURN_int16_t(msg, 14);
378 static inline int16_t mavlink_msg_scaled_imu_get_xmag(
const mavlink_message_t* msg)
380 return _MAV_RETURN_int16_t(msg, 16);
388 static inline int16_t mavlink_msg_scaled_imu_get_ymag(
const mavlink_message_t* msg)
390 return _MAV_RETURN_int16_t(msg, 18);
398 static inline int16_t mavlink_msg_scaled_imu_get_zmag(
const mavlink_message_t* msg)
400 return _MAV_RETURN_int16_t(msg, 20);
409 static inline void mavlink_msg_scaled_imu_decode(
const mavlink_message_t* msg,
mavlink_scaled_imu_t* scaled_imu)
411 #if MAVLINK_NEED_BYTE_SWAP
412 scaled_imu->
time_boot_ms = mavlink_msg_scaled_imu_get_time_boot_ms(msg);
413 scaled_imu->
xacc = mavlink_msg_scaled_imu_get_xacc(msg);
414 scaled_imu->
yacc = mavlink_msg_scaled_imu_get_yacc(msg);
415 scaled_imu->
zacc = mavlink_msg_scaled_imu_get_zacc(msg);
416 scaled_imu->
xgyro = mavlink_msg_scaled_imu_get_xgyro(msg);
417 scaled_imu->
ygyro = mavlink_msg_scaled_imu_get_ygyro(msg);
418 scaled_imu->
zgyro = mavlink_msg_scaled_imu_get_zgyro(msg);
419 scaled_imu->
xmag = mavlink_msg_scaled_imu_get_xmag(msg);
420 scaled_imu->
ymag = mavlink_msg_scaled_imu_get_ymag(msg);
421 scaled_imu->
zmag = mavlink_msg_scaled_imu_get_zmag(msg);
423 memcpy(scaled_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_IMU_LEN);
int16_t xgyro
Angular speed around X axis (millirad /sec)
Definition: mavlink_msg_scaled_imu.h:11
int16_t zmag
Z Magnetic field (milli tesla)
Definition: mavlink_msg_scaled_imu.h:16
int16_t ygyro
Angular speed around Y axis (millirad /sec)
Definition: mavlink_msg_scaled_imu.h:12
uint32_t time_boot_ms
Timestamp (milliseconds since system boot)
Definition: mavlink_msg_scaled_imu.h:7
Definition: mavlink_msg_scaled_imu.h:5
int16_t xmag
X Magnetic field (milli tesla)
Definition: mavlink_msg_scaled_imu.h:14
int16_t zgyro
Angular speed around Z axis (millirad /sec)
Definition: mavlink_msg_scaled_imu.h:13
int16_t xacc
X acceleration (mg)
Definition: mavlink_msg_scaled_imu.h:8
int16_t zacc
Z acceleration (mg)
Definition: mavlink_msg_scaled_imu.h:10
int16_t ymag
Y Magnetic field (milli tesla)
Definition: mavlink_msg_scaled_imu.h:15
int16_t yacc
Y acceleration (mg)
Definition: mavlink_msg_scaled_imu.h:9