Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE LOCAL_POSITION_SETPOINT_SET PACKING
2
 
3
#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET 50
4
 
5
typedef struct __mavlink_local_position_setpoint_set_t
6
{
7
 uint8_t target_system; ///< System ID
8
 uint8_t target_component; ///< Component ID
9
 float x; ///< x position
10
 float y; ///< y position
11
 float z; ///< z position
12
 float yaw; ///< Desired yaw angle
13
} mavlink_local_position_setpoint_set_t;
14
 
15
#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET_LEN 18
16
#define MAVLINK_MSG_ID_50_LEN 18
17
 
18
 
19
 
20
#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET { \
21
        "LOCAL_POSITION_SETPOINT_SET", \
22
        6, \
23
        {  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_local_position_setpoint_set_t, target_system) }, \
24
         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_local_position_setpoint_set_t, target_component) }, \
25
         { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_local_position_setpoint_set_t, x) }, \
26
         { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_local_position_setpoint_set_t, y) }, \
27
         { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_local_position_setpoint_set_t, z) }, \
28
         { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_local_position_setpoint_set_t, yaw) }, \
29
         } \
30
}
31
 
32
 
33
/**
34
 * @brief Pack a local_position_setpoint_set message
35
 * @param system_id ID of this system
36
 * @param component_id ID of this component (e.g. 200 for IMU)
37
 * @param msg The MAVLink message to compress the data into
38
 *
39
 * @param target_system System ID
40
 * @param target_component Component ID
41
 * @param x x position
42
 * @param y y position
43
 * @param z z position
44
 * @param yaw Desired yaw angle
45
 * @return length of the message in bytes (excluding serial stream start sign)
46
 */
47
static inline uint16_t mavlink_msg_local_position_setpoint_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
48
                                                       uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
49
{
50
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
51
        char buf[18];
52
        _mav_put_uint8_t(buf, 0, target_system);
53
        _mav_put_uint8_t(buf, 1, target_component);
54
        _mav_put_float(buf, 2, x);
55
        _mav_put_float(buf, 6, y);
56
        _mav_put_float(buf, 10, z);
57
        _mav_put_float(buf, 14, yaw);
58
 
59
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
60
#else
61
        mavlink_local_position_setpoint_set_t packet;
62
        packet.target_system = target_system;
63
        packet.target_component = target_component;
64
        packet.x = x;
65
        packet.y = y;
66
        packet.z = z;
67
        packet.yaw = yaw;
68
 
69
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
70
#endif
71
 
72
        msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET;
73
        return mavlink_finalize_message(msg, system_id, component_id, 18);
74
}
75
 
76
/**
77
 * @brief Pack a local_position_setpoint_set message on a channel
78
 * @param system_id ID of this system
79
 * @param component_id ID of this component (e.g. 200 for IMU)
80
 * @param chan The MAVLink channel this message was sent over
81
 * @param msg The MAVLink message to compress the data into
82
 * @param target_system System ID
83
 * @param target_component Component ID
84
 * @param x x position
85
 * @param y y position
86
 * @param z z position
87
 * @param yaw Desired yaw angle
88
 * @return length of the message in bytes (excluding serial stream start sign)
89
 */
90
static inline uint16_t mavlink_msg_local_position_setpoint_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
91
                                                           mavlink_message_t* msg,
92
                                                           uint8_t target_system,uint8_t target_component,float x,float y,float z,float yaw)
93
{
94
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
95
        char buf[18];
96
        _mav_put_uint8_t(buf, 0, target_system);
97
        _mav_put_uint8_t(buf, 1, target_component);
98
        _mav_put_float(buf, 2, x);
99
        _mav_put_float(buf, 6, y);
100
        _mav_put_float(buf, 10, z);
101
        _mav_put_float(buf, 14, yaw);
102
 
103
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
104
#else
105
        mavlink_local_position_setpoint_set_t packet;
106
        packet.target_system = target_system;
107
        packet.target_component = target_component;
108
        packet.x = x;
109
        packet.y = y;
110
        packet.z = z;
111
        packet.yaw = yaw;
112
 
113
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
114
#endif
115
 
116
        msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET;
117
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18);
118
}
119
 
120
/**
121
 * @brief Encode a local_position_setpoint_set struct into a message
122
 *
123
 * @param system_id ID of this system
124
 * @param component_id ID of this component (e.g. 200 for IMU)
125
 * @param msg The MAVLink message to compress the data into
126
 * @param local_position_setpoint_set C-struct to read the message contents from
127
 */
128
static inline uint16_t mavlink_msg_local_position_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_set_t* local_position_setpoint_set)
129
{
130
        return mavlink_msg_local_position_setpoint_set_pack(system_id, component_id, msg, local_position_setpoint_set->target_system, local_position_setpoint_set->target_component, local_position_setpoint_set->x, local_position_setpoint_set->y, local_position_setpoint_set->z, local_position_setpoint_set->yaw);
131
}
132
 
