mavlink_msg_rosflight_aux_cmd.h
Go to the documentation of this file.
1 // MESSAGE ROSFLIGHT_AUX_CMD PACKING
2 
3 #define MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD 193
4 
6 {
7  float aux_cmd_array[14]; /*< */
8  uint8_t type_array[14]; /*< */
10 
11 #define MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD_LEN 70
12 #define MAVLINK_MSG_ID_193_LEN 70
13 
14 #define MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD_CRC 1
15 #define MAVLINK_MSG_ID_193_CRC 1
16 
17 #define MAVLINK_MSG_ROSFLIGHT_AUX_CMD_FIELD_AUX_CMD_ARRAY_LEN 14
18 #define MAVLINK_MSG_ROSFLIGHT_AUX_CMD_FIELD_TYPE_ARRAY_LEN 14
19 
20 #define MAVLINK_MESSAGE_INFO_ROSFLIGHT_AUX_CMD { \
21  "ROSFLIGHT_AUX_CMD", \
22  2, \
23  { { "aux_cmd_array", NULL, MAVLINK_TYPE_FLOAT, 14, 0, offsetof(mavlink_rosflight_aux_cmd_t, aux_cmd_array) }, \
24  { "type_array", NULL, MAVLINK_TYPE_UINT8_T, 14, 56, offsetof(mavlink_rosflight_aux_cmd_t, type_array) }, \
25  } \
26 }
27 
28 
39 static inline uint16_t mavlink_msg_rosflight_aux_cmd_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
40  const uint8_t *type_array, const float *aux_cmd_array)
41 {
42 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
44 
45  _mav_put_float_array(buf, 0, aux_cmd_array, 14);
46  _mav_put_uint8_t_array(buf, 56, type_array, 14);
48 #else
50 
51  mav_array_memcpy(packet.aux_cmd_array, aux_cmd_array, sizeof(float)*14);
52  mav_array_memcpy(packet.type_array, type_array, sizeof(uint8_t)*14);
54 #endif
55 
57 #if MAVLINK_CRC_EXTRA
59 #else
60  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD_LEN);
61 #endif
62 }
63 
74 static inline uint16_t mavlink_msg_rosflight_aux_cmd_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
75  mavlink_message_t* msg,
76  const uint8_t *type_array,const float *aux_cmd_array)
77 {
78 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
80 
81  _mav_put_float_array(buf, 0, aux_cmd_array, 14);
82  _mav_put_uint8_t_array(buf, 56, type_array, 14);
84 #else
86 
87  mav_array_memcpy(packet.aux_cmd_array, aux_cmd_array, sizeof(float)*14);
88  mav_array_memcpy(packet.type_array, type_array, sizeof(uint8_t)*14);
90 #endif
91 
93 #if MAVLINK_CRC_EXTRA
95 #else
96  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD_LEN);
97 #endif
98 }
99 
108 static inline uint16_t mavlink_msg_rosflight_aux_cmd_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rosflight_aux_cmd_t* rosflight_aux_cmd)
109 {
110  return mavlink_msg_rosflight_aux_cmd_pack(system_id, component_id, msg, rosflight_aux_cmd->type_array, rosflight_aux_cmd->aux_cmd_array);
111 }
112 
122 static inline uint16_t mavlink_msg_rosflight_aux_cmd_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rosflight_aux_cmd_t* rosflight_aux_cmd)
123 {
124  return mavlink_msg_rosflight_aux_cmd_pack_chan(system_id, component_id, chan, msg, rosflight_aux_cmd->type_array, rosflight_aux_cmd->aux_cmd_array);
125 }
126 
134 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
135 
136 static inline void mavlink_msg_rosflight_aux_cmd_send(mavlink_channel_t chan, const uint8_t *type_array, const float *aux_cmd_array)
137 {
138 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
140 
141  _mav_put_float_array(buf, 0, aux_cmd_array, 14);
142  _mav_put_uint8_t_array(buf, 56, type_array, 14);
143 #if MAVLINK_CRC_EXTRA
145 #else
146  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD, buf, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD_LEN);
147 #endif
148 #else
150 
151  mav_array_memcpy(packet.aux_cmd_array, aux_cmd_array, sizeof(float)*14);
152  mav_array_memcpy(packet.type_array, type_array, sizeof(uint8_t)*14);
153 #if MAVLINK_CRC_EXTRA
154  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD_LEN, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD_CRC);
155 #else
156  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD_LEN);
157 #endif
158 #endif
159 }
160 
161 #if MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD_LEN <= MAVLINK_MAX_PAYLOAD_LEN
162 /*
163  This varient of _send() can be used to save stack space by re-using
164  memory from the receive buffer. The caller provides a
165  mavlink_message_t which is the size of a full mavlink message. This
166  is usually the receive buffer for the channel, and allows a reply to an
167  incoming message with minimum stack space usage.
168  */
169 static inline void mavlink_msg_rosflight_aux_cmd_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *type_array, const float *aux_cmd_array)
170 {
171 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
172  char *buf = (char *)msgbuf;
173 
174  _mav_put_float_array(buf, 0, aux_cmd_array, 14);
175  _mav_put_uint8_t_array(buf, 56, type_array, 14);
176 #if MAVLINK_CRC_EXTRA
178 #else
179  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD, buf, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD_LEN);
180 #endif
181 #else
183 
184  mav_array_memcpy(packet->aux_cmd_array, aux_cmd_array, sizeof(float)*14);
185  mav_array_memcpy(packet->type_array, type_array, sizeof(uint8_t)*14);
186 #if MAVLINK_CRC_EXTRA
187  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD_LEN, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD_CRC);
188 #else
189  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD_LEN);
190 #endif
191 #endif
192 }
193 #endif
194 
195 #endif
196 
197 // MESSAGE ROSFLIGHT_AUX_CMD UNPACKING
198 
199 
205 static inline uint16_t mavlink_msg_rosflight_aux_cmd_get_type_array(const mavlink_message_t* msg, uint8_t *type_array)
206 {
207  return _MAV_RETURN_uint8_t_array(msg, type_array, 14, 56);
208 }
209 
215 static inline uint16_t mavlink_msg_rosflight_aux_cmd_get_aux_cmd_array(const mavlink_message_t* msg, float *aux_cmd_array)
216 {
217  return _MAV_RETURN_float_array(msg, aux_cmd_array, 14, 0);
218 }
219 
226 static inline void mavlink_msg_rosflight_aux_cmd_decode(const mavlink_message_t* msg, mavlink_rosflight_aux_cmd_t* rosflight_aux_cmd)
227 {
228 #if MAVLINK_NEED_BYTE_SWAP
231 #else
232  memcpy(rosflight_aux_cmd, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROSFLIGHT_AUX_CMD_LEN);
233 #endif
234 }
static void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
Definition: protocol.h:197
static void mav_array_memcpy(void *dest, const void *src, size_t n)
Definition: protocol.h:176
static uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value, uint8_t array_length, uint8_t wire_offset)
Definition: protocol.h:295


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