mavlink_msg_flexifunction_command.h 7.91 KB
Newer Older
Lorenz Meier's avatar
Lorenz Meier committed
1 2 3 4 5 6 7 8 9 10 11 12 13 14
// MESSAGE FLEXIFUNCTION_COMMAND PACKING

#define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND 157

typedef struct __mavlink_flexifunction_command_t
{
 uint8_t target_system; ///< System ID
 uint8_t target_component; ///< Component ID
 uint8_t command_type; ///< Flexifunction command type
} mavlink_flexifunction_command_t;

#define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN 3
#define MAVLINK_MSG_ID_157_LEN 3

Lorenz Meier's avatar
Lorenz Meier committed
15 16 17
#define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC 133
#define MAVLINK_MSG_ID_157_CRC 133

Lorenz Meier's avatar
Lorenz Meier committed
18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44


#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_COMMAND { \
	"FLEXIFUNCTION_COMMAND", \
	3, \
	{  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_flexifunction_command_t, target_system) }, \
         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_flexifunction_command_t, target_component) }, \
         { "command_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_flexifunction_command_t, command_type) }, \
         } \
}


/**
 * @brief Pack a flexifunction_command 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_system System ID
 * @param target_component Component ID
 * @param command_type Flexifunction command type
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_flexifunction_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       uint8_t target_system, uint8_t target_component, uint8_t command_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
45
	char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN];
Lorenz Meier's avatar
Lorenz Meier committed
46 47 48 49
	_mav_put_uint8_t(buf, 0, target_system);
	_mav_put_uint8_t(buf, 1, target_component);
	_mav_put_uint8_t(buf, 2, command_type);

Lorenz Meier's avatar
Lorenz Meier committed
50
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN);
Lorenz Meier's avatar
Lorenz Meier committed
51 52 53 54 55 56
#else
	mavlink_flexifunction_command_t packet;
	packet.target_system = target_system;
	packet.target_component = target_component;
	packet.command_type = command_type;

Lorenz Meier's avatar
Lorenz Meier committed
57
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN);
Lorenz Meier's avatar
Lorenz Meier committed
58 59 60
#endif

	msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND;
Lorenz Meier's avatar
Lorenz Meier committed
61 62 63 64 65
#if MAVLINK_CRC_EXTRA
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC);
#else
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN);
#endif
Lorenz Meier's avatar
Lorenz Meier committed
66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83
}

/**
 * @brief Pack a flexifunction_command message on a channel
 * @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_system System ID
 * @param target_component Component ID
 * @param command_type Flexifunction command type
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_flexifunction_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
						           uint8_t target_system,uint8_t target_component,uint8_t command_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
84
	char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN];
Lorenz Meier's avatar
Lorenz Meier committed
85 86 87 88
	_mav_put_uint8_t(buf, 0, target_system);
	_mav_put_uint8_t(buf, 1, target_component);
	_mav_put_uint8_t(buf, 2, command_type);

Lorenz Meier's avatar
Lorenz Meier committed
89
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN);
Lorenz Meier's avatar
Lorenz Meier committed
90 91 92 93 94 95
#else
	mavlink_flexifunction_command_t packet;
	packet.target_system = target_system;
	packet.target_component = target_component;
	packet.command_type = command_type;

Lorenz Meier's avatar
Lorenz Meier committed
96
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN);
Lorenz Meier's avatar
Lorenz Meier committed
97 98 99
#endif

	msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND;
Lorenz Meier's avatar
Lorenz Meier committed
100 101 102 103 104
#if MAVLINK_CRC_EXTRA
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC);
#else
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN);
#endif
Lorenz Meier's avatar
Lorenz Meier committed
105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132
}

/**
 * @brief Encode a flexifunction_command 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 flexifunction_command C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_flexifunction_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_command_t* flexifunction_command)
{
	return mavlink_msg_flexifunction_command_pack(system_id, component_id, msg, flexifunction_command->target_system, flexifunction_command->target_component, flexifunction_command->command_type);
}

/**
 * @brief Send a flexifunction_command message
 * @param chan MAVLink channel to send the message
 *
 * @param target_system System ID
 * @param target_component Component ID
 * @param command_type Flexifunction command type
 */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

static inline void mavlink_msg_flexifunction_command_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
133
	char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN];
Lorenz Meier's avatar
Lorenz Meier committed
134 135 136 137
	_mav_put_uint8_t(buf, 0, target_system);
	_mav_put_uint8_t(buf, 1, target_component);
	_mav_put_uint8_t(buf, 2, command_type);

Lorenz Meier's avatar
Lorenz Meier committed
138 139 140 141 142
#if MAVLINK_CRC_EXTRA
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN);
#endif
Lorenz Meier's avatar
Lorenz Meier committed
143 144 145 146 147 148
#else
	mavlink_flexifunction_command_t packet;
	packet.target_system = target_system;
	packet.target_component = target_component;
	packet.command_type = command_type;

Lorenz Meier's avatar
Lorenz Meier committed
149 150 151 152 153
#if MAVLINK_CRC_EXTRA
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN);
#endif
Lorenz Meier's avatar
Lorenz Meier committed
154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204
#endif
}

#endif

// MESSAGE FLEXIFUNCTION_COMMAND UNPACKING


/**
 * @brief Get field target_system from flexifunction_command message
 *
 * @return System ID
 */
static inline uint8_t mavlink_msg_flexifunction_command_get_target_system(const mavlink_message_t* msg)
{
	return _MAV_RETURN_uint8_t(msg,  0);
}

/**
 * @brief Get field target_component from flexifunction_command message
 *
 * @return Component ID
 */
static inline uint8_t mavlink_msg_flexifunction_command_get_target_component(const mavlink_message_t* msg)
{
	return _MAV_RETURN_uint8_t(msg,  1);
}

/**
 * @brief Get field command_type from flexifunction_command message
 *
 * @return Flexifunction command type
 */
static inline uint8_t mavlink_msg_flexifunction_command_get_command_type(const mavlink_message_t* msg)
{
	return _MAV_RETURN_uint8_t(msg,  2);
}

/**
 * @brief Decode a flexifunction_command message into a struct
 *
 * @param msg The message to decode
 * @param flexifunction_command C-struct to decode the message contents into
 */
static inline void mavlink_msg_flexifunction_command_decode(const mavlink_message_t* msg, mavlink_flexifunction_command_t* flexifunction_command)
{
#if MAVLINK_NEED_BYTE_SWAP
	flexifunction_command->target_system = mavlink_msg_flexifunction_command_get_target_system(msg);
	flexifunction_command->target_component = mavlink_msg_flexifunction_command_get_target_component(msg);
	flexifunction_command->command_type = mavlink_msg_flexifunction_command_get_command_type(msg);
#else
Lorenz Meier's avatar
Lorenz Meier committed
205
	memcpy(flexifunction_command, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN);
Lorenz Meier's avatar
Lorenz Meier committed
206 207
#endif
}