mavlink_msg_param_set.h 12.7 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3 4
// MESSAGE PARAM_SET PACKING

#define MAVLINK_MSG_ID_PARAM_SET 23

lm's avatar
lm committed
5
typedef struct __mavlink_param_set_t
James Goppert's avatar
James Goppert committed
6
{
lm's avatar
lm committed
7 8 9
 float param_value; ///< Onboard parameter value
 uint8_t target_system; ///< System ID
 uint8_t target_component; ///< Component ID
Lorenz Meier's avatar
Lorenz Meier committed
10 11
 char param_id[16]; ///< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
 uint8_t param_type; ///< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
James Goppert's avatar
James Goppert committed
12
} mavlink_param_set_t;
lm's avatar
lm committed
13 14 15 16

#define MAVLINK_MSG_ID_PARAM_SET_LEN 23
#define MAVLINK_MSG_ID_23_LEN 23

Lorenz Meier's avatar
Lorenz Meier committed
17 18 19
#define MAVLINK_MSG_ID_PARAM_SET_CRC 168
#define MAVLINK_MSG_ID_23_CRC 168

20
#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 16
James Goppert's avatar
James Goppert committed
21

lm's avatar
lm committed
22 23 24
#define MAVLINK_MESSAGE_INFO_PARAM_SET { \
	"PARAM_SET", \
	5, \
