NinjaFlight
 All Data Structures Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
mavlink_msg_serial_udb_extra_f5.h
Go to the documentation of this file.
1 // MESSAGE SERIAL_UDB_EXTRA_F5 PACKING
2 
3 #define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5 173
4 
6 {
9  float sue_ROLLKP;
10  float sue_ROLLKD;
14 
15 #define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN 24
16 #define MAVLINK_MSG_ID_173_LEN 24
17 
18 #define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC 121
19 #define MAVLINK_MSG_ID_173_CRC 121
20 
21 
22 
23 #define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F5 { \
24  "SERIAL_UDB_EXTRA_F5", \
25  6, \
26  { { "sue_YAWKP_AILERON", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_serial_udb_extra_f5_t, sue_YAWKP_AILERON) }, \
27  { "sue_YAWKD_AILERON", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_serial_udb_extra_f5_t, sue_YAWKD_AILERON) }, \
28  { "sue_ROLLKP", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_serial_udb_extra_f5_t, sue_ROLLKP) }, \
29  { "sue_ROLLKD", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_serial_udb_extra_f5_t, sue_ROLLKD) }, \
30  { "sue_YAW_STABILIZATION_AILERON", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_serial_udb_extra_f5_t, sue_YAW_STABILIZATION_AILERON) }, \
31  { "sue_AILERON_BOOST", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_serial_udb_extra_f5_t, sue_AILERON_BOOST) }, \
32  } \
33 }
34 
35 
50 static inline uint16_t mavlink_msg_serial_udb_extra_f5_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
51  float sue_YAWKP_AILERON, float sue_YAWKD_AILERON, float sue_ROLLKP, float sue_ROLLKD, float sue_YAW_STABILIZATION_AILERON, float sue_AILERON_BOOST)
52 {
53 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
55  _mav_put_float(buf, 0, sue_YAWKP_AILERON);
56  _mav_put_float(buf, 4, sue_YAWKD_AILERON);
57  _mav_put_float(buf, 8, sue_ROLLKP);
58  _mav_put_float(buf, 12, sue_ROLLKD);
59  _mav_put_float(buf, 16, sue_YAW_STABILIZATION_AILERON);
60  _mav_put_float(buf, 20, sue_AILERON_BOOST);
61 
63 #else
65  packet.sue_YAWKP_AILERON = sue_YAWKP_AILERON;
66  packet.sue_YAWKD_AILERON = sue_YAWKD_AILERON;
67  packet.sue_ROLLKP = sue_ROLLKP;
68  packet.sue_ROLLKD = sue_ROLLKD;
69  packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON;
70  packet.sue_AILERON_BOOST = sue_AILERON_BOOST;
71 
73 #endif
74 
76 #if MAVLINK_CRC_EXTRA
78 #else
79  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN);
80 #endif
81 }
82 
97 static inline uint16_t mavlink_msg_serial_udb_extra_f5_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
98  mavlink_message_t* msg,
99  float sue_YAWKP_AILERON,float sue_YAWKD_AILERON,float sue_ROLLKP,float sue_ROLLKD,float sue_YAW_STABILIZATION_AILERON,float sue_AILERON_BOOST)
100 {
101 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
103  _mav_put_float(buf, 0, sue_YAWKP_AILERON);
104  _mav_put_float(buf, 4, sue_YAWKD_AILERON);
105  _mav_put_float(buf, 8, sue_ROLLKP);
106  _mav_put_float(buf, 12, sue_ROLLKD);
107  _mav_put_float(buf, 16, sue_YAW_STABILIZATION_AILERON);
108  _mav_put_float(buf, 20, sue_AILERON_BOOST);
109 
111 #else
113  packet.sue_YAWKP_AILERON = sue_YAWKP_AILERON;
114  packet.sue_YAWKD_AILERON = sue_YAWKD_AILERON;
115  packet.sue_ROLLKP = sue_ROLLKP;
116  packet.sue_ROLLKD = sue_ROLLKD;
117  packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON;
118  packet.sue_AILERON_BOOST = sue_AILERON_BOOST;
119 
121 #endif
122 
124 #if MAVLINK_CRC_EXTRA
126 #else
127  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN);
128 #endif
129 }
130 
139 static inline uint16_t mavlink_msg_serial_udb_extra_f5_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f5_t* serial_udb_extra_f5)
140 {
141  return mavlink_msg_serial_udb_extra_f5_pack(system_id, component_id, msg, serial_udb_extra_f5->sue_YAWKP_AILERON, serial_udb_extra_f5->sue_YAWKD_AILERON, serial_udb_extra_f5->sue_ROLLKP, serial_udb_extra_f5->sue_ROLLKD, serial_udb_extra_f5->sue_YAW_STABILIZATION_AILERON, serial_udb_extra_f5->sue_AILERON_BOOST);
142 }
143 
153 static inline uint16_t mavlink_msg_serial_udb_extra_f5_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f5_t* serial_udb_extra_f5)
154 {
155  return mavlink_msg_serial_udb_extra_f5_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f5->sue_YAWKP_AILERON, serial_udb_extra_f5->sue_YAWKD_AILERON, serial_udb_extra_f5->sue_ROLLKP, serial_udb_extra_f5->sue_ROLLKD, serial_udb_extra_f5->sue_YAW_STABILIZATION_AILERON, serial_udb_extra_f5->sue_AILERON_BOOST);
156 }
157 
169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
170 
171 static inline void mavlink_msg_serial_udb_extra_f5_send(mavlink_channel_t chan, float sue_YAWKP_AILERON, float sue_YAWKD_AILERON, float sue_ROLLKP, float sue_ROLLKD, float sue_YAW_STABILIZATION_AILERON, float sue_AILERON_BOOST)
172 {
173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
175  _mav_put_float(buf, 0, sue_YAWKP_AILERON);
176  _mav_put_float(buf, 4, sue_YAWKD_AILERON);
177  _mav_put_float(buf, 8, sue_ROLLKP);
178  _mav_put_float(buf, 12, sue_ROLLKD);
179  _mav_put_float(buf, 16, sue_YAW_STABILIZATION_AILERON);
180  _mav_put_float(buf, 20, sue_AILERON_BOOST);
181 
182 #if MAVLINK_CRC_EXTRA
184 #else
185  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN);
186 #endif
187 #else
189  packet.sue_YAWKP_AILERON = sue_YAWKP_AILERON;
190  packet.sue_YAWKD_AILERON = sue_YAWKD_AILERON;
191  packet.sue_ROLLKP = sue_ROLLKP;
192  packet.sue_ROLLKD = sue_ROLLKD;
193  packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON;
194  packet.sue_AILERON_BOOST = sue_AILERON_BOOST;
195 
196 #if MAVLINK_CRC_EXTRA
197  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC);
198 #else
199  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN);
200 #endif
201 #endif
202 }
203 
204 #if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_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_serial_udb_extra_f5_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float sue_YAWKP_AILERON, float sue_YAWKD_AILERON, float sue_ROLLKP, float sue_ROLLKD, float sue_YAW_STABILIZATION_AILERON, float sue_AILERON_BOOST)
213 {
214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
215  char *buf = (char *)msgbuf;
216  _mav_put_float(buf, 0, sue_YAWKP_AILERON);
217  _mav_put_float(buf, 4, sue_YAWKD_AILERON);
218  _mav_put_float(buf, 8, sue_ROLLKP);
219  _mav_put_float(buf, 12, sue_ROLLKD);
220  _mav_put_float(buf, 16, sue_YAW_STABILIZATION_AILERON);
221  _mav_put_float(buf, 20, sue_AILERON_BOOST);
222 
223 #if MAVLINK_CRC_EXTRA
225 #else
226  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN);
227 #endif
228 #else
230  packet->sue_YAWKP_AILERON = sue_YAWKP_AILERON;
231  packet->sue_YAWKD_AILERON = sue_YAWKD_AILERON;
232  packet->sue_ROLLKP = sue_ROLLKP;
233  packet->sue_ROLLKD = sue_ROLLKD;
234  packet->sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON;
235  packet->sue_AILERON_BOOST = sue_AILERON_BOOST;
236 
237 #if MAVLINK_CRC_EXTRA
239 #else
240  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN);
241 #endif
242 #endif
243 }
244 #endif
245 
246 #endif
247 
248 // MESSAGE SERIAL_UDB_EXTRA_F5 UNPACKING
249 
250 
256 static inline float mavlink_msg_serial_udb_extra_f5_get_sue_YAWKP_AILERON(const mavlink_message_t* msg)
257 {
258  return _MAV_RETURN_float(msg, 0);
259 }
260 
266 static inline float mavlink_msg_serial_udb_extra_f5_get_sue_YAWKD_AILERON(const mavlink_message_t* msg)
267 {
268  return _MAV_RETURN_float(msg, 4);
269 }
270 
276 static inline float mavlink_msg_serial_udb_extra_f5_get_sue_ROLLKP(const mavlink_message_t* msg)
277 {
278  return _MAV_RETURN_float(msg, 8);
279 }
280 
286 static inline float mavlink_msg_serial_udb_extra_f5_get_sue_ROLLKD(const mavlink_message_t* msg)
287 {
288  return _MAV_RETURN_float(msg, 12);
289 }
290 
296 static inline float mavlink_msg_serial_udb_extra_f5_get_sue_YAW_STABILIZATION_AILERON(const mavlink_message_t* msg)
297 {
298  return _MAV_RETURN_float(msg, 16);
299 }
300 
306 static inline float mavlink_msg_serial_udb_extra_f5_get_sue_AILERON_BOOST(const mavlink_message_t* msg)
307 {
308  return _MAV_RETURN_float(msg, 20);
309 }
310 
317 static inline void mavlink_msg_serial_udb_extra_f5_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f5_t* serial_udb_extra_f5)
318 {
319 #if MAVLINK_NEED_BYTE_SWAP
320  serial_udb_extra_f5->sue_YAWKP_AILERON = mavlink_msg_serial_udb_extra_f5_get_sue_YAWKP_AILERON(msg);
321  serial_udb_extra_f5->sue_YAWKD_AILERON = mavlink_msg_serial_udb_extra_f5_get_sue_YAWKD_AILERON(msg);
322  serial_udb_extra_f5->sue_ROLLKP = mavlink_msg_serial_udb_extra_f5_get_sue_ROLLKP(msg);
323  serial_udb_extra_f5->sue_ROLLKD = mavlink_msg_serial_udb_extra_f5_get_sue_ROLLKD(msg);
324  serial_udb_extra_f5->sue_YAW_STABILIZATION_AILERON = mavlink_msg_serial_udb_extra_f5_get_sue_YAW_STABILIZATION_AILERON(msg);
325  serial_udb_extra_f5->sue_AILERON_BOOST = mavlink_msg_serial_udb_extra_f5_get_sue_AILERON_BOOST(msg);
326 #else
327  memcpy(serial_udb_extra_f5, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN);
328 #endif
329 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145