Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE CONTROL_STATUS PACKING
2
 
3
#define MAVLINK_MSG_ID_CONTROL_STATUS 52
4
 
5
typedef struct __mavlink_control_status_t
6
{
7
 uint8_t position_fix; ///< Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 
8
 uint8_t vision_fix; ///< Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 
9
 uint8_t gps_fix; ///< GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 
10
 uint8_t ahrs_health; ///< Attitude estimation health: 0: poor, 255: excellent
11
 uint8_t control_att; ///< 0: Attitude control disabled, 1: enabled
12
 uint8_t control_pos_xy; ///< 0: X, Y position control disabled, 1: enabled
13
 uint8_t control_pos_z; ///< 0: Z position control disabled, 1: enabled
14
 uint8_t control_pos_yaw; ///< 0: Yaw angle control disabled, 1: enabled
15
} mavlink_control_status_t;
16
 
17
#define MAVLINK_MSG_ID_CONTROL_STATUS_LEN 8
18
#define MAVLINK_MSG_ID_52_LEN 8
19
 
20
 
21
 
22
#define MAVLINK_MESSAGE_INFO_CONTROL_STATUS { \
23
        "CONTROL_STATUS", \
24
        8, \
25
        {  { "position_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_control_status_t, position_fix) }, \
26
         { "vision_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_control_status_t, vision_fix) }, \
27
         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_control_status_t, gps_fix) }, \
28
         { "ahrs_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_control_status_t, ahrs_health) }, \
29
         { "control_att", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_control_status_t, control_att) }, \
30
         { "control_pos_xy", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_control_status_t, control_pos_xy) }, \
31
         { "control_pos_z", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_control_status_t, control_pos_z) }, \
32
         { "control_pos_yaw", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_control_status_t, control_pos_yaw) }, \
33
         } \
34
}
35
 
36
 
37
/**
38
 * @brief Pack a control_status 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 position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
44
 * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
45
 * @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
46
 * @param ahrs_health Attitude estimation health: 0: poor, 255: excellent
47
 * @param control_att 0: Attitude control disabled, 1: enabled
48
 * @param control_pos_xy 0: X, Y position control disabled, 1: enabled
49
 * @param control_pos_z 0: Z position control disabled, 1: enabled
50
 * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled
51
 * @return length of the message in bytes (excluding serial stream start sign)
52
 */
53
static inline uint16_t mavlink_msg_control_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
54
                                                       uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t ahrs_health, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw)
55
{
56
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
57
        char buf[8];
58
        _mav_put_uint8_t(buf, 0, position_fix);
59
        _mav_put_uint8_t(buf, 1, vision_fix);
60
        _mav_put_uint8_t(buf, 2, gps_fix);
61
        _mav_put_uint8_t(buf, 3, ahrs_health);
62
        _mav_put_uint8_t(buf, 4, control_att);
63
        _mav_put_uint8_t(buf, 5, control_pos_xy);
64
        _mav_put_uint8_t(buf, 6, control_pos_z);
65
        _mav_put_uint8_t(buf, 7, control_pos_yaw);
66
 
67
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
68
#else
69
        mavlink_control_status_t packet;
70
        packet.position_fix = position_fix;
71
        packet.vision_fix = vision_fix;
72
        packet.gps_fix = gps_fix;
73
        packet.ahrs_health = ahrs_health;
74
        packet.control_att = control_att;
75
        packet.control_pos_xy = control_pos_xy;
76
        packet.control_pos_z = control_pos_z;
77
        packet.control_pos_yaw = control_pos_yaw;
78
 
79
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
80
#endif
81
 
82
        msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS;
83
        return mavlink_finalize_message(msg, system_id, component_id, 8);
84
}
85
 
86
/**
87
 * @brief Pack a control_status 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 position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
93
 * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
94
 * @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
95
 * @param ahrs_health Attitude estimation health: 0: poor, 255: excellent
96
 * @param control_att 0: Attitude control disabled, 1: enabled
97
 * @param control_pos_xy 0: X, Y position control disabled, 1: enabled
98
 * @param control_pos_z 0: Z position control disabled, 1: enabled
99
 * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled
100
 * @return length of the message in bytes (excluding serial stream start sign)
101
 */
