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

#define MAVLINK_MSG_ID_PARAM_SET 23
4 5
#define MAVLINK_MSG_ID_PARAM_SET_LEN 22
#define MAVLINK_MSG_23_LEN 22
lm's avatar
lm committed
6 7
#define MAVLINK_MSG_ID_PARAM_SET_KEY 0x2D
#define MAVLINK_MSG_23_KEY 0x2D
James Goppert's avatar
James Goppert committed
8 9 10

typedef struct __mavlink_param_set_t 
{
lm's avatar
lm committed
11 12 13 14
	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
James Goppert's avatar
James Goppert committed
15 16

} mavlink_param_set_t;
17
#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 16
James Goppert's avatar
James Goppert committed
18 19 20 21 22 23 24 25 26 27 28 29 30

/**
 * @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
31
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
32
{
lm's avatar
lm committed
33
	mavlink_param_set_t *p = (mavlink_param_set_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
34 35
	msg->msgid = MAVLINK_MSG_ID_PARAM_SET;

lm's avatar
lm committed
36 37 38 39
	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[16]:Onboard parameter id
	p->param_value = param_value;	// float:Onboard parameter value
James Goppert's avatar
James Goppert committed
40

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

/**
 * @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
56
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
57
{
lm's avatar
lm committed
58
	mavlink_param_set_t *p = (mavlink_param_set_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
59 60
	msg->msgid = MAVLINK_MSG_ID_PARAM_SET;

lm's avatar
lm committed
61 62 63 64
	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[16]:Onboard parameter id
	p->param_value = param_value;	// float:Onboard parameter value
James Goppert's avatar
James Goppert committed
65

lm's avatar
lm committed
66
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN);
James Goppert's avatar
James Goppert committed
67 68 69 70 71 72 73 74 75 76 77 78 79 80 81
}

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

lm's avatar
lm committed
82 83

#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
James Goppert's avatar
James Goppert committed
84 85 86 87 88 89 90 91 92
/**
 * @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
 */
LM's avatar
LM committed
93
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)
lm's avatar
lm committed
94 95 96 97
{
	mavlink_header_t hdr;
	mavlink_param_set_t payload;

lm's avatar
lm committed
98 99 100 101 102
	MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_PARAM_SET_LEN )
	payload.target_system = target_system;	// uint8_t:System ID
	payload.target_component = target_component;	// uint8_t:Component ID
	memcpy(payload.param_id, param_id, sizeof(payload.param_id));	// char[16]:Onboard parameter id
	payload.param_value = param_value;	// float:Onboard parameter value
lm's avatar
lm committed
103 104 105 106 107 108 109 110 111 112

	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 );

lm's avatar
lm committed
113 114 115 116 117 118
	crc_init(&hdr.ck);
	crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
	crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
	crc_accumulate( 0x2D, &hdr.ck); /// include key in X25 checksum
	mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
	MAVLINK_BUFFER_CHECK_END
James Goppert's avatar
James Goppert committed
119 120 121 122 123 124 125 126 127 128 129 130
}

#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
131 132
	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
133 134 135 136 137 138 139 140 141
}

/**
 * @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
142 143
	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
144 145 146 147 148 149 150
}

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

lm's avatar
lm committed
155 156
	memcpy(param_id, p->param_id, sizeof(p->param_id));
	return sizeof(p->param_id);
James Goppert's avatar
James Goppert committed
157 158 159 160 161 162 163 164 165
}

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

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