Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE SYS_STATUS PACKING
2
 
3
#define MAVLINK_MSG_ID_SYS_STATUS 34
4
 
5
typedef struct __mavlink_sys_status_t
6
{
7
 uint8_t mode; ///< System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
8
 uint8_t nav_mode; ///< Navigation mode, see MAV_NAV_MODE ENUM
9
 uint8_t status; ///< System status flag, see MAV_STATUS ENUM
10
 uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
11
 uint16_t vbat; ///< Battery voltage, in millivolts (1 = 1 millivolt)
12
 uint16_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 1000)
13
 uint16_t packet_drop; ///< Dropped packets (packets that were corrupted on reception on the MAV)
14
} mavlink_sys_status_t;
15
 
16
#define MAVLINK_MSG_ID_SYS_STATUS_LEN 11
17
#define MAVLINK_MSG_ID_34_LEN 11
18
 
19
 
20
 
21
#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \
22
        "SYS_STATUS", \
23
        7, \
24
        {  { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_sys_status_t, mode) }, \
25
         { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_sys_status_t, nav_mode) }, \
26
         { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_sys_status_t, status) }, \
27
         { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_sys_status_t, load) }, \
28
         { "vbat", NULL, MAVLINK_TYPE_UINT16_T, 0, 5, offsetof(mavlink_sys_status_t, vbat) }, \
29
         { "battery_remaining", NULL, MAVLINK_TYPE_UINT16_T, 0, 7, offsetof(mavlink_sys_status_t, battery_remaining) }, \
30
         { "packet_drop", NULL, MAVLINK_TYPE_UINT16_T, 0, 9, offsetof(mavlink_sys_status_t, packet_drop) }, \
31
         } \
32
}
33
 
34
 
35
/**
36
 * @brief Pack a sys_status message
37
 * @param system_id ID of this system
38
 * @param component_id ID of this component (e.g. 200 for IMU)
39
 * @param msg The MAVLink message to compress the data into
40
 *
41
 * @param mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
42
 * @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM
43
 * @param status System status flag, see MAV_STATUS ENUM
44
 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
45
 * @param vbat Battery voltage, in millivolts (1 = 1 millivolt)
46
 * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 1000)
47
 * @param packet_drop Dropped packets (packets that were corrupted on reception on the MAV)
48
 * @return length of the message in bytes (excluding serial stream start sign)
49
 */
50
static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
51
                                                       uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint16_t battery_remaining, uint16_t packet_drop)
52
{
53
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
54
        char buf[11];
55
        _mav_put_uint8_t(buf, 0, mode);
56
        _mav_put_uint8_t(buf, 1, nav_mode);
57
        _mav_put_uint8_t(buf, 2, status);
58
        _mav_put_uint16_t(buf, 3, load);
59
        _mav_put_uint16_t(buf, 5, vbat);
60
        _mav_put_uint16_t(buf, 7, battery_remaining);
61
        _mav_put_uint16_t(buf, 9, packet_drop);
62
 
63
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 11);
64
#else
65
        mavlink_sys_status_t packet;
66
        packet.mode = mode;
67
        packet.nav_mode = nav_mode;
68
        packet.status = status;
69
        packet.load = load;
70
        packet.vbat = vbat;
71
        packet.battery_remaining = battery_remaining;
72
        packet.packet_drop = packet_drop;
73
 
74
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 11);
75
#endif
76
 
77
        msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
78
        return mavlink_finalize_message(msg, system_id, component_id, 11);
79
}
80
 
81
/**
82
 * @brief Pack a sys_status message on a channel
83
 * @param system_id ID of this system
84
 * @param component_id ID of this component (e.g. 200 for IMU)
85
 * @param chan The MAVLink channel this message was sent over
86
 * @param msg The MAVLink message to compress the data into
87
 * @param mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
88
 * @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM
89
 * @param status System status flag, see MAV_STATUS ENUM
90
 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
91
 * @param vbat Battery voltage, in millivolts (1 = 1 millivolt)
92
 * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 1000)
93
 * @param packet_drop Dropped packets (packets that were corrupted on reception on the MAV)
94
 * @return length of the message in bytes (excluding serial stream start sign)
95
 */
96
static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
97
                                                           mavlink_message_t* msg,
98
                                                           uint8_t mode,uint8_t nav_mode,uint8_t status,uint16_t load,uint16_t vbat,uint16_t battery_remaining,uint16_t packet_drop)
99
{
100
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
101
        char buf[11];
102
        _mav_put_uint8_t(buf, 0, mode);
103
        _mav_put_uint8_t(buf, 1, nav_mode);
104
        _mav_put_uint8_t(buf, 2, status);
105
        _mav_put_uint16_t(buf, 3, load);
106
        _mav_put_uint16_t(buf, 5, vbat);
107
        _mav_put_uint16_t(buf, 7, battery_remaining);
108
        _mav_put_uint16_t(buf, 9, packet_drop);
109
 
110
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 11);
111
#else
112
        mavlink_sys_status_t packet;
113
        packet.mode = mode;
114
        packet.nav_mode = nav_mode;
115
        packet.status = status;
116
        packet.load = load;
117
        packet.vbat = vbat;
118
        packet.battery_remaining = battery_remaining;
119
        packet.packet_drop = packet_drop;
120
 
121
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 11);
122
#endif
123
 
124
        msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
125
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 11);
126
}
127
 
