RflySimSDK v3.05
RflySimSDK说明文档
载入中...
搜索中...
未找到
mavlink_msg_sensor_bias.h
1#pragma once
2// MESSAGE SENSOR_BIAS PACKING
3
4#define MAVLINK_MSG_ID_SENSOR_BIAS 172
5
6MAVPACKED(
7typedef struct __mavlink_sensor_bias_t {
8 float axBias; /*< Accelerometer X bias (m/s)*/
9 float ayBias; /*< Accelerometer Y bias (m/s)*/
10 float azBias; /*< Accelerometer Z bias (m/s)*/
11 float gxBias; /*< Gyro X bias (rad/s)*/
12 float gyBias; /*< Gyro Y bias (rad/s)*/
13 float gzBias; /*< Gyro Z bias (rad/s)*/
14}) mavlink_sensor_bias_t;
15
16#define MAVLINK_MSG_ID_SENSOR_BIAS_LEN 24
17#define MAVLINK_MSG_ID_SENSOR_BIAS_MIN_LEN 24
18#define MAVLINK_MSG_ID_172_LEN 24
19#define MAVLINK_MSG_ID_172_MIN_LEN 24
20
21#define MAVLINK_MSG_ID_SENSOR_BIAS_CRC 168
22#define MAVLINK_MSG_ID_172_CRC 168
23
24
25
26#if MAVLINK_COMMAND_24BIT
27#define MAVLINK_MESSAGE_INFO_SENSOR_BIAS { \
28 172, \
29 "SENSOR_BIAS", \
30 6, \
31 { { "axBias", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_bias_t, axBias) }, \
32 { "ayBias", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sensor_bias_t, ayBias) }, \
33 { "azBias", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sensor_bias_t, azBias) }, \
34 { "gxBias", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_bias_t, gxBias) }, \
35 { "gyBias", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_bias_t, gyBias) }, \
36 { "gzBias", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_bias_t, gzBias) }, \
37 } \
38}
39#else
40#define MAVLINK_MESSAGE_INFO_SENSOR_BIAS { \
41 "SENSOR_BIAS", \
42 6, \
43 { { "axBias", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_bias_t, axBias) }, \
44 { "ayBias", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sensor_bias_t, ayBias) }, \
45 { "azBias", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sensor_bias_t, azBias) }, \
46 { "gxBias", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_bias_t, gxBias) }, \
47 { "gyBias", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_bias_t, gyBias) }, \
48 { "gzBias", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_bias_t, gzBias) }, \
49 } \
50}
51#endif
52
67static inline uint16_t mavlink_msg_sensor_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
68 float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
69{
70#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
71 char buf[MAVLINK_MSG_ID_SENSOR_BIAS_LEN];
72 _mav_put_float(buf, 0, axBias);
73 _mav_put_float(buf, 4, ayBias);
74 _mav_put_float(buf, 8, azBias);
75 _mav_put_float(buf, 12, gxBias);
76 _mav_put_float(buf, 16, gyBias);
77 _mav_put_float(buf, 20, gzBias);
78
79 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_BIAS_LEN);
80#else
81 mavlink_sensor_bias_t packet;
82 packet.axBias = axBias;
83 packet.ayBias = ayBias;
84 packet.azBias = azBias;
85 packet.gxBias = gxBias;
86 packet.gyBias = gyBias;
87 packet.gzBias = gzBias;
88
89 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_BIAS_LEN);
90#endif
91
92 msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS;
93 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_BIAS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_CRC);
94}
95
110static inline uint16_t mavlink_msg_sensor_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
111 mavlink_message_t* msg,
112 float axBias,float ayBias,float azBias,float gxBias,float gyBias,float gzBias)
113{
114#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
115 char buf[MAVLINK_MSG_ID_SENSOR_BIAS_LEN];
116 _mav_put_float(buf, 0, axBias);
117 _mav_put_float(buf, 4, ayBias);
118 _mav_put_float(buf, 8, azBias);
119 _mav_put_float(buf, 12, gxBias);
120 _mav_put_float(buf, 16, gyBias);
121 _mav_put_float(buf, 20, gzBias);
122
123 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_BIAS_LEN);
124#else
125 mavlink_sensor_bias_t packet;
126 packet.axBias = axBias;
127 packet.ayBias = ayBias;
128 packet.azBias = azBias;
129 packet.gxBias = gxBias;
130 packet.gyBias = gyBias;
131 packet.gzBias = gzBias;
132
133 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_BIAS_LEN);
134#endif
135
136 msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS;
137 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSOR_BIAS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_CRC);
138}
139
148static inline uint16_t mavlink_msg_sensor_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_bias_t* sensor_bias)
149{
150 return mavlink_msg_sensor_bias_pack(system_id, component_id, msg, sensor_bias->axBias, sensor_bias->ayBias, sensor_bias->azBias, sensor_bias->gxBias, sensor_bias->gyBias, sensor_bias->gzBias);
151}
152
162static inline uint16_t mavlink_msg_sensor_bias_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sensor_bias_t* sensor_bias)
163{
164 return mavlink_msg_sensor_bias_pack_chan(system_id, component_id, chan, msg, sensor_bias->axBias, sensor_bias->ayBias, sensor_bias->azBias, sensor_bias->gxBias, sensor_bias->gyBias, sensor_bias->gzBias);
165}
166
178#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
179
180static inline void mavlink_msg_sensor_bias_send(mavlink_channel_t chan, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
181{
182#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
183 char buf[MAVLINK_MSG_ID_SENSOR_BIAS_LEN];
184 _mav_put_float(buf, 0, axBias);
185 _mav_put_float(buf, 4, ayBias);
186 _mav_put_float(buf, 8, azBias);
187 _mav_put_float(buf, 12, gxBias);
188 _mav_put_float(buf, 16, gyBias);
189 _mav_put_float(buf, 20, gzBias);
190
191 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_BIAS, buf, MAVLINK_MSG_ID_SENSOR_BIAS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_CRC);
192#else
193 mavlink_sensor_bias_t packet;
194 packet.axBias = axBias;
195 packet.ayBias = ayBias;
196 packet.azBias = azBias;
197 packet.gxBias = gxBias;
198 packet.gyBias = gyBias;
199 packet.gzBias = gzBias;
200
201 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_BIAS, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_BIAS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_CRC);
202#endif
203}
204
210static inline void mavlink_msg_sensor_bias_send_struct(mavlink_channel_t chan, const mavlink_sensor_bias_t* sensor_bias)
211{
212#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
213 mavlink_msg_sensor_bias_send(chan, sensor_bias->axBias, sensor_bias->ayBias, sensor_bias->azBias, sensor_bias->gxBias, sensor_bias->gyBias, sensor_bias->gzBias);
214#else
215 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_BIAS, (const char *)sensor_bias, MAVLINK_MSG_ID_SENSOR_BIAS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_CRC);
216#endif
217}
218
219#if MAVLINK_MSG_ID_SENSOR_BIAS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
220/*
221 This varient of _send() can be used to save stack space by re-using
222 memory from the receive buffer. The caller provides a
223 mavlink_message_t which is the size of a full mavlink message. This
224 is usually the receive buffer for the channel, and allows a reply to an
225 incoming message with minimum stack space usage.
226 */
227static inline void mavlink_msg_sensor_bias_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
228{
229#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
230 char *buf = (char *)msgbuf;
231 _mav_put_float(buf, 0, axBias);
232 _mav_put_float(buf, 4, ayBias);
233 _mav_put_float(buf, 8, azBias);
234 _mav_put_float(buf, 12, gxBias);
235 _mav_put_float(buf, 16, gyBias);
236 _mav_put_float(buf, 20, gzBias);
237
238 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_BIAS, buf, MAVLINK_MSG_ID_SENSOR_BIAS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_CRC);
239#else
240 mavlink_sensor_bias_t *packet = (mavlink_sensor_bias_t *)msgbuf;
241 packet->axBias = axBias;
242 packet->ayBias = ayBias;
243 packet->azBias = azBias;
244 packet->gxBias = gxBias;
245 packet->gyBias = gyBias;
246 packet->gzBias = gzBias;
247
248 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_BIAS, (const char *)packet, MAVLINK_MSG_ID_SENSOR_BIAS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_CRC);
249#endif
250}
251#endif
252
253#endif
254
255// MESSAGE SENSOR_BIAS UNPACKING
256
257
263static inline float mavlink_msg_sensor_bias_get_axBias(const mavlink_message_t* msg)
264{
265 return _MAV_RETURN_float(msg, 0);
266}
267
273static inline float mavlink_msg_sensor_bias_get_ayBias(const mavlink_message_t* msg)
274{
275 return _MAV_RETURN_float(msg, 4);
276}
277
283static inline float mavlink_msg_sensor_bias_get_azBias(const mavlink_message_t* msg)
284{
285 return _MAV_RETURN_float(msg, 8);
286}
287
293static inline float mavlink_msg_sensor_bias_get_gxBias(const mavlink_message_t* msg)
294{
295 return _MAV_RETURN_float(msg, 12);
296}
297
303static inline float mavlink_msg_sensor_bias_get_gyBias(const mavlink_message_t* msg)
304{
305 return _MAV_RETURN_float(msg, 16);
306}
307
313static inline float mavlink_msg_sensor_bias_get_gzBias(const mavlink_message_t* msg)
314{
315 return _MAV_RETURN_float(msg, 20);
316}
317
324static inline void mavlink_msg_sensor_bias_decode(const mavlink_message_t* msg, mavlink_sensor_bias_t* sensor_bias)
325{
326#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
327 sensor_bias->axBias = mavlink_msg_sensor_bias_get_axBias(msg);
328 sensor_bias->ayBias = mavlink_msg_sensor_bias_get_ayBias(msg);
329 sensor_bias->azBias = mavlink_msg_sensor_bias_get_azBias(msg);
330 sensor_bias->gxBias = mavlink_msg_sensor_bias_get_gxBias(msg);
331 sensor_bias->gyBias = mavlink_msg_sensor_bias_get_gyBias(msg);
332 sensor_bias->gzBias = mavlink_msg_sensor_bias_get_gzBias(msg);
333#else
334 uint8_t len = msg->len < MAVLINK_MSG_ID_SENSOR_BIAS_LEN? msg->len : MAVLINK_MSG_ID_SENSOR_BIAS_LEN;
335 memset(sensor_bias, 0, MAVLINK_MSG_ID_SENSOR_BIAS_LEN);
336 memcpy(sensor_bias, _MAV_PAYLOAD(msg), len);
337#endif
338}