mavlink_msg_param_request_list.h 6.71 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3 4
// MESSAGE PARAM_REQUEST_LIST PACKING

#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21

lm's avatar
lm committed
5
typedef struct __mavlink_param_request_list_t
James Goppert's avatar
James Goppert committed
6
{
lm's avatar
lm committed
7 8
 uint8_t target_system; ///< System ID
 uint8_t target_component; ///< Component ID
James Goppert's avatar
James Goppert committed
9 10
} mavlink_param_request_list_t;

lm's avatar
lm committed
11 12 13
#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2
#define MAVLINK_MSG_ID_21_LEN 2

Lorenz Meier's avatar
Lorenz Meier committed
14 15 16
#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC 159
#define MAVLINK_MSG_ID_21_CRC 159

lm's avatar
lm committed
17 18 19 20 21


#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \
	"PARAM_REQUEST_LIST", \
	2, \
lm's avatar
lm committed
22 23
	{  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \
         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \
lm's avatar
lm committed
24 25 26 27
         } \
}


James Goppert's avatar
James Goppert committed
28 29 30 31 32 33 34 35 36 37
/**
 * @brief Pack a param_request_list 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
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
38 39
static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       uint8_t target_system, uint8_t target_component)
James Goppert's avatar
James Goppert committed
40
{
LM's avatar
LM committed
41
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
42
	char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN];
LM's avatar
LM committed
43 44 45
	_mav_put_uint8_t(buf, 0, target_system);
	_mav_put_uint8_t(buf, 1, target_component);

Lorenz Meier's avatar
Lorenz Meier committed
46
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
LM's avatar
LM committed
47 48 49 50
#else
	mavlink_param_request_list_t packet;
	packet.target_system = target_system;
	packet.target_component = target_component;
James Goppert's avatar
James Goppert committed
51

Lorenz Meier's avatar
Lorenz Meier committed
52
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
LM's avatar
LM committed
53
#endif
James Goppert's avatar
James Goppert committed
54

LM's avatar
LM committed
55
	msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST;
Lorenz Meier's avatar
Lorenz Meier committed
56 57 58 59 60
#if MAVLINK_CRC_EXTRA
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC);
#else
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
#endif
James Goppert's avatar
James Goppert committed
61 62 63
}

/**
lm's avatar
lm committed
64
 * @brief Pack a param_request_list message on a channel
James Goppert's avatar
James Goppert committed
65 66 67 68 69 70 71 72
 * @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
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
73 74 75 76
static inline uint16_t mavlink_msg_param_request_list_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)
{
LM's avatar
LM committed
77
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
78
	char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN];
LM's avatar
LM committed
79 80
	_mav_put_uint8_t(buf, 0, target_system);
	_mav_put_uint8_t(buf, 1, target_component);
lm's avatar
lm committed
81

Lorenz Meier's avatar
Lorenz Meier committed
82
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
LM's avatar
LM committed
83 84 85 86
#else
	mavlink_param_request_list_t packet;
	packet.target_system = target_system;
	packet.target_component = target_component;
lm's avatar
lm committed
87

Lorenz Meier's avatar
Lorenz Meier committed
88
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
LM's avatar
LM committed
89 90 91
#endif

	msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST;
Lorenz Meier's avatar
Lorenz Meier committed
92 93 94 95 96
#if MAVLINK_CRC_EXTRA
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC);
#else
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
#endif
lm's avatar
lm committed
97 98
}

James Goppert's avatar
James Goppert committed
99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118
/**
 * @brief Encode a param_request_list 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 param_request_list C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list)
{
	return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component);
}

/**
 * @brief Send a param_request_list message
 * @param chan MAVLink channel to send the message
 *
 * @param target_system System ID
 * @param target_component Component ID
 */
lm's avatar
lm committed
119 120
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

lm's avatar
lm committed
121 122
static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
LM's avatar
LM committed
123
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
124
	char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN];
LM's avatar
LM committed
125 126
	_mav_put_uint8_t(buf, 0, target_system);
	_mav_put_uint8_t(buf, 1, target_component);
LM's avatar
LM committed
127

Lorenz Meier's avatar
Lorenz Meier committed
128 129 130 131 132
#if MAVLINK_CRC_EXTRA
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
#endif
LM's avatar
LM committed
133 134 135 136
#else
	mavlink_param_request_list_t packet;
	packet.target_system = target_system;
	packet.target_component = target_component;
LM's avatar
LM committed
137

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_PARAM_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
#endif
LM's avatar
LM committed
143
#endif
James Goppert's avatar
James Goppert committed
144 145 146
}

#endif
lm's avatar
lm committed
147

James Goppert's avatar
James Goppert committed
148 149
// MESSAGE PARAM_REQUEST_LIST UNPACKING

lm's avatar
lm committed
150

James Goppert's avatar
James Goppert committed
151 152 153 154 155 156 157
/**
 * @brief Get field target_system from param_request_list message
 *
 * @return System ID
 */
static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mavlink_message_t* msg)
{
LM's avatar
LM committed
158
	return _MAV_RETURN_uint8_t(msg,  0);
James Goppert's avatar
James Goppert committed
159 160 161 162 163 164 165 166 167
}

/**
 * @brief Get field target_component from param_request_list message
 *
 * @return Component ID
 */
static inline uint8_t mavlink_msg_param_request_list_get_target_component(const mavlink_message_t* msg)
{
LM's avatar
LM committed
168
	return _MAV_RETURN_uint8_t(msg,  1);
James Goppert's avatar
James Goppert committed
169 170 171 172 173 174 175 176 177 178
}

/**
 * @brief Decode a param_request_list message into a struct
 *
 * @param msg The message to decode
 * @param param_request_list C-struct to decode the message contents into
 */
static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t* msg, mavlink_param_request_list_t* param_request_list)
{
lm's avatar
lm committed
179 180 181 182
#if MAVLINK_NEED_BYTE_SWAP
	param_request_list->target_system = mavlink_msg_param_request_list_get_target_system(msg);
	param_request_list->target_component = mavlink_msg_param_request_list_get_target_component(msg);
#else
Lorenz Meier's avatar
Lorenz Meier committed
183
	memcpy(param_request_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
lm's avatar
lm committed
184
#endif
James Goppert's avatar
James Goppert committed
185
}