3 #define MAVLINK_MSG_ID_SET_MODE 11
12 #define MAVLINK_MSG_ID_SET_MODE_LEN 6
13 #define MAVLINK_MSG_ID_11_LEN 6
15 #define MAVLINK_MSG_ID_SET_MODE_CRC 89
16 #define MAVLINK_MSG_ID_11_CRC 89
20 #define MAVLINK_MESSAGE_INFO_SET_MODE { \
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) }, \
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)
44 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
45 char buf[MAVLINK_MSG_ID_SET_MODE_LEN];
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);
50 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MODE_LEN);
57 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MODE_LEN);
60 msg->msgid = MAVLINK_MSG_ID_SET_MODE;
62 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
64 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MODE_LEN);
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)
83 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
84 char buf[MAVLINK_MSG_ID_SET_MODE_LEN];
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);
89 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MODE_LEN);
96 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MODE_LEN);
99 msg->msgid = MAVLINK_MSG_ID_SET_MODE;
100 #if MAVLINK_CRC_EXTRA
101 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
103 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MODE_LEN);
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)
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)
142 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
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)
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);
149 _mav_put_uint8_t(buf, 4, target_system);
150 _mav_put_uint8_t(buf, 5, base_mode);
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);
155 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN);
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);
166 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (
const char *)&packet, MAVLINK_MSG_ID_SET_MODE_LEN);
171 #if MAVLINK_MSG_ID_SET_MODE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
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)
181 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
182 char *buf = (
char *)msgbuf;
183 _mav_put_uint32_t(buf, 0, custom_mode);
184 _mav_put_uint8_t(buf, 4, target_system);
185 _mav_put_uint8_t(buf, 5, base_mode);
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);
190 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN);
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);
201 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (
const char *)packet, MAVLINK_MSG_ID_SET_MODE_LEN);
217 static inline uint8_t mavlink_msg_set_mode_get_target_system(
const mavlink_message_t* msg)
219 return _MAV_RETURN_uint8_t(msg, 4);
227 static inline uint8_t mavlink_msg_set_mode_get_base_mode(
const mavlink_message_t* msg)
229 return _MAV_RETURN_uint8_t(msg, 5);
237 static inline uint32_t mavlink_msg_set_mode_get_custom_mode(
const mavlink_message_t* msg)
239 return _MAV_RETURN_uint32_t(msg, 0);
248 static inline void mavlink_msg_set_mode_decode(
const mavlink_message_t* msg,
mavlink_set_mode_t* set_mode)
250 #if MAVLINK_NEED_BYTE_SWAP
251 set_mode->
custom_mode = mavlink_msg_set_mode_get_custom_mode(msg);
252 set_mode->
target_system = mavlink_msg_set_mode_get_target_system(msg);
253 set_mode->
base_mode = mavlink_msg_set_mode_get_base_mode(msg);
255 memcpy(set_mode, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_MODE_LEN);
uint8_t base_mode
The new base mode.
Definition: mavlink_msg_set_mode.h:9
uint32_t custom_mode
The new autopilot-specific mode. This field can be ignored by an autopilot.
Definition: mavlink_msg_set_mode.h:7
Definition: mavlink_msg_set_mode.h:5
uint8_t target_system
The system setting the mode.
Definition: mavlink_msg_set_mode.h:8