mavlink_msg_param_set.h 8.16 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 10 11
 float param_value; ///< Onboard parameter value
 uint8_t target_system; ///< System ID
 uint8_t target_component; ///< Component ID
 char param_id[16]; ///< Onboard parameter id
 uint8_t param_type; ///< Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t
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

17
#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 16
James Goppert's avatar
James Goppert committed
18

lm's avatar
lm committed
19 20 21
#define MAVLINK_MESSAGE_INFO_PARAM_SET { \
	"PARAM_SET", \
	5, \
lm's avatar
lm committed
22 23 24 25 26
	{  { "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
27 28 29 30
         } \
}


James Goppert's avatar
James Goppert committed
31 32 33 34 35 36 37 38 39 40
/**
 * @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
 * @param param_id Onboard parameter id
 * @param param_value Onboard parameter value
41
 * @param param_type Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t
James Goppert's avatar
James Goppert committed
42 43
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
44 45
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
46
{
LM's avatar
LM committed
47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[23];
	_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);
        memcpy(_MAV_PAYLOAD(msg), buf, 23);
#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;
	memcpy(packet.param_id, param_id, sizeof(char)*16);
        memcpy(_MAV_PAYLOAD(msg), &packet, 23);
#endif
James Goppert's avatar
James Goppert committed
64

LM's avatar
LM committed
65
	msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
lm's avatar
lm committed
66
	return mavlink_finalize_message(msg, system_id, component_id, 23, 168);
James Goppert's avatar
James Goppert committed
67 68 69
}

/**
lm's avatar
lm committed
70
 * @brief Pack a param_set message on a channel
James Goppert's avatar
James Goppert committed
71 72 73 74 75 76 77 78
 * @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 param_id Onboard parameter id
 * @param param_value Onboard parameter value
79
 * @param param_type Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t
James Goppert's avatar
James Goppert committed
80 81
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
82 83 84
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
85
{
LM's avatar
LM committed
86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[23];
	_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);
        memcpy(_MAV_PAYLOAD(msg), buf, 23);
#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;
	memcpy(packet.param_id, param_id, sizeof(char)*16);
        memcpy(_MAV_PAYLOAD(msg), &packet, 23);
#endif
James Goppert's avatar
James Goppert committed
103

LM's avatar
LM committed
104
	msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
lm's avatar
lm committed
105
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 23, 168);
James Goppert's avatar
James Goppert committed
106 107 108 109 110 111 112 113 114 115 116 117
}

/**
 * @brief Encode a param_set 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_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)
{
118
	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
119 120 121 122 123 124 125 126 127 128
}

/**
 * @brief Send a param_set message
 * @param chan MAVLink channel to send the message
 *
 * @param target_system System ID
 * @param target_component Component ID
 * @param param_id Onboard parameter id
 * @param param_value Onboard parameter value
129
 * @param param_type Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t
James Goppert's avatar
James Goppert committed
130
 */
lm's avatar
lm committed
131 132 133
#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
134
{
LM's avatar
LM committed
135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[23];
	_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);
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, 23, 168);
#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;
	memcpy(packet.param_id, param_id, sizeof(char)*16);
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, 23, 168);
#endif
James Goppert's avatar
James Goppert committed
152 153 154
}

#endif
lm's avatar
lm committed
155

James Goppert's avatar
James Goppert committed
156 157
// MESSAGE PARAM_SET UNPACKING

lm's avatar
lm committed
158

James Goppert's avatar
James Goppert committed
159 160 161 162 163 164 165
/**
 * @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
166
	return _MAV_RETURN_uint8_t(msg,  4);
James Goppert's avatar
James Goppert committed
167 168 169 170 171 172 173 174 175
}

/**
 * @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
176
	return _MAV_RETURN_uint8_t(msg,  5);
James Goppert's avatar
James Goppert committed
177 178 179 180 181 182 183
}

/**
 * @brief Get field param_id from param_set message
 *
 * @return Onboard parameter id
 */
lm's avatar
lm committed
184
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
185
{
LM's avatar
LM committed
186
	return _MAV_RETURN_char_array(msg, param_id, 16,  6);
James Goppert's avatar
James Goppert committed
187 188 189 190 191 192 193 194 195
}

/**
 * @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
196
	return _MAV_RETURN_float(msg,  0);
James Goppert's avatar
James Goppert committed
197 198
}

199 200 201 202 203 204 205
/**
 * @brief Get field param_type from param_set message
 *
 * @return Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t
 */
static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg)
{
LM's avatar
LM committed
206
	return _MAV_RETURN_uint8_t(msg,  22);
207 208
}

James Goppert's avatar
James Goppert committed
209 210 211 212 213 214 215 216
/**
 * @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
217 218 219 220 221 222 223
#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
LM's avatar
LM committed
224
	memcpy(param_set, _MAV_PAYLOAD(msg), 23);
lm's avatar
lm committed
225
#endif
James Goppert's avatar
James Goppert committed
226
}