1 // MESSAGE SET_MODE PACKING
3 #define MAVLINK_MSG_ID_SET_MODE 11
5 typedef struct __mavlink_set_mode_t
{
6 uint32_t custom_mode
; ///< The new autopilot-specific mode. This field can be ignored by an autopilot.
7 uint8_t target_system
; ///< The system setting the mode
8 uint8_t base_mode
; ///< The new base mode
11 #define MAVLINK_MSG_ID_SET_MODE_LEN 6
12 #define MAVLINK_MSG_ID_11_LEN 6
15 #define MAVLINK_MESSAGE_INFO_SET_MODE \
20 { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \
21 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \
22 { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \
28 * @brief Pack a set_mode message
29 * @param system_id ID of this system
30 * @param component_id ID of this component (e.g. 200 for IMU)
31 * @param msg The MAVLink message to compress the data into
33 * @param target_system The system setting the mode
34 * @param base_mode The new base mode
35 * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot.
36 * @return length of the message in bytes (excluding serial stream start sign)
38 static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*msg
,
39 uint8_t target_system
, uint8_t base_mode
, uint32_t custom_mode
)
41 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
43 _mav_put_uint32_t(buf
, 0, custom_mode
);
44 _mav_put_uint8_t(buf
, 4, target_system
);
45 _mav_put_uint8_t(buf
, 5, base_mode
);
47 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 6);
49 mavlink_set_mode_t packet
;
50 packet
.custom_mode
= custom_mode
;
51 packet
.target_system
= target_system
;
52 packet
.base_mode
= base_mode
;
54 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 6);
57 msg
->msgid
= MAVLINK_MSG_ID_SET_MODE
;
58 return mavlink_finalize_message(msg
, system_id
, component_id
, 6, 89);
62 * @brief Pack a set_mode message on a channel
63 * @param system_id ID of this system
64 * @param component_id ID of this component (e.g. 200 for IMU)
65 * @param chan The MAVLink channel this message was sent over
66 * @param msg The MAVLink message to compress the data into
67 * @param target_system The system setting the mode
68 * @param base_mode The new base mode
69 * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot.
70 * @return length of the message in bytes (excluding serial stream start sign)
72 static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
73 mavlink_message_t
*msg
,
74 uint8_t target_system
, uint8_t base_mode
, uint32_t custom_mode
)
76 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
78 _mav_put_uint32_t(buf
, 0, custom_mode
);
79 _mav_put_uint8_t(buf
, 4, target_system
);
80 _mav_put_uint8_t(buf
, 5, base_mode
);
82 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 6);
84 mavlink_set_mode_t packet
;
85 packet
.custom_mode
= custom_mode
;
86 packet
.target_system
= target_system
;
87 packet
.base_mode
= base_mode
;
89 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 6);
92 msg
->msgid
= MAVLINK_MSG_ID_SET_MODE
;
93 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, 6, 89);
97 * @brief Encode a set_mode struct into a message
99 * @param system_id ID of this system
100 * @param component_id ID of this component (e.g. 200 for IMU)
101 * @param msg The MAVLink message to compress the data into
102 * @param set_mode C-struct to read the message contents from
104 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
)
106 return mavlink_msg_set_mode_pack(system_id
, component_id
, msg
, set_mode
->target_system
, set_mode
->base_mode
, set_mode
->custom_mode
);
110 * @brief Send a set_mode message
111 * @param chan MAVLink channel to send the message
113 * @param target_system The system setting the mode
114 * @param base_mode The new base mode
115 * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot.
117 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
119 static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan
, uint8_t target_system
, uint8_t base_mode
, uint32_t custom_mode
)
121 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
123 _mav_put_uint32_t(buf
, 0, custom_mode
);
124 _mav_put_uint8_t(buf
, 4, target_system
);
125 _mav_put_uint8_t(buf
, 5, base_mode
);
127 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SET_MODE
, buf
, 6, 89);
129 mavlink_set_mode_t packet
;
130 packet
.custom_mode
= custom_mode
;
131 packet
.target_system
= target_system
;
132 packet
.base_mode
= base_mode
;
134 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SET_MODE
, (const char *)&packet
, 6, 89);
138 #endif // ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
140 // MESSAGE SET_MODE UNPACKING
144 * @brief Get field target_system from set_mode message
146 * @return The system setting the mode
148 static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_message_t
*msg
)
150 return _MAV_RETURN_uint8_t(msg
, 4);
154 * @brief Get field base_mode from set_mode message
156 * @return The new base mode
158 static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t
*msg
)
160 return _MAV_RETURN_uint8_t(msg
, 5);
164 * @brief Get field custom_mode from set_mode message
166 * @return The new autopilot-specific mode. This field can be ignored by an autopilot.
168 static inline uint32_t mavlink_msg_set_mode_get_custom_mode(const mavlink_message_t
*msg
)
170 return _MAV_RETURN_uint32_t(msg
, 0);
174 * @brief Decode a set_mode message into a struct
176 * @param msg The message to decode
177 * @param set_mode C-struct to decode the message contents into
179 static inline void mavlink_msg_set_mode_decode(const mavlink_message_t
*msg
, mavlink_set_mode_t
*set_mode
)
181 #if MAVLINK_NEED_BYTE_SWAP
182 set_mode
->custom_mode
= mavlink_msg_set_mode_get_custom_mode(msg
);
183 set_mode
->target_system
= mavlink_msg_set_mode_get_target_system(msg
);
184 set_mode
->base_mode
= mavlink_msg_set_mode_get_base_mode(msg
);
186 memcpy(set_mode
, _MAV_PAYLOAD(msg
), 6);