mavlink_msg_set_mode.h
Go to the documentation of this file.
1 // MESSAGE SET_MODE PACKING
2 
3 #define MAVLINK_MSG_ID_SET_MODE 11
4 
5 typedef struct __mavlink_set_mode_t
6 {
7  uint32_t custom_mode; /*< The new autopilot-specific mode. This field can be ignored by an autopilot.*/
8  uint8_t target_system; /*< The system setting the mode*/
9  uint8_t base_mode; /*< The new base mode*/
11 
12 #define MAVLINK_MSG_ID_SET_MODE_LEN 6
13 #define MAVLINK_MSG_ID_11_LEN 6
14 
15 #define MAVLINK_MSG_ID_SET_MODE_CRC 89
16 #define MAVLINK_MSG_ID_11_CRC 89
17 
18 
19 
20 #define MAVLINK_MESSAGE_INFO_SET_MODE { \
21  "SET_MODE", \
22  3, \
23  { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \
24  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \
25  { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \
26  } \
27 }
28 
29 
41 static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42  uint8_t target_system, uint8_t base_mode, uint32_t custom_mode)
43 {
44 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
46  _mav_put_uint32_t(buf, 0, custom_mode);
47  _mav_put_uint8_t(buf, 4, target_system);
48  _mav_put_uint8_t(buf, 5, base_mode);
49 
51 #else
52  mavlink_set_mode_t packet;
53  packet.custom_mode = custom_mode;
55  packet.base_mode = base_mode;
56 
58 #endif
59 
60  msg->msgid = MAVLINK_MSG_ID_SET_MODE;
61 #if MAVLINK_CRC_EXTRA
63 #else
64  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MODE_LEN);
65 #endif
66 }
67 
79 static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
80  mavlink_message_t* msg,
81  uint8_t target_system,uint8_t base_mode,uint32_t custom_mode)
82 {
83 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
85  _mav_put_uint32_t(buf, 0, custom_mode);
86  _mav_put_uint8_t(buf, 4, target_system);
87  _mav_put_uint8_t(buf, 5, base_mode);
88 
90 #else
91  mavlink_set_mode_t packet;
92  packet.custom_mode = custom_mode;
94  packet.base_mode = base_mode;
95 
97 #endif
98 
99  msg->msgid = MAVLINK_MSG_ID_SET_MODE;
100 #if MAVLINK_CRC_EXTRA
102 #else
103  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MODE_LEN);
104 #endif
105 }
106 
115 static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode)
116 {
117  return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode);
118 }
119 
129 static inline uint16_t mavlink_msg_set_mode_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode)
130 {
131  return mavlink_msg_set_mode_pack_chan(system_id, component_id, chan, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode);
132 }
133 
142 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
143 
144 static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode)
145 {
146 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
147  char buf[MAVLINK_MSG_ID_SET_MODE_LEN];
148  _mav_put_uint32_t(buf, 0, custom_mode);
150  _mav_put_uint8_t(buf, 5, base_mode);
151 
152 #if MAVLINK_CRC_EXTRA
153  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
154 #else
155  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN);
156 #endif
157 #else
158  mavlink_set_mode_t packet;
159  packet.custom_mode = custom_mode;
160  packet.target_system = target_system;
161  packet.base_mode = base_mode;
162 
163 #if MAVLINK_CRC_EXTRA
164  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
165 #else
166  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, MAVLINK_MSG_ID_SET_MODE_LEN);
167 #endif
168 #endif
169 }
170 
171 #if MAVLINK_MSG_ID_SET_MODE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
172 /*
173  This varient of _send() can be used to save stack space by re-using
174  memory from the receive buffer. The caller provides a
175  mavlink_message_t which is the size of a full mavlink message. This
176  is usually the receive buffer for the channel, and allows a reply to an
177  incoming message with minimum stack space usage.
178  */
179 static inline void mavlink_msg_set_mode_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode)
180 {
181 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
182  char *buf = (char *)msgbuf;
183  _mav_put_uint32_t(buf, 0, custom_mode);
185  _mav_put_uint8_t(buf, 5, base_mode);
186 
187 #if MAVLINK_CRC_EXTRA
188  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
189 #else
190  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN);
191 #endif
192 #else
193  mavlink_set_mode_t *packet = (mavlink_set_mode_t *)msgbuf;
194  packet->custom_mode = custom_mode;
195  packet->target_system = target_system;
196  packet->base_mode = base_mode;
197 
198 #if MAVLINK_CRC_EXTRA
199  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)packet, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
200 #else
201  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)packet, MAVLINK_MSG_ID_SET_MODE_LEN);
202 #endif
203 #endif
204 }
205 #endif
206 
207 #endif
208 
209 // MESSAGE SET_MODE UNPACKING
210 
211 
217 static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_message_t* msg)
218 {
219  return _MAV_RETURN_uint8_t(msg, 4);
220 }
221 
227 static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t* msg)
228 {
229  return _MAV_RETURN_uint8_t(msg, 5);
230 }
231 
237 static inline uint32_t mavlink_msg_set_mode_get_custom_mode(const mavlink_message_t* msg)
238 {
239  return _MAV_RETURN_uint32_t(msg, 0);
240 }
241 
248 static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode)
249 {
250 #if MAVLINK_NEED_BYTE_SWAP
254 #else
255  memcpy(set_mode, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_MODE_LEN);
256 #endif
257 }
#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_uint32_t(buf, wire_offset, b)
Definition: protocol.h:147


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