mavlink_msg_set_mode.h 5.66 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 8 9
 uint16_t custom_mode; ///< The new autopilot-specific mode. This field can be ignored by an autopilot.
 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 4
#define MAVLINK_MSG_ID_11_LEN 4
lm's avatar
lm committed
14 15 16 17 18



#define MAVLINK_MESSAGE_INFO_SET_MODE { \
	"SET_MODE", \
19 20 21 22
	3, \
	{  { "custom_mode", MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \
         { "target_system", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_set_mode_t, target_system) }, \
         { "base_mode", MAVLINK_TYPE_UINT8_T, 0, 3, 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, uint16_t custom_mode)
James Goppert's avatar
James Goppert committed
40 41 42
{
	msg->msgid = MAVLINK_MSG_ID_SET_MODE;

43 44 45
	put_uint16_t_by_index(msg, 0, custom_mode); // The new autopilot-specific mode. This field can be ignored by an autopilot.
	put_uint8_t_by_index(msg, 2, target_system); // The system setting the mode
	put_uint8_t_by_index(msg, 3, base_mode); // The new base mode
James Goppert's avatar
James Goppert committed
46

47
	return mavlink_finalize_message(msg, system_id, component_id, 4, 197);
James Goppert's avatar
James Goppert committed
48 49 50
}

/**
lm's avatar
lm committed
51
 * @brief Pack a set_mode message on a channel
James Goppert's avatar
James Goppert committed
52 53 54 55
 * @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
56 57 58
 * @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
59 60
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
61 62
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,
63
						           uint8_t target_system,uint8_t base_mode,uint16_t custom_mode)
lm's avatar
lm committed
64 65 66
{
	msg->msgid = MAVLINK_MSG_ID_SET_MODE;

67 68 69
	put_uint16_t_by_index(msg, 0, custom_mode); // The new autopilot-specific mode. This field can be ignored by an autopilot.
	put_uint8_t_by_index(msg, 2, target_system); // The system setting the mode
	put_uint8_t_by_index(msg, 3, base_mode); // The new base mode
lm's avatar
lm committed
70

71
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 197);
lm's avatar
lm committed
72 73
}

James Goppert's avatar
James Goppert committed
74 75 76 77 78 79 80 81 82 83
/**
 * @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)
{
84
	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
85 86 87 88 89 90
}

/**
 * @brief Send a set_mode message
 * @param chan MAVLink channel to send the message
 *
91 92 93
 * @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
94
 */
lm's avatar
lm committed
95 96
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

97
static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint16_t custom_mode)
lm's avatar
lm committed
98
{
99
	MAVLINK_ALIGNED_MESSAGE(msg, 4);
LM's avatar
LM committed
100 101
	msg->msgid = MAVLINK_MSG_ID_SET_MODE;

102 103 104
	put_uint16_t_by_index(msg, 0, custom_mode); // The new autopilot-specific mode. This field can be ignored by an autopilot.
	put_uint8_t_by_index(msg, 2, target_system); // The system setting the mode
	put_uint8_t_by_index(msg, 3, base_mode); // The new base mode
LM's avatar
LM committed
105

106
	mavlink_finalize_message_chan_send(msg, chan, 4, 197);
James Goppert's avatar
James Goppert committed
107 108 109
}

#endif
lm's avatar
lm committed
110

James Goppert's avatar
James Goppert committed
111 112
// MESSAGE SET_MODE UNPACKING

lm's avatar
lm committed
113

James Goppert's avatar
James Goppert committed
114
/**
115
 * @brief Get field target_system from set_mode message
James Goppert's avatar
James Goppert committed
116 117 118
 *
 * @return The system setting the mode
 */
119
static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
120
{
121
	return MAVLINK_MSG_RETURN_uint8_t(msg,  2);
James Goppert's avatar
James Goppert committed
122 123 124
}

/**
125
 * @brief Get field base_mode from set_mode message
James Goppert's avatar
James Goppert committed
126
 *
127
 * @return The new base mode
James Goppert's avatar
James Goppert committed
128
 */
129
static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
130
{
131 132 133 134 135 136 137 138 139 140 141
	return MAVLINK_MSG_RETURN_uint8_t(msg,  3);
}

/**
 * @brief Get field custom_mode from set_mode message
 *
 * @return The new autopilot-specific mode. This field can be ignored by an autopilot.
 */
static inline uint16_t mavlink_msg_set_mode_get_custom_mode(const mavlink_message_t* msg)
{
	return MAVLINK_MSG_RETURN_uint16_t(msg,  0);
James Goppert's avatar
James Goppert committed
142 143 144 145 146 147 148 149 150 151
}

/**
 * @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
152
#if MAVLINK_NEED_BYTE_SWAP
153 154 155
	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
156
#else
157
	memcpy(set_mode, MAVLINK_PAYLOAD(msg), 4);
lm's avatar
lm committed
158
#endif
James Goppert's avatar
James Goppert committed
159
}