mavlink_msg_hil_controls.h
Go to the documentation of this file.
1 // MESSAGE HIL_CONTROLS PACKING
2 
3 #define MAVLINK_MSG_ID_HIL_CONTROLS 91
4 
6 {
7  uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
8  float roll_ailerons; /*< Control output -1 .. 1*/
9  float pitch_elevator; /*< Control output -1 .. 1*/
10  float yaw_rudder; /*< Control output -1 .. 1*/
11  float throttle; /*< Throttle 0 .. 1*/
12  float aux1; /*< Aux 1, -1 .. 1*/
13  float aux2; /*< Aux 2, -1 .. 1*/
14  float aux3; /*< Aux 3, -1 .. 1*/
15  float aux4; /*< Aux 4, -1 .. 1*/
16  uint8_t mode; /*< System mode (MAV_MODE)*/
17  uint8_t nav_mode; /*< Navigation mode (MAV_NAV_MODE)*/
19 
20 #define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42
21 #define MAVLINK_MSG_ID_91_LEN 42
22 
23 #define MAVLINK_MSG_ID_HIL_CONTROLS_CRC 63
24 #define MAVLINK_MSG_ID_91_CRC 63
25 
26 
27 
28 #define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \
29  "HIL_CONTROLS", \
30  11, \
31  { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \
32  { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \
33  { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \
34  { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \
35  { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \
36  { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \
37  { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \
38  { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \
39  { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \
40  { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \
41  { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \
42  } \
43 }
44 
45 
65 static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
66  uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode)
67 {
68 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
70  _mav_put_uint64_t(buf, 0, time_usec);
71  _mav_put_float(buf, 8, roll_ailerons);
72  _mav_put_float(buf, 12, pitch_elevator);
73  _mav_put_float(buf, 16, yaw_rudder);
74  _mav_put_float(buf, 20, throttle);
75  _mav_put_float(buf, 24, aux1);
76  _mav_put_float(buf, 28, aux2);
77  _mav_put_float(buf, 32, aux3);
78  _mav_put_float(buf, 36, aux4);
79  _mav_put_uint8_t(buf, 40, mode);
80  _mav_put_uint8_t(buf, 41, nav_mode);
81 
83 #else
85  packet.time_usec = time_usec;
88  packet.yaw_rudder = yaw_rudder;
89  packet.throttle = throttle;
90  packet.aux1 = aux1;
91  packet.aux2 = aux2;
92  packet.aux3 = aux3;
93  packet.aux4 = aux4;
94  packet.mode = mode;
95  packet.nav_mode = nav_mode;
96 
98 #endif
99 
100  msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
101 #if MAVLINK_CRC_EXTRA
103 #else
104  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
105 #endif
106 }
107 
127 static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
128  mavlink_message_t* msg,
129  uint64_t time_usec,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,uint8_t mode,uint8_t nav_mode)
130 {
131 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
133  _mav_put_uint64_t(buf, 0, time_usec);
134  _mav_put_float(buf, 8, roll_ailerons);
135  _mav_put_float(buf, 12, pitch_elevator);
136  _mav_put_float(buf, 16, yaw_rudder);
137  _mav_put_float(buf, 20, throttle);
138  _mav_put_float(buf, 24, aux1);
139  _mav_put_float(buf, 28, aux2);
140  _mav_put_float(buf, 32, aux3);
141  _mav_put_float(buf, 36, aux4);
142  _mav_put_uint8_t(buf, 40, mode);
143  _mav_put_uint8_t(buf, 41, nav_mode);
144 
146 #else
147  mavlink_hil_controls_t packet;
148  packet.time_usec = time_usec;
149  packet.roll_ailerons = roll_ailerons;
151  packet.yaw_rudder = yaw_rudder;
152  packet.throttle = throttle;
153  packet.aux1 = aux1;
154  packet.aux2 = aux2;
155  packet.aux3 = aux3;
156  packet.aux4 = aux4;
157  packet.mode = mode;
158  packet.nav_mode = nav_mode;
159 
161 #endif
162 
163  msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
164 #if MAVLINK_CRC_EXTRA
166 #else
167  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
168 #endif
169 }
170 
179 static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls)
180 {
181  return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode);
182 }
183 
193 static inline uint16_t mavlink_msg_hil_controls_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls)
194 {
195  return mavlink_msg_hil_controls_pack_chan(system_id, component_id, chan, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode);
196 }
197 
214 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
215 
216 static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode)
217 {
218 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
220  _mav_put_uint64_t(buf, 0, time_usec);
221  _mav_put_float(buf, 8, roll_ailerons);
222  _mav_put_float(buf, 12, pitch_elevator);
223  _mav_put_float(buf, 16, yaw_rudder);
224  _mav_put_float(buf, 20, throttle);
225  _mav_put_float(buf, 24, aux1);
226  _mav_put_float(buf, 28, aux2);
227  _mav_put_float(buf, 32, aux3);
228  _mav_put_float(buf, 36, aux4);
229  _mav_put_uint8_t(buf, 40, mode);
230  _mav_put_uint8_t(buf, 41, nav_mode);
231 
232 #if MAVLINK_CRC_EXTRA
234 #else
235  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
236 #endif
237 #else
238  mavlink_hil_controls_t packet;
239  packet.time_usec = time_usec;
240  packet.roll_ailerons = roll_ailerons;
242  packet.yaw_rudder = yaw_rudder;
243  packet.throttle = throttle;
244  packet.aux1 = aux1;
245  packet.aux2 = aux2;
246  packet.aux3 = aux3;
247  packet.aux4 = aux4;
248  packet.mode = mode;
249  packet.nav_mode = nav_mode;
250 
251 #if MAVLINK_CRC_EXTRA
252  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
253 #else
254  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
255 #endif
256 #endif
257 }
258 
259 #if MAVLINK_MSG_ID_HIL_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
260 /*
261  This varient of _send() can be used to save stack space by re-using
262  memory from the receive buffer. The caller provides a
263  mavlink_message_t which is the size of a full mavlink message. This
264  is usually the receive buffer for the channel, and allows a reply to an
265  incoming message with minimum stack space usage.
266  */
267 static inline void mavlink_msg_hil_controls_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode)
268 {
269 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
270  char *buf = (char *)msgbuf;
271  _mav_put_uint64_t(buf, 0, time_usec);
272  _mav_put_float(buf, 8, roll_ailerons);
273  _mav_put_float(buf, 12, pitch_elevator);
274  _mav_put_float(buf, 16, yaw_rudder);
275  _mav_put_float(buf, 20, throttle);
276  _mav_put_float(buf, 24, aux1);
277  _mav_put_float(buf, 28, aux2);
278  _mav_put_float(buf, 32, aux3);
279  _mav_put_float(buf, 36, aux4);
280  _mav_put_uint8_t(buf, 40, mode);
281  _mav_put_uint8_t(buf, 41, nav_mode);
282 
283 #if MAVLINK_CRC_EXTRA
285 #else
286  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
287 #endif
288 #else
290  packet->time_usec = time_usec;
291  packet->roll_ailerons = roll_ailerons;
292  packet->pitch_elevator = pitch_elevator;
293  packet->yaw_rudder = yaw_rudder;
294  packet->throttle = throttle;
295  packet->aux1 = aux1;
296  packet->aux2 = aux2;
297  packet->aux3 = aux3;
298  packet->aux4 = aux4;
299  packet->mode = mode;
300  packet->nav_mode = nav_mode;
301 
302 #if MAVLINK_CRC_EXTRA
303  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
304 #else
305  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
306 #endif
307 #endif
308 }
309 #endif
310 
311 #endif
312 
313 // MESSAGE HIL_CONTROLS UNPACKING
314 
315 
321 static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t* msg)
322 {
323  return _MAV_RETURN_uint64_t(msg, 0);
324 }
325 
331 static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg)
332 {
333  return _MAV_RETURN_float(msg, 8);
334 }
335 
341 static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg)
342 {
343  return _MAV_RETURN_float(msg, 12);
344 }
345 
351 static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg)
352 {
353  return _MAV_RETURN_float(msg, 16);
354 }
355 
361 static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg)
362 {
363  return _MAV_RETURN_float(msg, 20);
364 }
365 
371 static inline float mavlink_msg_hil_controls_get_aux1(const mavlink_message_t* msg)
372 {
373  return _MAV_RETURN_float(msg, 24);
374 }
375 
381 static inline float mavlink_msg_hil_controls_get_aux2(const mavlink_message_t* msg)
382 {
383  return _MAV_RETURN_float(msg, 28);
384 }
385 
391 static inline float mavlink_msg_hil_controls_get_aux3(const mavlink_message_t* msg)
392 {
393  return _MAV_RETURN_float(msg, 32);
394 }
395 
401 static inline float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t* msg)
402 {
403  return _MAV_RETURN_float(msg, 36);
404 }
405 
411 static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg)
412 {
413  return _MAV_RETURN_uint8_t(msg, 40);
414 }
415 
421 static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg)
422 {
423  return _MAV_RETURN_uint8_t(msg, 41);
424 }
425 
432 static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls)
433 {
434 #if MAVLINK_NEED_BYTE_SWAP
439  hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg);
440  hil_controls->aux1 = mavlink_msg_hil_controls_get_aux1(msg);
441  hil_controls->aux2 = mavlink_msg_hil_controls_get_aux2(msg);
442  hil_controls->aux3 = mavlink_msg_hil_controls_get_aux3(msg);
443  hil_controls->aux4 = mavlink_msg_hil_controls_get_aux4(msg);
444  hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg);
445  hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg);
446 #else
447  memcpy(hil_controls, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
448 #endif
449 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:151
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:244
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:140
#define _mav_put_uint64_t(buf, wire_offset, b)
Definition: protocol.h:149


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:47