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

#define MAVLINK_MSG_ID_PARAM_SET 23
lm's avatar
lm committed
4 5
#define MAVLINK_MSG_ID_PARAM_SET_LEN 21
#define MAVLINK_MSG_23_LEN 21
James Goppert's avatar
James Goppert committed
6 7 8 9 10

typedef struct __mavlink_param_set_t 
{
	uint8_t target_system; ///< System ID
	uint8_t target_component; ///< Component ID
lm's avatar
lm committed
11
	char param_id[15]; ///< Onboard parameter id
James Goppert's avatar
James Goppert committed
12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28
	float param_value; ///< Onboard parameter value

} mavlink_param_set_t;
#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 15

/**
 * @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
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
29
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)
James Goppert's avatar
James Goppert committed
30
{
lm's avatar
lm committed
31
	mavlink_param_set_t *p = (mavlink_param_set_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
32 33
	msg->msgid = MAVLINK_MSG_ID_PARAM_SET;

lm's avatar
lm committed
34 35 36 37
	p->target_system = target_system; // uint8_t:System ID
	p->target_component = target_component; // uint8_t:Component ID
	memcpy(p->param_id, param_id, sizeof(p->param_id)); // char[15]:Onboard parameter id
	p->param_value = param_value; // float:Onboard parameter value
James Goppert's avatar
James Goppert committed
38

lm's avatar
lm committed
39
	return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN);
James Goppert's avatar
James Goppert committed
40 41 42 43 44 45 46 47 48 49 50 51 52 53
}

/**
 * @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 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
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
54
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)
James Goppert's avatar
James Goppert committed
55
{
lm's avatar
lm committed
56
	mavlink_param_set_t *p = (mavlink_param_set_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
57 58
	msg->msgid = MAVLINK_MSG_ID_PARAM_SET;

lm's avatar
lm committed
59 60 61 62
	p->target_system = target_system; // uint8_t:System ID
	p->target_component = target_component; // uint8_t:Component ID
	memcpy(p->param_id, param_id, sizeof(p->param_id)); // char[15]:Onboard parameter id
	p->param_value = param_value; // float:Onboard parameter value
James Goppert's avatar
James Goppert committed
63

lm's avatar
lm committed
64
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN);
James Goppert's avatar
James Goppert committed
65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89
}

/**
 * @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)
{
	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);
}

/**
 * @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
 */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
lm's avatar
lm committed
90
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)
James Goppert's avatar
James Goppert committed
91 92
{
	mavlink_message_t msg;
lm's avatar
lm committed
93 94 95 96 97 98 99 100 101 102 103 104 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 133 134 135 136 137 138 139 140 141 142 143 144 145 146
	uint16_t checksum;
	mavlink_param_set_t *p = (mavlink_param_set_t *)&msg.payload[0];

	p->target_system = target_system; // uint8_t:System ID
	p->target_component = target_component; // uint8_t:Component ID
	memcpy(p->param_id, param_id, sizeof(p->param_id)); // char[15]:Onboard parameter id
	p->param_value = param_value; // float:Onboard parameter value

	msg.STX = MAVLINK_STX;
	msg.len = MAVLINK_MSG_ID_PARAM_SET_LEN;
	msg.msgid = MAVLINK_MSG_ID_PARAM_SET;
	msg.sysid = mavlink_system.sysid;
	msg.compid = mavlink_system.compid;
	msg.seq = mavlink_get_channel_status(chan)->current_tx_seq;
	mavlink_get_channel_status(chan)->current_tx_seq = msg.seq + 1;
	checksum = crc_calculate_msg(&msg, msg.len + MAVLINK_CORE_HEADER_LEN);
	msg.ck_a = (uint8_t)(checksum & 0xFF); ///< Low byte
	msg.ck_b = (uint8_t)(checksum >> 8); ///< High byte

	mavlink_send_msg(chan, &msg);
}

#endif

#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS_SMALL
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)
{
	mavlink_header_t hdr;
	mavlink_param_set_t payload;
	uint16_t checksum;
	mavlink_param_set_t *p = &payload;

	p->target_system = target_system; // uint8_t:System ID
	p->target_component = target_component; // uint8_t:Component ID
	memcpy(p->param_id, param_id, sizeof(p->param_id)); // char[15]:Onboard parameter id
	p->param_value = param_value; // float:Onboard parameter value

	hdr.STX = MAVLINK_STX;
	hdr.len = MAVLINK_MSG_ID_PARAM_SET_LEN;
	hdr.msgid = MAVLINK_MSG_ID_PARAM_SET;
	hdr.sysid = mavlink_system.sysid;
	hdr.compid = mavlink_system.compid;
	hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
	mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
	mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );

	crc_init(&checksum);
	checksum = crc_calculate_mem((uint8_t *)&hdr.len, &checksum, MAVLINK_CORE_HEADER_LEN);
	checksum = crc_calculate_mem((uint8_t *)&payload, &checksum, hdr.len );
	hdr.ck_a = (uint8_t)(checksum & 0xFF); ///< Low byte
	hdr.ck_b = (uint8_t)(checksum >> 8); ///< High byte

	mavlink_send_mem(chan, (uint8_t *)&payload, hdr.len);
	mavlink_send_mem(chan, (uint8_t *)&hdr.ck_a, MAVLINK_NUM_CHECKSUM_BYTES);
James Goppert's avatar
James Goppert committed
147 148 149 150 151 152 153 154 155 156 157 158
}

#endif
// MESSAGE PARAM_SET UNPACKING

/**
 * @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
159 160
	mavlink_param_set_t *p = (mavlink_param_set_t *)&msg->payload[0];
	return (uint8_t)(p->target_system);
James Goppert's avatar
James Goppert committed
161 162 163 164 165 166 167 168 169
}

/**
 * @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
170 171
	mavlink_param_set_t *p = (mavlink_param_set_t *)&msg->payload[0];
	return (uint8_t)(p->target_component);
James Goppert's avatar
James Goppert committed
172 173 174 175 176 177 178
}

/**
 * @brief Get field param_id from param_set message
 *
 * @return Onboard parameter id
 */
lm's avatar
lm committed
179
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
180
{
lm's avatar
lm committed
181
	mavlink_param_set_t *p = (mavlink_param_set_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
182

lm's avatar
lm committed
183 184
	memcpy(param_id, p->param_id, sizeof(p->param_id));
	return sizeof(p->param_id);
James Goppert's avatar
James Goppert committed
185 186 187 188 189 190 191 192 193
}

/**
 * @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
194 195
	mavlink_param_set_t *p = (mavlink_param_set_t *)&msg->payload[0];
	return (float)(p->param_value);
James Goppert's avatar
James Goppert committed
196 197 198 199 200 201 202 203 204 205
}

/**
 * @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
206
	memcpy( param_set, msg->payload, sizeof(mavlink_param_set_t));
James Goppert's avatar
James Goppert committed
207
}