NinjaFlight
 All Data Structures Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
mavlink_msg_sensor_bias.h
Go to the documentation of this file.
1 // MESSAGE SENSOR_BIAS PACKING
2 
3 #define MAVLINK_MSG_ID_SENSOR_BIAS 172
4 
5 typedef struct __mavlink_sensor_bias_t
6 {
7  float axBias;
8  float ayBias;
9  float azBias;
10  float gxBias;
11  float gyBias;
12  float gzBias;
14 
15 #define MAVLINK_MSG_ID_SENSOR_BIAS_LEN 24
16 #define MAVLINK_MSG_ID_172_LEN 24
17 
18 #define MAVLINK_MSG_ID_SENSOR_BIAS_CRC 168
19 #define MAVLINK_MSG_ID_172_CRC 168
20 
21 
22 
23 #define MAVLINK_MESSAGE_INFO_SENSOR_BIAS { \
24  "SENSOR_BIAS", \
25  6, \
26  { { "axBias", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_bias_t, axBias) }, \
27  { "ayBias", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sensor_bias_t, ayBias) }, \
28  { "azBias", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sensor_bias_t, azBias) }, \
29  { "gxBias", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_bias_t, gxBias) }, \
30  { "gyBias", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_bias_t, gyBias) }, \
31  { "gzBias", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_bias_t, gzBias) }, \
32  } \
33 }
34 
35 
50 static inline uint16_t mavlink_msg_sensor_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
51  float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
52 {
53 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
55  _mav_put_float(buf, 0, axBias);
56  _mav_put_float(buf, 4, ayBias);
57  _mav_put_float(buf, 8, azBias);
58  _mav_put_float(buf, 12, gxBias);
59  _mav_put_float(buf, 16, gyBias);
60  _mav_put_float(buf, 20, gzBias);
61 
63 #else
64  mavlink_sensor_bias_t packet;
65  packet.axBias = axBias;
66  packet.ayBias = ayBias;
67  packet.azBias = azBias;
68  packet.gxBias = gxBias;
69  packet.gyBias = gyBias;
70  packet.gzBias = gzBias;
71 
73 #endif
74 
75  msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS;
76 #if MAVLINK_CRC_EXTRA
78 #else
79  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_BIAS_LEN);
80 #endif
81 }
82 
97 static inline uint16_t mavlink_msg_sensor_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
98  mavlink_message_t* msg,
99  float axBias,float ayBias,float azBias,float gxBias,float gyBias,float gzBias)
100 {
101 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
103  _mav_put_float(buf, 0, axBias);
104  _mav_put_float(buf, 4, ayBias);
105  _mav_put_float(buf, 8, azBias);
106  _mav_put_float(buf, 12, gxBias);
107  _mav_put_float(buf, 16, gyBias);
108  _mav_put_float(buf, 20, gzBias);
109 
111 #else
112  mavlink_sensor_bias_t packet;
113  packet.axBias = axBias;
114  packet.ayBias = ayBias;
115  packet.azBias = azBias;
116  packet.gxBias = gxBias;
117  packet.gyBias = gyBias;
118  packet.gzBias = gzBias;
119 
121 #endif
122 
123  msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS;
124 #if MAVLINK_CRC_EXTRA
126 #else
127  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSOR_BIAS_LEN);
128 #endif
129 }
130 
139 static 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)
140 {
141  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);
142 }
143 
153 static 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)
154 {
155  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);
156 }
157 
169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
170 
171 static inline void mavlink_msg_sensor_bias_send(mavlink_channel_t chan, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
172 {
173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
175  _mav_put_float(buf, 0, axBias);
176  _mav_put_float(buf, 4, ayBias);
177  _mav_put_float(buf, 8, azBias);
178  _mav_put_float(buf, 12, gxBias);
179  _mav_put_float(buf, 16, gyBias);
180  _mav_put_float(buf, 20, gzBias);
181 
182 #if MAVLINK_CRC_EXTRA
184 #else
185  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_BIAS, buf, MAVLINK_MSG_ID_SENSOR_BIAS_LEN);
186 #endif
187 #else
188  mavlink_sensor_bias_t packet;
189  packet.axBias = axBias;
190  packet.ayBias = ayBias;
191  packet.azBias = azBias;
192  packet.gxBias = gxBias;
193  packet.gyBias = gyBias;
194  packet.gzBias = gzBias;
195 
196 #if MAVLINK_CRC_EXTRA
197  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_BIAS, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_BIAS_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_CRC);
198 #else
199  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_BIAS, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_BIAS_LEN);
200 #endif
201 #endif
202 }
203 
204 #if MAVLINK_MSG_ID_SENSOR_BIAS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
205 /*
206  This varient of _send() can be used to save stack space by re-using
207  memory from the receive buffer. The caller provides a
208  mavlink_message_t which is the size of a full mavlink message. This
209  is usually the receive buffer for the channel, and allows a reply to an
210  incoming message with minimum stack space usage.
211  */
212 static 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)
213 {
214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
215  char *buf = (char *)msgbuf;
216  _mav_put_float(buf, 0, axBias);
217  _mav_put_float(buf, 4, ayBias);
218  _mav_put_float(buf, 8, azBias);
219  _mav_put_float(buf, 12, gxBias);
220  _mav_put_float(buf, 16, gyBias);
221  _mav_put_float(buf, 20, gzBias);
222 
223 #if MAVLINK_CRC_EXTRA
225 #else
226  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_BIAS, buf, MAVLINK_MSG_ID_SENSOR_BIAS_LEN);
227 #endif
228 #else
229  mavlink_sensor_bias_t *packet = (mavlink_sensor_bias_t *)msgbuf;
230  packet->axBias = axBias;
231  packet->ayBias = ayBias;
232  packet->azBias = azBias;
233  packet->gxBias = gxBias;
234  packet->gyBias = gyBias;
235  packet->gzBias = gzBias;
236 
237 #if MAVLINK_CRC_EXTRA
238  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_BIAS, (const char *)packet, MAVLINK_MSG_ID_SENSOR_BIAS_LEN, MAVLINK_MSG_ID_SENSOR_BIAS_CRC);
239 #else
240  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_BIAS, (const char *)packet, MAVLINK_MSG_ID_SENSOR_BIAS_LEN);
241 #endif
242 #endif
243 }
244 #endif
245 
246 #endif
247 
248 // MESSAGE SENSOR_BIAS UNPACKING
249 
250 
256 static inline float mavlink_msg_sensor_bias_get_axBias(const mavlink_message_t* msg)
257 {
258  return _MAV_RETURN_float(msg, 0);
259 }
260 
266 static inline float mavlink_msg_sensor_bias_get_ayBias(const mavlink_message_t* msg)
267 {
268  return _MAV_RETURN_float(msg, 4);
269 }
270 
276 static inline float mavlink_msg_sensor_bias_get_azBias(const mavlink_message_t* msg)
277 {
278  return _MAV_RETURN_float(msg, 8);
279 }
280 
286 static inline float mavlink_msg_sensor_bias_get_gxBias(const mavlink_message_t* msg)
287 {
288  return _MAV_RETURN_float(msg, 12);
289 }
290 
296 static inline float mavlink_msg_sensor_bias_get_gyBias(const mavlink_message_t* msg)
297 {
298  return _MAV_RETURN_float(msg, 16);
299 }
300 
306 static inline float mavlink_msg_sensor_bias_get_gzBias(const mavlink_message_t* msg)
307 {
308  return _MAV_RETURN_float(msg, 20);
309 }
310 
317 static inline void mavlink_msg_sensor_bias_decode(const mavlink_message_t* msg, mavlink_sensor_bias_t* sensor_bias)
318 {
319 #if MAVLINK_NEED_BYTE_SWAP
320  sensor_bias->axBias = mavlink_msg_sensor_bias_get_axBias(msg);
321  sensor_bias->ayBias = mavlink_msg_sensor_bias_get_ayBias(msg);
322  sensor_bias->azBias = mavlink_msg_sensor_bias_get_azBias(msg);
323  sensor_bias->gxBias = mavlink_msg_sensor_bias_get_gxBias(msg);
324  sensor_bias->gyBias = mavlink_msg_sensor_bias_get_gyBias(msg);
325  sensor_bias->gzBias = mavlink_msg_sensor_bias_get_gzBias(msg);
326 #else
327  memcpy(sensor_bias, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SENSOR_BIAS_LEN);
328 #endif
329 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145