Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE PARAM_VALUE PACKING
2
 
3
#define MAVLINK_MSG_ID_PARAM_VALUE 22
4
 
5
typedef struct __mavlink_param_value_t
6
{
7
 float param_value; ///< Onboard parameter value
8
 uint16_t param_count; ///< Total number of onboard parameters
9
 uint16_t param_index; ///< Index of this onboard parameter
10
 char param_id[16]; ///< Onboard parameter id
11
 uint8_t param_type; ///< Onboard parameter type: see MAV_VAR enum
12
} mavlink_param_value_t;
13
 
14
#define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25
15
#define MAVLINK_MSG_ID_22_LEN 25
16
 
17
#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 16
18
 
19
#define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \
20
        "PARAM_VALUE", \
21
        5, \
22
        {  { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \
23
         { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \
24
         { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \
25
         { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \
26
         { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \
27
         } \
28
}
29
 
30
 
31
/**
32
 * @brief Pack a param_value message
33
 * @param system_id ID of this system
34
 * @param component_id ID of this component (e.g. 200 for IMU)
35
 * @param msg The MAVLink message to compress the data into
36
 *
37
 * @param param_id Onboard parameter id
38
 * @param param_value Onboard parameter value
39
 * @param param_type Onboard parameter type: see MAV_VAR enum
40
 * @param param_count Total number of onboard parameters
41
 * @param param_index Index of this onboard parameter
42
 * @return length of the message in bytes (excluding serial stream start sign)
43
 */
44
static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
45
                                                       const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index)
46
{
47
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
48
        char buf[25];
49
        _mav_put_float(buf, 0, param_value);
50
        _mav_put_uint16_t(buf, 4, param_count);
51
        _mav_put_uint16_t(buf, 6, param_index);
52
        _mav_put_uint8_t(buf, 24, param_type);
53
        _mav_put_char_array(buf, 8, param_id, 16);
54
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
55
#else
56
        mavlink_param_value_t packet;
57
        packet.param_value = param_value;
58
        packet.param_count = param_count;
59
        packet.param_index = param_index;
60
        packet.param_type = param_type;
61
        mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
62
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
63
#endif
64
 
65
        msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
66
        return mavlink_finalize_message(msg, system_id, component_id, 25, 220);
67
}
68
 
69
/**
70
 * @brief Pack a param_value message on a channel
71
 * @param system_id ID of this system
72
 * @param component_id ID of this component (e.g. 200 for IMU)
73
 * @param chan The MAVLink channel this message was sent over
74
 * @param msg The MAVLink message to compress the data into
75
 * @param param_id Onboard parameter id
76
 * @param param_value Onboard parameter value
77
 * @param param_type Onboard parameter type: see MAV_VAR enum
78
 * @param param_count Total number of onboard parameters
79
 * @param param_index Index of this onboard parameter
80
 * @return length of the message in bytes (excluding serial stream start sign)
81
 */
82
static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
83
                                                           mavlink_message_t* msg,
84
                                                           const char *param_id,float param_value,uint8_t param_type,uint16_t param_count,uint16_t param_index)
85
{
86
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
87
        char buf[25];
88
        _mav_put_float(buf, 0, param_value);
89
        _mav_put_uint16_t(buf, 4, param_count);
90
        _mav_put_uint16_t(buf, 6, param_index);
91
        _mav_put_uint8_t(buf, 24, param_type);
92
        _mav_put_char_array(buf, 8, param_id, 16);
93
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
94
#else
95
        mavlink_param_value_t packet;
96
        packet.param_value = param_value;
97
        packet.param_count = param_count;
98
        packet.param_index = param_index;
99
        packet.param_type = param_type;
100
        mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
101
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
102
#endif
103
 
104
        msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
105
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 220);
106
}
107
 
108
/**
109
 * @brief Encode a param_value struct into a message
110
 *
111
 * @param system_id ID of this system
112
 * @param component_id ID of this component (e.g. 200 for IMU)
113
 * @param msg The MAVLink message to compress the data into
114
 * @param param_value C-struct to read the message contents from
115
 */
116
static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value)
117
{
118
        return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index);
119
}
120
 
121
/**
122
 * @brief Send a param_value message
123
 * @param chan MAVLink channel to send the message
124
 *
125
 * @param param_id Onboard parameter id
126
 * @param param_value Onboard parameter value
127
 * @param param_type Onboard parameter type: see MAV_VAR enum
128
 * @param param_count Total number of onboard parameters
129
 * @param param_index Index of this onboard parameter
130
 */
131
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
132
 
133
static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index)
134
{
135
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
136
        char buf[25];
137
        _mav_put_float(buf, 0, param_value);
138
        _mav_put_uint16_t(buf, 4, param_count);
139
        _mav_put_uint16_t(buf, 6, param_index);
140
        _mav_put_uint8_t(buf, 24, param_type);
141
        _mav_put_char_array(buf, 8, param_id, 16);
142
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, 25, 220);
143
#else
144
        mavlink_param_value_t packet;
145
        packet.param_value = param_value;
146
        packet.param_count = param_count;
147
        packet.param_index = param_index;
148
        packet.param_type = param_type;
149
        mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
150
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, 25, 220);
151
#endif
152
}
153
 
154
#endif
155
 
156
// MESSAGE PARAM_VALUE UNPACKING
157
 
158
 
159
/**
160
 * @brief Get field param_id from param_value message
161
 *
162
 * @return Onboard parameter id
163
 */
164
static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, char *param_id)
165
{
166
        return _MAV_RETURN_char_array(msg, param_id, 16,  8);
167
}
168
 
169
/**
170
 * @brief Get field param_value from param_value message
171
 *
172
 * @return Onboard parameter value
173
 */
174
static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg)
175
{
176
        return _MAV_RETURN_float(msg,  0);
177
}
178
 
179
/**
180
 * @brief Get field param_type from param_value message
181
 *
182
 * @return Onboard parameter type: see MAV_VAR enum
183
 */
184
static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_message_t* msg)
185
{
186
        return _MAV_RETURN_uint8_t(msg,  24);
187
}
188
 
189
/**
190
 * @brief Get field param_count from param_value message
191
 *
192
 * @return Total number of onboard parameters
193
 */
194
static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg)
195
{
196
        return _MAV_RETURN_uint16_t(msg,  4);
197
}
198
 
199
/**
200
 * @brief Get field param_index from param_value message
201
 *
202
 * @return Index of this onboard parameter
203
 */
204
static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg)
205
{
206
        return _MAV_RETURN_uint16_t(msg,  6);
207
}
208
 
209
/**
210
 * @brief Decode a param_value message into a struct
211
 *
212
 * @param msg The message to decode
213
 * @param param_value C-struct to decode the message contents into
214
 */
215
static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value)
216
{
217
#if MAVLINK_NEED_BYTE_SWAP
218
        param_value->param_value = mavlink_msg_param_value_get_param_value(msg);
219
        param_value->param_count = mavlink_msg_param_value_get_param_count(msg);
220
        param_value->param_index = mavlink_msg_param_value_get_param_index(msg);
221
        mavlink_msg_param_value_get_param_id(msg, param_value->param_id);
222
        param_value->param_type = mavlink_msg_param_value_get_param_type(msg);
223
#else
224
        memcpy(param_value, _MAV_PAYLOAD(msg), 25);
225
#endif
226
}