mavlink_msg_set_mode.h 4.69 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
{
lm's avatar
lm committed
7 8
 uint8_t target; ///< The system setting the mode
 uint8_t mode; ///< The new mode
James Goppert's avatar
James Goppert committed
9 10
} mavlink_set_mode_t;

lm's avatar
lm committed
11 12 13 14 15 16 17 18 19 20 21 22 23 24
#define MAVLINK_MSG_ID_SET_MODE_LEN 2
#define MAVLINK_MSG_ID_11_LEN 2



#define MAVLINK_MESSAGE_INFO_SET_MODE { \
	"SET_MODE", \
	2, \
	{  { "target", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_mode_t, target) }, \
         { "mode", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_mode_t, mode) }, \
         } \
}


James Goppert's avatar
James Goppert committed
25 26 27 28 29 30 31 32 33 34
/**
 * @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
 *
 * @param target The system setting the mode
 * @param mode The new mode
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
35 36
static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       uint8_t target, uint8_t mode)
James Goppert's avatar
James Goppert committed
37 38 39
{
	msg->msgid = MAVLINK_MSG_ID_SET_MODE;

lm's avatar
lm committed
40 41
	put_uint8_t_by_index(msg, 0, target); // The system setting the mode
	put_uint8_t_by_index(msg, 1, mode); // The new mode
James Goppert's avatar
James Goppert committed
42

lm's avatar
lm committed
43
	return mavlink_finalize_message(msg, system_id, component_id, 2, 186);
James Goppert's avatar
James Goppert committed
44 45 46
}

/**
lm's avatar
lm committed
47
 * @brief Pack a set_mode message on a channel
James Goppert's avatar
James Goppert committed
48 49 50 51 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
 * @param target The system setting the mode
 * @param mode The new mode
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79
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,
						           uint8_t target,uint8_t mode)
{
	msg->msgid = MAVLINK_MSG_ID_SET_MODE;

	put_uint8_t_by_index(msg, 0, target); // The system setting the mode
	put_uint8_t_by_index(msg, 1, mode); // The new mode

	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 186);
}

#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

/**
 * @brief Pack a set_mode message on a channel and send
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
 * @param target The system setting the mode
 * @param mode The new mode
 */
static inline void mavlink_msg_set_mode_pack_chan_send(mavlink_channel_t chan,
							   mavlink_message_t* msg,
						           uint8_t target,uint8_t mode)
James Goppert's avatar
James Goppert committed
80 81 82
{
	msg->msgid = MAVLINK_MSG_ID_SET_MODE;

lm's avatar
lm committed
83 84
	put_uint8_t_by_index(msg, 0, target); // The system setting the mode
	put_uint8_t_by_index(msg, 1, mode); // The new mode
James Goppert's avatar
James Goppert committed
85

lm's avatar
lm committed
86
	mavlink_finalize_message_chan_send(msg, chan, 2, 186);
James Goppert's avatar
James Goppert committed
87
}
lm's avatar
lm committed
88 89
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS

James Goppert's avatar
James Goppert committed
90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110

/**
 * @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)
{
	return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target, set_mode->mode);
}

/**
 * @brief Send a set_mode message
 * @param chan MAVLink channel to send the message
 *
 * @param target The system setting the mode
 * @param mode The new mode
 */
lm's avatar
lm committed
111 112
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

lm's avatar
lm committed
113 114
static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target, uint8_t mode)
{
lm's avatar
lm committed
115 116
	MAVLINK_ALIGNED_MESSAGE(msg, 2);
	mavlink_msg_set_mode_pack_chan_send(chan, msg, target, mode);
James Goppert's avatar
James Goppert committed
117 118 119
}

#endif
lm's avatar
lm committed
120

James Goppert's avatar
James Goppert committed
121 122
// MESSAGE SET_MODE UNPACKING

lm's avatar
lm committed
123

James Goppert's avatar
James Goppert committed
124 125 126 127 128 129 130
/**
 * @brief Get field target from set_mode message
 *
 * @return The system setting the mode
 */
static inline uint8_t mavlink_msg_set_mode_get_target(const mavlink_message_t* msg)
{
lm's avatar
lm committed
131
	return MAVLINK_MSG_RETURN_uint8_t(msg,  0);
James Goppert's avatar
James Goppert committed
132 133 134 135 136 137 138 139 140
}

/**
 * @brief Get field mode from set_mode message
 *
 * @return The new mode
 */
static inline uint8_t mavlink_msg_set_mode_get_mode(const mavlink_message_t* msg)
{
lm's avatar
lm committed
141
	return MAVLINK_MSG_RETURN_uint8_t(msg,  1);
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 153 154 155 156 157
#if MAVLINK_NEED_BYTE_SWAP
	set_mode->target = mavlink_msg_set_mode_get_target(msg);
	set_mode->mode = mavlink_msg_set_mode_get_mode(msg);
#else
	memcpy(set_mode, MAVLINK_PAYLOAD(msg), 2);
#endif
James Goppert's avatar
James Goppert committed
158
}