Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE COMMAND PACKING
2
 
3
#define MAVLINK_MSG_ID_COMMAND 75
4
 
5
typedef struct __mavlink_command_t
6
{
7
 uint8_t target_system; ///< System which should execute the command
8
 uint8_t target_component; ///< Component which should execute the command, 0 for all components
9
 uint8_t command; ///< Command ID, as defined by MAV_CMD enum.
10
 uint8_t confirmation; ///< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
11
 float param1; ///< Parameter 1, as defined by MAV_CMD enum.
12
 float param2; ///< Parameter 2, as defined by MAV_CMD enum.
13
 float param3; ///< Parameter 3, as defined by MAV_CMD enum.
14
 float param4; ///< Parameter 4, as defined by MAV_CMD enum.
15
} mavlink_command_t;
16
 
17
#define MAVLINK_MSG_ID_COMMAND_LEN 20
18
#define MAVLINK_MSG_ID_75_LEN 20
19
 
20
 
21
 
22
#define MAVLINK_MESSAGE_INFO_COMMAND { \
23
        "COMMAND", \
24
        8, \
25
        {  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_command_t, target_system) }, \
26
         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_command_t, target_component) }, \
27
         { "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_t, command) }, \
28
         { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_t, confirmation) }, \
29
         { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_t, param1) }, \
30
         { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_t, param2) }, \
31
         { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_t, param3) }, \
32
         { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_t, param4) }, \
33
         } \
34
}
35
 
36
 
37
/**
38
 * @brief Pack a command message
39
 * @param system_id ID of this system
40
 * @param component_id ID of this component (e.g. 200 for IMU)
41
 * @param msg The MAVLink message to compress the data into
42
 *
43
 * @param target_system System which should execute the command
44
 * @param target_component Component which should execute the command, 0 for all components
45
 * @param command Command ID, as defined by MAV_CMD enum.
46
 * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
47
 * @param param1 Parameter 1, as defined by MAV_CMD enum.
48
 * @param param2 Parameter 2, as defined by MAV_CMD enum.
49
 * @param param3 Parameter 3, as defined by MAV_CMD enum.
50
 * @param param4 Parameter 4, as defined by MAV_CMD enum.
51
 * @return length of the message in bytes (excluding serial stream start sign)
52
 */
53
static inline uint16_t mavlink_msg_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
54
                                                       uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4)
55
{
56
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
57
        char buf[20];
58
        _mav_put_uint8_t(buf, 0, target_system);
59
        _mav_put_uint8_t(buf, 1, target_component);
60
        _mav_put_uint8_t(buf, 2, command);
61
        _mav_put_uint8_t(buf, 3, confirmation);
62
        _mav_put_float(buf, 4, param1);
63
        _mav_put_float(buf, 8, param2);
64
        _mav_put_float(buf, 12, param3);
65
        _mav_put_float(buf, 16, param4);
66
 
67
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
68
#else
69
        mavlink_command_t packet;
70
        packet.target_system = target_system;
71
        packet.target_component = target_component;
72
        packet.command = command;
73
        packet.confirmation = confirmation;
74
        packet.param1 = param1;
75
        packet.param2 = param2;
76
        packet.param3 = param3;
77
        packet.param4 = param4;
78
 
79
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
80
#endif
81
 
82
        msg->msgid = MAVLINK_MSG_ID_COMMAND;
83
        return mavlink_finalize_message(msg, system_id, component_id, 20);
84
}
85
 
86
/**
87
 * @brief Pack a command message on a channel
88
 * @param system_id ID of this system
89
 * @param component_id ID of this component (e.g. 200 for IMU)
90
 * @param chan The MAVLink channel this message was sent over
91
 * @param msg The MAVLink message to compress the data into
92
 * @param target_system System which should execute the command
93
 * @param target_component Component which should execute the command, 0 for all components
94
 * @param command Command ID, as defined by MAV_CMD enum.
95
 * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
96
 * @param param1 Parameter 1, as defined by MAV_CMD enum.
97
 * @param param2 Parameter 2, as defined by MAV_CMD enum.
98
 * @param param3 Parameter 3, as defined by MAV_CMD enum.
99
 * @param param4 Parameter 4, as defined by MAV_CMD enum.
100
 * @return length of the message in bytes (excluding serial stream start sign)
101
 */
102
static inline uint16_t mavlink_msg_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
103
                                                           mavlink_message_t* msg,
104
                                                           uint8_t target_system,uint8_t target_component,uint8_t command,uint8_t confirmation,float param1,float param2,float param3,float param4)
105
{
106
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
107
        char buf[20];
108
        _mav_put_uint8_t(buf, 0, target_system);
109
        _mav_put_uint8_t(buf, 1, target_component);
110
        _mav_put_uint8_t(buf, 2, command);
111
        _mav_put_uint8_t(buf, 3, confirmation);
112
        _mav_put_float(buf, 4, param1);
113
        _mav_put_float(buf, 8, param2);
114
        _mav_put_float(buf, 12, param3);
115
        _mav_put_float(buf, 16, param4);
116
 
117
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
118
#else
119
        mavlink_command_t packet;
120
        packet.target_system = target_system;
121
        packet.target_component = target_component;
122
        packet.command = command;
123
        packet.confirmation = confirmation;
124
        packet.param1 = param1;
125
        packet.param2 = param2;
126
        packet.param3 = param3;
127
        packet.param4 = param4;
128
 
129
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
130
#endif
131
 
132
        msg->msgid = MAVLINK_MSG_ID_COMMAND;
133
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20);
134
}
135
 
136
/**
137
 * @brief Encode a command struct into a message
138
 *
139
 * @param system_id ID of this system
140
 * @param component_id ID of this component (e.g. 200 for IMU)
141
 * @param msg The MAVLink message to compress the data into
142
 * @param command C-struct to read the message contents from
143
 */