128
/**
129
 * @brief Encode a sys_status struct into a message
130
 *
131
 * @param system_id ID of this system
132
 * @param component_id ID of this component (e.g. 200 for IMU)
133
 * @param msg The MAVLink message to compress the data into
134
 * @param sys_status C-struct to read the message contents from
135
 */
136
static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status)
137
{
138
        return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->mode, sys_status->nav_mode, sys_status->status, sys_status->load, sys_status->vbat, sys_status->battery_remaining, sys_status->packet_drop);
139
}
140
 
141
/**
142
 * @brief Send a sys_status message
143
 * @param chan MAVLink channel to send the message
144
 *
145
 * @param mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
146
 * @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM
147
 * @param status System status flag, see MAV_STATUS ENUM
148
 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
149
 * @param vbat Battery voltage, in millivolts (1 = 1 millivolt)
150
 * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 1000)
151
 * @param packet_drop Dropped packets (packets that were corrupted on reception on the MAV)
152
 */
153
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
154
 
155
static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint16_t battery_remaining, uint16_t packet_drop)
156
{
157
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
158
        char buf[11];
159
        _mav_put_uint8_t(buf, 0, mode);
160
        _mav_put_uint8_t(buf, 1, nav_mode);
161
        _mav_put_uint8_t(buf, 2, status);
162
        _mav_put_uint16_t(buf, 3, load);
163
        _mav_put_uint16_t(buf, 5, vbat);
164
        _mav_put_uint16_t(buf, 7, battery_remaining);
165
        _mav_put_uint16_t(buf, 9, packet_drop);
166
 
167
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, 11);
168
#else
169
        mavlink_sys_status_t packet;
170
        packet.mode = mode;
171
        packet.nav_mode = nav_mode;
172
        packet.status = status;
173
        packet.load = load;
174
        packet.vbat = vbat;
175
        packet.battery_remaining = battery_remaining;
176
        packet.packet_drop = packet_drop;
177
 
178
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, 11);
179
#endif
180
}
181
 
182
#endif
183
 
184
// MESSAGE SYS_STATUS UNPACKING
185
 
186
 
187
/**
188
 * @brief Get field mode from sys_status message
189
 *
190
 * @return System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
191
 */
192
static inline uint8_t mavlink_msg_sys_status_get_mode(const mavlink_message_t* msg)
193
{
194
        return _MAV_RETURN_uint8_t(msg,  0);
195
}
196
 
197
/**
198
 * @brief Get field nav_mode from sys_status message
199
 *
200
 * @return Navigation mode, see MAV_NAV_MODE ENUM
201
 */
202
static inline uint8_t mavlink_msg_sys_status_get_nav_mode(const mavlink_message_t* msg)
203
{
204
        return _MAV_RETURN_uint8_t(msg,  1);
205
}
206
 
207
/**
208
 * @brief Get field status from sys_status message
209
 *
210
 * @return System status flag, see MAV_STATUS ENUM
211
 */
212
static inline uint8_t mavlink_msg_sys_status_get_status(const mavlink_message_t* msg)
213
{
214
        return _MAV_RETURN_uint8_t(msg,  2);
215
}
216
 
217
/**
218
 * @brief Get field load from sys_status message
219
 *
220
 * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
221
 */
222
static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg)
223
{
224
        return _MAV_RETURN_uint16_t(msg,  3);
225
}
226
 
227
/**
228
 * @brief Get field vbat from sys_status message
229
 *
230
 * @return Battery voltage, in millivolts (1 = 1 millivolt)
231
 */
232
static inline uint16_t mavlink_msg_sys_status_get_vbat(const mavlink_message_t* msg)
233
{
234
        return _MAV_RETURN_uint16_t(msg,  5);
235
}
236
 
237
/**
238
 * @brief Get field battery_remaining from sys_status message
239
 *
240
 * @return Remaining battery energy: (0%: 0, 100%: 1000)
241
 */
242
static inline uint16_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg)
243
{
244
        return _MAV_RETURN_uint16_t(msg,  7);
245
}
246
 
247
/**
248
 * @brief Get field packet_drop from sys_status message
249
 *
250
 * @return Dropped packets (packets that were corrupted on reception on the MAV)
251
 */
252
static inline uint16_t mavlink_msg_sys_status_get_packet_drop(const mavlink_message_t* msg)
253
{
254
        return _MAV_RETURN_uint16_t(msg,  9);
255
}
256
 
257
/**
258
 * @brief Decode a sys_status message into a struct
259
 *
260
 * @param msg The message to decode
261
 * @param sys_status C-struct to decode the message contents into
262
 */
263
static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status)
264
{
265
#if MAVLINK_NEED_BYTE_SWAP
266
        sys_status->mode = mavlink_msg_sys_status_get_mode(msg);
267
        sys_status->nav_mode = mavlink_msg_sys_status_get_nav_mode(msg);
268
        sys_status->status = mavlink_msg_sys_status_get_status(msg);
269
        sys_status->load = mavlink_msg_sys_status_get_load(msg);
270
        sys_status->vbat = mavlink_msg_sys_status_get_vbat(msg);
271
        sys_status->battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg);
272
        sys_status->packet_drop = mavlink_msg_sys_status_get_packet_drop(msg);
273
#else
274
        memcpy(sys_status, _MAV_PAYLOAD(msg), 11);
275
#endif
276
}