102
static inline uint16_t mavlink_msg_control_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
103
                                                           mavlink_message_t* msg,
104
                                                           uint8_t position_fix,uint8_t vision_fix,uint8_t gps_fix,uint8_t ahrs_health,uint8_t control_att,uint8_t control_pos_xy,uint8_t control_pos_z,uint8_t control_pos_yaw)
105
{
106
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
107
        char buf[8];
108
        _mav_put_uint8_t(buf, 0, position_fix);
109
        _mav_put_uint8_t(buf, 1, vision_fix);
110
        _mav_put_uint8_t(buf, 2, gps_fix);
111
        _mav_put_uint8_t(buf, 3, ahrs_health);
112
        _mav_put_uint8_t(buf, 4, control_att);
113
        _mav_put_uint8_t(buf, 5, control_pos_xy);
114
        _mav_put_uint8_t(buf, 6, control_pos_z);
115
        _mav_put_uint8_t(buf, 7, control_pos_yaw);
116
 
117
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
118
#else
119
        mavlink_control_status_t packet;
120
        packet.position_fix = position_fix;
121
        packet.vision_fix = vision_fix;
122
        packet.gps_fix = gps_fix;
123
        packet.ahrs_health = ahrs_health;
124
        packet.control_att = control_att;
125
        packet.control_pos_xy = control_pos_xy;
126
        packet.control_pos_z = control_pos_z;
127
        packet.control_pos_yaw = control_pos_yaw;
128
 
129
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
130
#endif
131
 
132
        msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS;
133
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8);
134
}
135
 
136
/**
137
 * @brief Encode a control_status 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 control_status C-struct to read the message contents from
143
 */
144
static inline uint16_t mavlink_msg_control_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_control_status_t* control_status)
145
{
146
        return mavlink_msg_control_status_pack(system_id, component_id, msg, control_status->position_fix, control_status->vision_fix, control_status->gps_fix, control_status->ahrs_health, control_status->control_att, control_status->control_pos_xy, control_status->control_pos_z, control_status->control_pos_yaw);
147
}
148
 
149
/**
150
 * @brief Send a control_status message
151
 * @param chan MAVLink channel to send the message
152
 *
153
 * @param position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
154
 * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
155
 * @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
156
 * @param ahrs_health Attitude estimation health: 0: poor, 255: excellent
157
 * @param control_att 0: Attitude control disabled, 1: enabled
158
 * @param control_pos_xy 0: X, Y position control disabled, 1: enabled
159
 * @param control_pos_z 0: Z position control disabled, 1: enabled
160
 * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled
161
 */
162
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
163
 
164
static inline void mavlink_msg_control_status_send(mavlink_channel_t chan, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t ahrs_health, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw)
165
{
166
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
167
        char buf[8];
168
        _mav_put_uint8_t(buf, 0, position_fix);
169
        _mav_put_uint8_t(buf, 1, vision_fix);
170
        _mav_put_uint8_t(buf, 2, gps_fix);
171
        _mav_put_uint8_t(buf, 3, ahrs_health);
172
        _mav_put_uint8_t(buf, 4, control_att);
173
        _mav_put_uint8_t(buf, 5, control_pos_xy);
174
        _mav_put_uint8_t(buf, 6, control_pos_z);
175
        _mav_put_uint8_t(buf, 7, control_pos_yaw);
176
 
177
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_STATUS, buf, 8);
178
#else
179
        mavlink_control_status_t packet;
180
        packet.position_fix = position_fix;
181
        packet.vision_fix = vision_fix;
182
        packet.gps_fix = gps_fix;
183
        packet.ahrs_health = ahrs_health;
184
        packet.control_att = control_att;
185
        packet.control_pos_xy = control_pos_xy;
186
        packet.control_pos_z = control_pos_z;
187
        packet.control_pos_yaw = control_pos_yaw;
188
 
189
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_STATUS, (const char *)&packet, 8);
190
#endif
191
}
192
 
193
#endif
194
 
195
// MESSAGE CONTROL_STATUS UNPACKING
196
 