144
static inline uint16_t mavlink_msg_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_t* command)
145
{
146
        return mavlink_msg_command_pack(system_id, component_id, msg, command->target_system, command->target_component, command->command, command->confirmation, command->param1, command->param2, command->param3, command->param4);
147
}
148
 
149
/**
150
 * @brief Send a command message
151
 * @param chan MAVLink channel to send the message
152
 *
153
 * @param target_system System which should execute the command
154
 * @param target_component Component which should execute the command, 0 for all components
155
 * @param command Command ID, as defined by MAV_CMD enum.
156
 * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
157
 * @param param1 Parameter 1, as defined by MAV_CMD enum.
158
 * @param param2 Parameter 2, as defined by MAV_CMD enum.
159
 * @param param3 Parameter 3, as defined by MAV_CMD enum.
160
 * @param param4 Parameter 4, as defined by MAV_CMD enum.
161
 */
162
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
163
 
164
static inline void mavlink_msg_command_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4)
165
{
166
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
167
        char buf[20];
168
        _mav_put_uint8_t(buf, 0, target_system);
169
        _mav_put_uint8_t(buf, 1, target_component);
170
        _mav_put_uint8_t(buf, 2, command);
171
        _mav_put_uint8_t(buf, 3, confirmation);
172
        _mav_put_float(buf, 4, param1);
173
        _mav_put_float(buf, 8, param2);
174
        _mav_put_float(buf, 12, param3);
175
        _mav_put_float(buf, 16, param4);
176
 
177
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND, buf, 20);
178
#else
179
        mavlink_command_t packet;
180
        packet.target_system = target_system;
181
        packet.target_component = target_component;
182
        packet.command = command;
183
        packet.confirmation = confirmation;
184
        packet.param1 = param1;
185
        packet.param2 = param2;
186
        packet.param3 = param3;
187
        packet.param4 = param4;
188
 
189
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND, (const char *)&packet, 20);
190
#endif
191
}
192
 
193
#endif
194
 
195
// MESSAGE COMMAND UNPACKING
196
 
197
 
198
/**
199
 * @brief Get field target_system from command message
200
 *
201
 * @return System which should execute the command
202
 */
203
static inline uint8_t mavlink_msg_command_get_target_system(const mavlink_message_t* msg)
204
{
205
        return _MAV_RETURN_uint8_t(msg,  0);
206
}
207
 
208
/**
209
 * @brief Get field target_component from command message
210
 *
211
 * @return Component which should execute the command, 0 for all components
212
 */
213
static inline uint8_t mavlink_msg_command_get_target_component(const mavlink_message_t* msg)
214
{
215
        return _MAV_RETURN_uint8_t(msg,  1);
216
}
217
 
218
/**
219
 * @brief Get field command from command message
220
 *
221
 * @return Command ID, as defined by MAV_CMD enum.
222
 */
223
static inline uint8_t mavlink_msg_command_get_command(const mavlink_message_t* msg)
224
{
225
        return _MAV_RETURN_uint8_t(msg,  2);
226
}
227
 
228
/**
229
 * @brief Get field confirmation from command message
230
 *
231
 * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
232
 */
233
static inline uint8_t mavlink_msg_command_get_confirmation(const mavlink_message_t* msg)
234
{
235
        return _MAV_RETURN_uint8_t(msg,  3);
236
}
237
 
238
/**
239
 * @brief Get field param1 from command message
240
 *
241
 * @return Parameter 1, as defined by MAV_CMD enum.
242
 */
243
static inline float mavlink_msg_command_get_param1(const mavlink_message_t* msg)
244
{
245
        return _MAV_RETURN_float(msg,  4);
246
}
247
 
248
/**
249
 * @brief Get field param2 from command message
250
 *
251
 * @return Parameter 2, as defined by MAV_CMD enum.
252
 */
253
static inline float mavlink_msg_command_get_param2(const mavlink_message_t* msg)
254
{
255
        return _MAV_RETURN_float(msg,  8);
256
}
257
 
258
/**
259
 * @brief Get field param3 from command message
260
 *
261
 * @return Parameter 3, as defined by MAV_CMD enum.
262
 */
263
static inline float mavlink_msg_command_get_param3(const mavlink_message_t* msg)
264
{
265
        return _MAV_RETURN_float(msg,  12);
266
}
267
 
268
/**
269
 * @brief Get field param4 from command message
270
 *
271
 * @return Parameter 4, as defined by MAV_CMD enum.
272
 */
273
static inline float mavlink_msg_command_get_param4(const mavlink_message_t* msg)
274
{
275
        return _MAV_RETURN_float(msg,  16);
276
}
277
 
278
/**
279
 * @brief Decode a command message into a struct
280
 *
281
 * @param msg The message to decode
282
 * @param command C-struct to decode the message contents into
283
 */
284
static inline void mavlink_msg_command_decode(const mavlink_message_t* msg, mavlink_command_t* command)
285
{
286
#if MAVLINK_NEED_BYTE_SWAP
287
        command->target_system = mavlink_msg_command_get_target_system(msg);
288
        command->target_component = mavlink_msg_command_get_target_component(msg);
289
        command->command = mavlink_msg_command_get_command(msg);
290
        command->confirmation = mavlink_msg_command_get_confirmation(msg);
291
        command->param1 = mavlink_msg_command_get_param1(msg);
292
        command->param2 = mavlink_msg_command_get_param2(msg);
293
        command->param3 = mavlink_msg_command_get_param3(msg);
294
        command->param4 = mavlink_msg_command_get_param4(msg);
295
#else
296
        memcpy(command, _MAV_PAYLOAD(msg), 20);
297
#endif
298
}