lm's avatar
lm committed
25 26 27 28 29
	{  { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \
         { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \
         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \
         { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \
         { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \
lm's avatar
lm committed
30 31 32 33
         } \
}


James Goppert's avatar
James Goppert committed
34 35 36 37 38 39 40 41
/**
 * @brief Pack a param_set 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
Lorenz Meier's avatar
Lorenz Meier committed
42
 * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
James Goppert's avatar
James Goppert committed
43
 * @param param_value Onboard parameter value
Lorenz Meier's avatar
Lorenz Meier committed
44
 * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
James Goppert's avatar
James Goppert committed
45 46
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
47 48
static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type)
James Goppert's avatar
James Goppert committed
49
{
LM's avatar
LM committed
50
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
51
	char buf[MAVLINK_MSG_ID_PARAM_SET_LEN];
LM's avatar
LM committed
52 53 54 55 56
	_mav_put_float(buf, 0, param_value);
	_mav_put_uint8_t(buf, 4, target_system);
	_mav_put_uint8_t(buf, 5, target_component);
	_mav_put_uint8_t(buf, 22, param_type);
	_mav_put_char_array(buf, 6, param_id, 16);
Lorenz Meier's avatar
Lorenz Meier committed
57
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_SET_LEN);
LM's avatar
LM committed
58 59 60 61 62 63
#else
	mavlink_param_set_t packet;
	packet.param_value = param_value;
	packet.target_system = target_system;
	packet.target_component = target_component;
	packet.param_type = param_type;
64
	mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
Lorenz Meier's avatar
Lorenz Meier committed
65
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_SET_LEN);
LM's avatar
LM committed
66
#endif
James Goppert's avatar
James Goppert committed
67

LM's avatar
LM committed
68
	msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
Lorenz Meier's avatar
Lorenz Meier committed
69 70 71 72 73
#if MAVLINK_CRC_EXTRA
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
#else
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN);
#endif
James Goppert's avatar
James Goppert committed
74 75 76
}

/**
lm's avatar
lm committed
77
 * @brief Pack a param_set message on a channel
James Goppert's avatar
James Goppert committed
78 79
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
Lorenz Meier's avatar
Lorenz Meier committed
80
 * @param chan The MAVLink channel this message will be sent over
James Goppert's avatar
James Goppert committed
81 82 83
 * @param msg The MAVLink message to compress the data into
 * @param target_system System ID
 * @param target_component Component ID
Lorenz Meier's avatar
Lorenz Meier committed
84
 * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
James Goppert's avatar
James Goppert committed
85
 * @param param_value Onboard parameter value
Lorenz Meier's avatar
Lorenz Meier committed
86
 * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
James Goppert's avatar
James Goppert committed
87 88
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
89 90 91
static inline uint16_t mavlink_msg_param_set_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,const char *param_id,float param_value,uint8_t param_type)
James Goppert's avatar
James Goppert committed
92
{
LM's avatar
LM committed
93
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
94
	char buf[MAVLINK_MSG_ID_PARAM_SET_LEN];
LM's avatar
LM committed
95 96 97 98 99
	_mav_put_float(buf, 0, param_value);
	_mav_put_uint8_t(buf, 4, target_system);
	_mav_put_uint8_t(buf, 5, target_component);
	_mav_put_uint8_t(buf, 22, param_type);
	_mav_put_char_array(buf, 6, param_id, 16);
Lorenz Meier's avatar
Lorenz Meier committed
100
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_SET_LEN);
LM's avatar
LM committed
101 102 103 104 105 106
#else
	mavlink_param_set_t packet;
	packet.param_value = param_value;
	packet.target_system = target_system;
	packet.target_component = target_component;
	packet.param_type = param_type;
107
	mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
Lorenz Meier's avatar
Lorenz Meier committed
108
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_SET_LEN);
LM's avatar
LM committed
109
#endif
James Goppert's avatar
James Goppert committed
110

LM's avatar
LM committed
111
	msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
Lorenz Meier's avatar
Lorenz Meier committed
112 113 114 115 116
#if MAVLINK_CRC_EXTRA
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
#else
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN);
#endif
James Goppert's avatar
James Goppert committed
117 118 119
}

/**
Lorenz Meier's avatar
Lorenz Meier committed
120
 * @brief Encode a param_set struct
James Goppert's avatar
James Goppert committed
121 122 123 124 125 126 127 128
 *
 * @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_set C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set)
{
129
	return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type);
James Goppert's avatar
James Goppert committed
130 131
}

Lorenz Meier's avatar
Lorenz Meier committed
132 133 134 135 136 137 138 139 140 141 142 143 144 145
/**
 * @brief Encode a param_set struct 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 will be sent over
 * @param msg The MAVLink message to compress the data into
 * @param param_set C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_param_set_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_set_t* param_set)
{
	return mavlink_msg_param_set_pack_chan(system_id, component_id, chan, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type);
}

James Goppert's avatar
James Goppert committed
146 147 148 149 150 151
/**
 * @brief Send a param_set message
 * @param chan MAVLink channel to send the message
 *
 * @param target_system System ID
 * @param target_component Component ID
Lorenz Meier's avatar
Lorenz Meier committed
152
 * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
James Goppert's avatar
James Goppert committed
153
 * @param param_value Onboard parameter value
Lorenz Meier's avatar
Lorenz Meier committed
154
 * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
James Goppert's avatar
James Goppert committed
155
 */
lm's avatar
lm committed
156 157 158
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type)
lm's avatar
lm committed
159
{
LM's avatar
LM committed
160
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
161
	char buf[MAVLINK_MSG_ID_PARAM_SET_LEN];
LM's avatar
LM committed
162 163 164 165 166
	_mav_put_float(buf, 0, param_value);
	_mav_put_uint8_t(buf, 4, target_system);
	_mav_put_uint8_t(buf, 5, target_component);
	_mav_put_uint8_t(buf, 22, param_type);
	_mav_put_char_array(buf, 6, param_id, 16);
Lorenz Meier's avatar
Lorenz Meier committed
167 168 169 170 171
#if MAVLINK_CRC_EXTRA
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN);
#endif
LM's avatar
LM committed
172 173 174 175 176 177
#else
	mavlink_param_set_t packet;
	packet.param_value = param_value;
	packet.target_system = target_system;
	packet.target_component = target_component;
	packet.param_type = param_type;
178
	mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
Lorenz Meier's avatar
Lorenz Meier committed
179 180 181 182 183
#if MAVLINK_CRC_EXTRA
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_SET_LEN);
#endif
LM's avatar
LM committed
184
#endif
James Goppert's avatar
James Goppert committed
185 186
}