197
 
198
/**
199
 * @brief Get field position_fix from control_status message
200
 *
201
 * @return Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
202
 */
203
static inline uint8_t mavlink_msg_control_status_get_position_fix(const mavlink_message_t* msg)
204
{
205
        return _MAV_RETURN_uint8_t(msg,  0);
206
}
207
 
208
/**
209
 * @brief Get field vision_fix from control_status message
210
 *
211
 * @return Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
212
 */
213
static inline uint8_t mavlink_msg_control_status_get_vision_fix(const mavlink_message_t* msg)
214
{
215
        return _MAV_RETURN_uint8_t(msg,  1);
216
}
217
 
218
/**
219
 * @brief Get field gps_fix from control_status message
220
 *
221
 * @return GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
222
 */
223
static inline uint8_t mavlink_msg_control_status_get_gps_fix(const mavlink_message_t* msg)
224
{
225
        return _MAV_RETURN_uint8_t(msg,  2);
226
}
227
 
228
/**
229
 * @brief Get field ahrs_health from control_status message
230
 *
231
 * @return Attitude estimation health: 0: poor, 255: excellent
232
 */
233
static inline uint8_t mavlink_msg_control_status_get_ahrs_health(const mavlink_message_t* msg)
234
{
235
        return _MAV_RETURN_uint8_t(msg,  3);
236
}
237
 
238
/**
239
 * @brief Get field control_att from control_status message
240
 *
241
 * @return 0: Attitude control disabled, 1: enabled
242
 */
243
static inline uint8_t mavlink_msg_control_status_get_control_att(const mavlink_message_t* msg)
244
{
245
        return _MAV_RETURN_uint8_t(msg,  4);
246
}
247
 
248
/**
249
 * @brief Get field control_pos_xy from control_status message
250
 *
251
 * @return 0: X, Y position control disabled, 1: enabled
252
 */
253
static inline uint8_t mavlink_msg_control_status_get_control_pos_xy(const mavlink_message_t* msg)
254
{
255
        return _MAV_RETURN_uint8_t(msg,  5);
256
}
257
 
258
/**
259
 * @brief Get field control_pos_z from control_status message
260
 *
261
 * @return 0: Z position control disabled, 1: enabled
262
 */
263
static inline uint8_t mavlink_msg_control_status_get_control_pos_z(const mavlink_message_t* msg)
264
{
265
        return _MAV_RETURN_uint8_t(msg,  6);
266
}
267
 
268
/**
269
 * @brief Get field control_pos_yaw from control_status message
270
 *
271
 * @return 0: Yaw angle control disabled, 1: enabled
272
 */
273
static inline uint8_t mavlink_msg_control_status_get_control_pos_yaw(const mavlink_message_t* msg)
274
{
275
        return _MAV_RETURN_uint8_t(msg,  7);
276
}
277
 
278
/**
279
 * @brief Decode a control_status message into a struct
280
 *
281
 * @param msg The message to decode
282
 * @param control_status C-struct to decode the message contents into
283
 */
284
static inline void mavlink_msg_control_status_decode(const mavlink_message_t* msg, mavlink_control_status_t* control_status)
285
{
286
#if MAVLINK_NEED_BYTE_SWAP
287
        control_status->position_fix = mavlink_msg_control_status_get_position_fix(msg);
288
        control_status->vision_fix = mavlink_msg_control_status_get_vision_fix(msg);
289
        control_status->gps_fix = mavlink_msg_control_status_get_gps_fix(msg);
290
        control_status->ahrs_health = mavlink_msg_control_status_get_ahrs_health(msg);
291
        control_status->control_att = mavlink_msg_control_status_get_control_att(msg);
292
        control_status->control_pos_xy = mavlink_msg_control_status_get_control_pos_xy(msg);
293
        control_status->control_pos_z = mavlink_msg_control_status_get_control_pos_z(msg);
294
        control_status->control_pos_yaw = mavlink_msg_control_status_get_control_pos_yaw(msg);
295
#else
296
        memcpy(control_status, _MAV_PAYLOAD(msg), 8);
297
#endif
298
}