Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE SYS_Stat PACKING
2
 
3
#define MAVLINK_MSG_ID_SYS_Stat 190
4
 
5
typedef struct __mavlink_sys_stat_t
6
{
7
 uint8_t gps; ///< gps status
8
 uint8_t act; ///< actuator status
9
 uint8_t mod; ///< module status
10
 uint8_t commRssi; ///< module status
11
} mavlink_sys_stat_t;
12
 
13
#define MAVLINK_MSG_ID_SYS_Stat_LEN 4
14
#define MAVLINK_MSG_ID_190_LEN 4
15
 
16
 
17
 
18
#define MAVLINK_MESSAGE_INFO_SYS_Stat { \
19
        "SYS_Stat", \
20
        4, \
21
        {  { "gps", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_sys_stat_t, gps) }, \
22
         { "act", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_sys_stat_t, act) }, \
23
         { "mod", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_sys_stat_t, mod) }, \
24
         { "commRssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_sys_stat_t, commRssi) }, \
25
         } \
26
}
27
 
28
 
29
/**
30
 * @brief Pack a sys_stat 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 gps gps status
36
 * @param act actuator status
37
 * @param mod module status
38
 * @param commRssi module status
39
 * @return length of the message in bytes (excluding serial stream start sign)
40
 */
41
static inline uint16_t mavlink_msg_sys_stat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42
                                                       uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi)
43
{
44
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
45
        char buf[4];
46
        _mav_put_uint8_t(buf, 0, gps);
47
        _mav_put_uint8_t(buf, 1, act);
48
        _mav_put_uint8_t(buf, 2, mod);
49
        _mav_put_uint8_t(buf, 3, commRssi);
50
 
51
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
52
#else
53
        mavlink_sys_stat_t packet;
54
        packet.gps = gps;
55
        packet.act = act;
56
        packet.mod = mod;
57
        packet.commRssi = commRssi;
58
 
59
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
60
#endif
61
 
62
        msg->msgid = MAVLINK_MSG_ID_SYS_Stat;
63
        return mavlink_finalize_message(msg, system_id, component_id, 4, 157);
64
}
65
 
66
/**
67
 * @brief Pack a sys_stat message on a channel
68
 * @param system_id ID of this system
69
 * @param component_id ID of this component (e.g. 200 for IMU)
70
 * @param chan The MAVLink channel this message was sent over
71
 * @param msg The MAVLink message to compress the data into
72
 * @param gps gps status
73
 * @param act actuator status
74
 * @param mod module status
75
 * @param commRssi module status
76
 * @return length of the message in bytes (excluding serial stream start sign)
77
 */
78
static inline uint16_t mavlink_msg_sys_stat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
79
                                                           mavlink_message_t* msg,
80
                                                           uint8_t gps,uint8_t act,uint8_t mod,uint8_t commRssi)
81
{
82
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
83
        char buf[4];
84
        _mav_put_uint8_t(buf, 0, gps);
85
        _mav_put_uint8_t(buf, 1, act);
86
        _mav_put_uint8_t(buf, 2, mod);
87
        _mav_put_uint8_t(buf, 3, commRssi);
88
 
89
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
90
#else
91
        mavlink_sys_stat_t packet;
92
        packet.gps = gps;
93
        packet.act = act;
94
        packet.mod = mod;
95
        packet.commRssi = commRssi;
96
 
97
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
98
#endif
99
 
100
        msg->msgid = MAVLINK_MSG_ID_SYS_Stat;
101
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 157);
102
}
103
 
104
/**
105
 * @brief Encode a sys_stat struct into a message
106
 *
107
 * @param system_id ID of this system
108
 * @param component_id ID of this component (e.g. 200 for IMU)
109
 * @param msg The MAVLink message to compress the data into
110
 * @param sys_stat C-struct to read the message contents from
111
 */
112
static inline uint16_t mavlink_msg_sys_stat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_stat_t* sys_stat)
113
{
114
        return mavlink_msg_sys_stat_pack(system_id, component_id, msg, sys_stat->gps, sys_stat->act, sys_stat->mod, sys_stat->commRssi);
115
}
116
 
117
/**
118
 * @brief Send a sys_stat message
119
 * @param chan MAVLink channel to send the message
120
 *
121
 * @param gps gps status
122
 * @param act actuator status
123
 * @param mod module status
124
 * @param commRssi module status
125
 */
126
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
127
 
128
static inline void mavlink_msg_sys_stat_send(mavlink_channel_t chan, uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi)
129
{
130
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
131
        char buf[4];
132
        _mav_put_uint8_t(buf, 0, gps);
133
        _mav_put_uint8_t(buf, 1, act);
134
        _mav_put_uint8_t(buf, 2, mod);
135
        _mav_put_uint8_t(buf, 3, commRssi);
136
 
137
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, buf, 4, 157);
138
#else
139
        mavlink_sys_stat_t packet;
140
        packet.gps = gps;
141
        packet.act = act;
142
        packet.mod = mod;
143
        packet.commRssi = commRssi;
144
 
145
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, (const char *)&packet, 4, 157);
146
#endif
147
}
148
 
149
#endif
150
 
151
// MESSAGE SYS_Stat UNPACKING
152
 
153
 
154
/**
155
 * @brief Get field gps from sys_stat message
156
 *
157
 * @return gps status
158
 */
159
static inline uint8_t mavlink_msg_sys_stat_get_gps(const mavlink_message_t* msg)
160
{
161
        return _MAV_RETURN_uint8_t(msg,  0);
162
}
163
 
164
/**
165
 * @brief Get field act from sys_stat message
166
 *
167
 * @return actuator status
168
 */
169
static inline uint8_t mavlink_msg_sys_stat_get_act(const mavlink_message_t* msg)
170
{
171
        return _MAV_RETURN_uint8_t(msg,  1);
172
}
173
 
174
/**
175
 * @brief Get field mod from sys_stat message
176
 *
177
 * @return module status
178
 */
179
static inline uint8_t mavlink_msg_sys_stat_get_mod(const mavlink_message_t* msg)
180
{
181
        return _MAV_RETURN_uint8_t(msg,  2);
182
}
183
 
184
/**
185
 * @brief Get field commRssi from sys_stat message
186
 *
187
 * @return module status
188
 */
189
static inline uint8_t mavlink_msg_sys_stat_get_commRssi(const mavlink_message_t* msg)
190
{
191
        return _MAV_RETURN_uint8_t(msg,  3);
192
}
193
 
194
/**
195
 * @brief Decode a sys_stat message into a struct
196
 *
197
 * @param msg The message to decode
198
 * @param sys_stat C-struct to decode the message contents into
199
 */
200
static inline void mavlink_msg_sys_stat_decode(const mavlink_message_t* msg, mavlink_sys_stat_t* sys_stat)
201
{
202
#if MAVLINK_NEED_BYTE_SWAP
203
        sys_stat->gps = mavlink_msg_sys_stat_get_gps(msg);
204
        sys_stat->act = mavlink_msg_sys_stat_get_act(msg);
205
        sys_stat->mod = mavlink_msg_sys_stat_get_mod(msg);
206
        sys_stat->commRssi = mavlink_msg_sys_stat_get_commRssi(msg);
207
#else
208
        memcpy(sys_stat, _MAV_PAYLOAD(msg), 4);
209
#endif
210
}