mavlink_msg_set_mode.h 6.11 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3 4
// MESSAGE SET_MODE PACKING

#define MAVLINK_MSG_ID_SET_MODE 11

lm's avatar
lm committed
5
typedef struct __mavlink_set_mode_t
James Goppert's avatar
James Goppert committed
6
{
7
 uint32_t custom_mode; ///< The new autopilot-specific mode. This field can be ignored by an autopilot.
8 9
 uint8_t target_system; ///< The system setting the mode
 uint8_t base_mode; ///< The new base mode
James Goppert's avatar
James Goppert committed
10 11
} mavlink_set_mode_t;

12 13
#define MAVLINK_MSG_ID_SET_MODE_LEN 6
#define MAVLINK_MSG_ID_11_LEN 6
lm's avatar
lm committed
14 15 16 17 18



#define MAVLINK_MESSAGE_INFO_SET_MODE { \
	"SET_MODE", \
19
	3, \
20 21 22
	{  { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \
         { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \
         { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \
lm's avatar
lm committed
23 24 25 26
         } \
}


James Goppert's avatar
James Goppert committed
27 28 29 30 31 32
/**
 * @brief Pack a set_mode message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 *
33 34 35
 * @param target_system The system setting the mode
 * @param base_mode The new base mode
 * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot.
James Goppert's avatar
James Goppert committed
36 37
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
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)
James Goppert's avatar
James Goppert committed
40
{
LM's avatar
LM committed
41
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
42 43 44 45
	char buf[6];
	_mav_put_uint32_t(buf, 0, custom_mode);
	_mav_put_uint8_t(buf, 4, target_system);
	_mav_put_uint8_t(buf, 5, base_mode);
LM's avatar
LM committed
46

47
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
LM's avatar
LM committed
48 49 50 51 52
#else
	mavlink_set_mode_t packet;
	packet.custom_mode = custom_mode;
	packet.target_system = target_system;
	packet.base_mode = base_mode;
James Goppert's avatar
James Goppert committed
53

54
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
LM's avatar
LM committed
55
#endif
James Goppert's avatar
James Goppert committed
56

LM's avatar
LM committed
57
	msg->msgid = MAVLINK_MSG_ID_SET_MODE;
58
	return mavlink_finalize_message(msg, system_id, component_id, 6, 89);
James Goppert's avatar
James Goppert committed
59 60 61
}

/**
lm's avatar
lm committed
62
 * @brief Pack a set_mode message on a channel
James Goppert's avatar
James Goppert committed
63 64 65 66
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
67 68 69
 * @param target_system The system setting the mode
 * @param base_mode The new base mode
 * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot.
James Goppert's avatar
James Goppert committed
70 71
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
72 73
static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
74
						           uint8_t target_system,uint8_t base_mode,uint32_t custom_mode)
lm's avatar
lm committed
75
{
LM's avatar
LM committed
76
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
77 78 79 80
	char buf[6];
	_mav_put_uint32_t(buf, 0, custom_mode);
	_mav_put_uint8_t(buf, 4, target_system);
	_mav_put_uint8_t(buf, 5, base_mode);
lm's avatar
lm committed
81

82
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
LM's avatar
LM committed
83 84 85 86 87
#else
	mavlink_set_mode_t packet;
	packet.custom_mode = custom_mode;
	packet.target_system = target_system;
	packet.base_mode = base_mode;
lm's avatar
lm committed
88

89
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
LM's avatar
LM committed
90 91 92
#endif

	msg->msgid = MAVLINK_MSG_ID_SET_MODE;
93
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 89);
lm's avatar
lm committed
94 95
}

James Goppert's avatar
James Goppert committed
96 97 98 99 100 101 102 103 104 105
/**
 * @brief Encode a set_mode struct into a message
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 * @param set_mode C-struct to read the message contents from
 */
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);
James Goppert's avatar
James Goppert committed
107 108 109 110 111 112
}

/**
 * @brief Send a set_mode message
 * @param chan MAVLink channel to send the message
 *
113 114 115
 * @param target_system The system setting the mode
 * @param base_mode The new base mode
 * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot.
James Goppert's avatar
James Goppert committed
116
 */
lm's avatar
lm committed
117 118
#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)
lm's avatar
lm committed
120
{
LM's avatar
LM committed
121
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
122 123 124 125
	char buf[6];
	_mav_put_uint32_t(buf, 0, custom_mode);
	_mav_put_uint8_t(buf, 4, target_system);
	_mav_put_uint8_t(buf, 5, base_mode);
LM's avatar
LM committed
126

127
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, 6, 89);
LM's avatar
LM committed
128 129 130 131 132
#else
	mavlink_set_mode_t packet;
	packet.custom_mode = custom_mode;
	packet.target_system = target_system;
	packet.base_mode = base_mode;
LM's avatar
LM committed
133

134
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, 6, 89);
LM's avatar
LM committed
135
#endif
James Goppert's avatar
James Goppert committed
136 137 138
}

#endif
lm's avatar
lm committed
139

James Goppert's avatar
James Goppert committed
140 141
// MESSAGE SET_MODE UNPACKING

lm's avatar
lm committed
142

James Goppert's avatar
James Goppert committed
143
/**
144
 * @brief Get field target_system from set_mode message
James Goppert's avatar
James Goppert committed
145 146 147
 *
 * @return The system setting the mode
 */
148
static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
149
{
150
	return _MAV_RETURN_uint8_t(msg,  4);
James Goppert's avatar
James Goppert committed
151 152 153
}

/**
154
 * @brief Get field base_mode from set_mode message
James Goppert's avatar
James Goppert committed
155
 *
156
 * @return The new base mode
James Goppert's avatar
James Goppert committed
157
 */
158
static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
159
{
160
	return _MAV_RETURN_uint8_t(msg,  5);
161 162 163 164 165 166 167
}

/**
 * @brief Get field custom_mode from set_mode message
 *
 * @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)
169
{
170
	return _MAV_RETURN_uint32_t(msg,  0);
James Goppert's avatar
James Goppert committed
171 172 173 174 175 176 177 178 179 180
}

/**
 * @brief Decode a set_mode message into a struct
 *
 * @param msg The message to decode
 * @param set_mode C-struct to decode the message contents into
 */
static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode)
{
lm's avatar
lm committed
181
#if MAVLINK_NEED_BYTE_SWAP
182 183 184
	set_mode->custom_mode = mavlink_msg_set_mode_get_custom_mode(msg);
	set_mode->target_system = mavlink_msg_set_mode_get_target_system(msg);
	set_mode->base_mode = mavlink_msg_set_mode_get_base_mode(msg);
lm's avatar
lm committed
185
#else
186
	memcpy(set_mode, _MAV_PAYLOAD(msg), 6);
lm's avatar
lm committed
187
#endif
James Goppert's avatar
James Goppert committed
188
}