187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224
#if MAVLINK_MSG_ID_PARAM_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
  This varient of _send() can be used to save stack space by re-using
  memory from the receive buffer.  The caller provides a
  mavlink_message_t which is the size of a full mavlink message. This
  is usually the receive buffer for the channel, and allows a reply to an
  incoming message with minimum stack space usage.
 */
static inline void mavlink_msg_param_set_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char *buf = (char *)msgbuf;
	_mav_put_float(buf, 0, param_value);
	_mav_put_uint8_t(buf, 4, target_system);
	_mav_put_uint8_t(buf, 5, target_component);
	_mav_put_uint8_t(buf, 22, param_type);
	_mav_put_char_array(buf, 6, param_id, 16);
#if MAVLINK_CRC_EXTRA
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN);
#endif
#else
	mavlink_param_set_t *packet = (mavlink_param_set_t *)msgbuf;
	packet->param_value = param_value;
	packet->target_system = target_system;
	packet->target_component = target_component;
	packet->param_type = param_type;
	mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16);
#if MAVLINK_CRC_EXTRA
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_SET_LEN);
#endif
#endif
}
#endif

James Goppert's avatar
James Goppert committed
225
#endif
lm's avatar
lm committed
226

James Goppert's avatar
James Goppert committed
227 228
// MESSAGE PARAM_SET UNPACKING

lm's avatar
lm committed
229

James Goppert's avatar
James Goppert committed
230 231 232 233 234 235 236
/**
 * @brief Get field target_system from param_set message
 *
 * @return System ID
 */
static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg)
{
LM's avatar
LM committed
237
	return _MAV_RETURN_uint8_t(msg,  4);
James Goppert's avatar
James Goppert committed
238 239 240 241 242 243 244 245 246
}

/**
 * @brief Get field target_component from param_set message
 *
 * @return Component ID
 */
static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg)
{
LM's avatar
LM committed
247
	return _MAV_RETURN_uint8_t(msg,  5);
James Goppert's avatar
James Goppert committed
248 249 250 251 252
}

/**
 * @brief Get field param_id from param_set message
 *
Lorenz Meier's avatar
Lorenz Meier committed
253
 * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
James Goppert's avatar
James Goppert committed
254
 */
lm's avatar
lm committed
255
static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, char *param_id)
James Goppert's avatar
James Goppert committed
256
{
LM's avatar
LM committed
257
	return _MAV_RETURN_char_array(msg, param_id, 16,  6);
James Goppert's avatar
James Goppert committed
258 259 260 261 262 263 264 265 266
}

/**
 * @brief Get field param_value from param_set message
 *
 * @return Onboard parameter value
 */
static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg)
{
LM's avatar
LM committed
267
	return _MAV_RETURN_float(msg,  0);
James Goppert's avatar
James Goppert committed
268 269
}

270 271 272
/**
 * @brief Get field param_type from param_set message
 *
Lorenz Meier's avatar
Lorenz Meier committed
273
 * @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
274 275 276
 */
static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg)
{
LM's avatar
LM committed
277
	return _MAV_RETURN_uint8_t(msg,  22);
278 279
}

James Goppert's avatar
James Goppert committed
280 281 282 283 284 285 286 287
/**
 * @brief Decode a param_set message into a struct
 *
 * @param msg The message to decode
 * @param param_set C-struct to decode the message contents into
 */
static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set)
{
lm's avatar
lm committed
288 289 290 291 292 293 294
#if MAVLINK_NEED_BYTE_SWAP
	param_set->param_value = mavlink_msg_param_set_get_param_value(msg);
	param_set->target_system = mavlink_msg_param_set_get_target_system(msg);
	param_set->target_component = mavlink_msg_param_set_get_target_component(msg);
	mavlink_msg_param_set_get_param_id(msg, param_set->param_id);
	param_set->param_type = mavlink_msg_param_set_get_param_type(msg);
#else
Lorenz Meier's avatar
Lorenz Meier committed
295
	memcpy(param_set, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_SET_LEN);
lm's avatar
lm committed
296
#endif
James Goppert's avatar
James Goppert committed
297
}