Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE PARAM_REQUEST_READ PACKING
2
 
3
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20
4
 
5
typedef struct __mavlink_param_request_read_t
6
{
7
 int16_t param_index; ///< Parameter index. Send -1 to use the param ID field as identifier
8
 uint8_t target_system; ///< System ID
9
 uint8_t target_component; ///< Component ID
10
 char param_id[16]; ///< Onboard parameter id
11
} mavlink_param_request_read_t;
12
 
13
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20
14
#define MAVLINK_MSG_ID_20_LEN 20
15
 
16
#define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 16
17
 
18
#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \
19
        "PARAM_REQUEST_READ", \
20
        4, \
21
        {  { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \
22
         { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \
23
         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \
24
         { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \
25
         } \
26
}
27
 
28
 
29
/**
30
 * @brief Pack a param_request_read message
31
 * @param system_id ID of this system
32
 * @param component_id ID of this component (e.g. 200 for IMU)
33
 * @param msg The MAVLink message to compress the data into
34
 *
35
 * @param target_system System ID
36
 * @param target_component Component ID
37
 * @param param_id Onboard parameter id
38
 * @param param_index Parameter index. Send -1 to use the param ID field as identifier
39
 * @return length of the message in bytes (excluding serial stream start sign)
40
 */
41
static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42
                                                       uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index)
43
{
44
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
45
        char buf[20];
46
        _mav_put_int16_t(buf, 0, param_index);
47
        _mav_put_uint8_t(buf, 2, target_system);
48
        _mav_put_uint8_t(buf, 3, target_component);
49
        _mav_put_char_array(buf, 4, param_id, 16);
50
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
51
#else
52
        mavlink_param_request_read_t packet;
53
        packet.param_index = param_index;
54
        packet.target_system = target_system;
55
        packet.target_component = target_component;
56
        mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
57
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
58
#endif
59
 
60
        msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
61
        return mavlink_finalize_message(msg, system_id, component_id, 20, 214);
62
}
63
 
64
/**
65
 * @brief Pack a param_request_read message on a channel
66
 * @param system_id ID of this system
67
 * @param component_id ID of this component (e.g. 200 for IMU)
68
 * @param chan The MAVLink channel this message was sent over
69
 * @param msg The MAVLink message to compress the data into
70
 * @param target_system System ID
71
 * @param target_component Component ID
72
 * @param param_id Onboard parameter id
73
 * @param param_index Parameter index. Send -1 to use the param ID field as identifier
74
 * @return length of the message in bytes (excluding serial stream start sign)
75
 */
76
static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
77
                                                           mavlink_message_t* msg,
78
                                                           uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index)
79
{
80
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
81
        char buf[20];
82
        _mav_put_int16_t(buf, 0, param_index);
83
        _mav_put_uint8_t(buf, 2, target_system);
84
        _mav_put_uint8_t(buf, 3, target_component);
85
        _mav_put_char_array(buf, 4, param_id, 16);
86
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
87
#else
88
        mavlink_param_request_read_t packet;
89
        packet.param_index = param_index;
90
        packet.target_system = target_system;
91
        packet.target_component = target_component;
92
        mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
93
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
94
#endif
95
 
96
        msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
97
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 214);
98
}
99
 
100
/**
101
 * @brief Encode a param_request_read struct into a message
102
 *
103
 * @param system_id ID of this system
104
 * @param component_id ID of this component (e.g. 200 for IMU)
105
 * @param msg The MAVLink message to compress the data into
106
 * @param param_request_read C-struct to read the message contents from
107
 */
108
static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read)
109
{
110
        return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index);
111
}
112
 
113
/**
114
 * @brief Send a param_request_read message
115
 * @param chan MAVLink channel to send the message
116
 *
117
 * @param target_system System ID
118
 * @param target_component Component ID
119
 * @param param_id Onboard parameter id
120
 * @param param_index Parameter index. Send -1 to use the param ID field as identifier
121
 */
122
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
123
 
124
static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index)
125
{
126
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
127
        char buf[20];
128
        _mav_put_int16_t(buf, 0, param_index);
129
        _mav_put_uint8_t(buf, 2, target_system);
130
        _mav_put_uint8_t(buf, 3, target_component);
131
        _mav_put_char_array(buf, 4, param_id, 16);
132
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, 20, 214);
133
#else
134
        mavlink_param_request_read_t packet;
135
        packet.param_index = param_index;
136
        packet.target_system = target_system;
137
        packet.target_component = target_component;
138
        mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
139
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, 20, 214);
140
#endif
141
}
142
 
143
#endif
144
 
145
// MESSAGE PARAM_REQUEST_READ UNPACKING
146
 
147
 
148
/**
149
 * @brief Get field target_system from param_request_read message
150
 *
151
 * @return System ID
152
 */
153
static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg)
154
{
155
        return _MAV_RETURN_uint8_t(msg,  2);
156
}
157
 
158
/**
159
 * @brief Get field target_component from param_request_read message
160
 *
161
 * @return Component ID
162
 */
163
static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg)
164
{
165
        return _MAV_RETURN_uint8_t(msg,  3);
166
}
167
 
168
/**
169
 * @brief Get field param_id from param_request_read message
170
 *
171
 * @return Onboard parameter id
172
 */
173
static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, char *param_id)
174
{
175
        return _MAV_RETURN_char_array(msg, param_id, 16,  4);
176
}
177
 
178
/**
179
 * @brief Get field param_index from param_request_read message
180
 *
181
 * @return Parameter index. Send -1 to use the param ID field as identifier
182
 */
183
static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg)
184
{
185
        return _MAV_RETURN_int16_t(msg,  0);
186
}
187
 
188
/**
189
 * @brief Decode a param_request_read message into a struct
190
 *
191
 * @param msg The message to decode
192
 * @param param_request_read C-struct to decode the message contents into
193
 */
194
static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read)
195
{
196
#if MAVLINK_NEED_BYTE_SWAP
197
        param_request_read->param_index = mavlink_msg_param_request_read_get_param_index(msg);
198
        param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg);
199
        param_request_read->target_component = mavlink_msg_param_request_read_get_target_component(msg);
200
        mavlink_msg_param_request_read_get_param_id(msg, param_request_read->param_id);
201
#else
202
        memcpy(param_request_read, _MAV_PAYLOAD(msg), 20);
203
#endif
204
}