133
/**
134
 * @brief Send a local_position_setpoint_set message
135
 * @param chan MAVLink channel to send the message
136
 *
137
 * @param target_system System ID
138
 * @param target_component Component ID
139
 * @param x x position
140
 * @param y y position
141
 * @param z z position
142
 * @param yaw Desired yaw angle
143
 */
144
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
145
 
146
static inline void mavlink_msg_local_position_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
147
{
148
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
149
        char buf[18];
150
        _mav_put_uint8_t(buf, 0, target_system);
151
        _mav_put_uint8_t(buf, 1, target_component);
152
        _mav_put_float(buf, 2, x);
153
        _mav_put_float(buf, 6, y);
154
        _mav_put_float(buf, 10, z);
155
        _mav_put_float(buf, 14, yaw);
156
 
157
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET, buf, 18);
158
#else
159
        mavlink_local_position_setpoint_set_t packet;
160
        packet.target_system = target_system;
161
        packet.target_component = target_component;
162
        packet.x = x;
163
        packet.y = y;
164
        packet.z = z;
165
        packet.yaw = yaw;
166
 
167
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET, (const char *)&packet, 18);
168
#endif
169
}
170
 
171
#endif
172
 
173
// MESSAGE LOCAL_POSITION_SETPOINT_SET UNPACKING
174
 
175
 
176
/**
177
 * @brief Get field target_system from local_position_setpoint_set message
178
 *
179
 * @return System ID
180
 */
181
static inline uint8_t mavlink_msg_local_position_setpoint_set_get_target_system(const mavlink_message_t* msg)
182
{
183
        return _MAV_RETURN_uint8_t(msg,  0);
184
}
185
 
186
/**
187
 * @brief Get field target_component from local_position_setpoint_set message
188
 *
189
 * @return Component ID
190
 */
191
static inline uint8_t mavlink_msg_local_position_setpoint_set_get_target_component(const mavlink_message_t* msg)
192
{
193
        return _MAV_RETURN_uint8_t(msg,  1);
194
}
195
 
196
/**
197
 * @brief Get field x from local_position_setpoint_set message
198
 *
199
 * @return x position
200
 */
201
static inline float mavlink_msg_local_position_setpoint_set_get_x(const mavlink_message_t* msg)
202
{
203
        return _MAV_RETURN_float(msg,  2);
204
}
205
 
206
/**
207
 * @brief Get field y from local_position_setpoint_set message
208
 *
209
 * @return y position
210
 */
211
static inline float mavlink_msg_local_position_setpoint_set_get_y(const mavlink_message_t* msg)
212
{
213
        return _MAV_RETURN_float(msg,  6);
214
}
215
 
216
/**
217
 * @brief Get field z from local_position_setpoint_set message
218
 *
219
 * @return z position
220
 */
221
static inline float mavlink_msg_local_position_setpoint_set_get_z(const mavlink_message_t* msg)
222
{
223
        return _MAV_RETURN_float(msg,  10);
224
}
225
 
226
/**
227
 * @brief Get field yaw from local_position_setpoint_set message
228
 *
229
 * @return Desired yaw angle
230
 */
231
static inline float mavlink_msg_local_position_setpoint_set_get_yaw(const mavlink_message_t* msg)
232
{
233
        return _MAV_RETURN_float(msg,  14);
234
}
235
 
236
/**
237
 * @brief Decode a local_position_setpoint_set message into a struct
238
 *
239
 * @param msg The message to decode
240
 * @param local_position_setpoint_set C-struct to decode the message contents into
241
 */
242
static inline void mavlink_msg_local_position_setpoint_set_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_set_t* local_position_setpoint_set)
243
{
244
#if MAVLINK_NEED_BYTE_SWAP
245
        local_position_setpoint_set->target_system = mavlink_msg_local_position_setpoint_set_get_target_system(msg);
246
        local_position_setpoint_set->target_component = mavlink_msg_local_position_setpoint_set_get_target_component(msg);
247
        local_position_setpoint_set->x = mavlink_msg_local_position_setpoint_set_get_x(msg);
248
        local_position_setpoint_set->y = mavlink_msg_local_position_setpoint_set_get_y(msg);
249
        local_position_setpoint_set->z = mavlink_msg_local_position_setpoint_set_get_z(msg);
250
        local_position_setpoint_set->yaw = mavlink_msg_local_position_setpoint_set_get_yaw(msg);
251
#else
252
        memcpy(local_position_setpoint_set, _MAV_PAYLOAD(msg), 18);
253
#endif
254
}