Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE FENCE_STATUS PACKING
2
 
3
#define MAVLINK_MSG_ID_FENCE_STATUS 162
4
 
5
typedef struct __mavlink_fence_status_t
6
{
7
 uint8_t breach_status; ///< 0 if currently inside fence, 1 if outside
8
 uint16_t breach_count; ///< number of fence breaches
9
 uint8_t breach_type; ///< last breach type (see FENCE_BREACH_* enum)
10
 uint32_t breach_time; ///< time of last breach in milliseconds since boot
11
} mavlink_fence_status_t;
12
 
13
#define MAVLINK_MSG_ID_FENCE_STATUS_LEN 8
14
#define MAVLINK_MSG_ID_162_LEN 8
15
 
16
 
17
 
18
#define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \
19
        "FENCE_STATUS", \
20
        4, \
21
        {  { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_fence_status_t, breach_status) }, \
22
         { "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 1, offsetof(mavlink_fence_status_t, breach_count) }, \
23
         { "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_fence_status_t, breach_type) }, \
24
         { "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_fence_status_t, breach_time) }, \
25
         } \
26
}
27
 
28
 
29
/**
30
 * @brief Pack a fence_status 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 breach_status 0 if currently inside fence, 1 if outside
36
 * @param breach_count number of fence breaches
37
 * @param breach_type last breach type (see FENCE_BREACH_* enum)
38
 * @param breach_time time of last breach in milliseconds since boot
39
 * @return length of the message in bytes (excluding serial stream start sign)
40
 */
41
static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42
                                                       uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
43
{
44
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
45
        char buf[8];
46
        _mav_put_uint8_t(buf, 0, breach_status);
47
        _mav_put_uint16_t(buf, 1, breach_count);
48
        _mav_put_uint8_t(buf, 3, breach_type);
49
        _mav_put_uint32_t(buf, 4, breach_time);
50
 
51
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
52
#else
53
        mavlink_fence_status_t packet;
54
        packet.breach_status = breach_status;
55
        packet.breach_count = breach_count;
56
        packet.breach_type = breach_type;
57
        packet.breach_time = breach_time;
58
 
59
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
60
#endif
61
 
62
        msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS;
63
        return mavlink_finalize_message(msg, system_id, component_id, 8);
64
}
65
 
66
/**
67
 * @brief Pack a fence_status 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 breach_status 0 if currently inside fence, 1 if outside
73
 * @param breach_count number of fence breaches
74
 * @param breach_type last breach type (see FENCE_BREACH_* enum)
75
 * @param breach_time time of last breach in milliseconds since boot
76
 * @return length of the message in bytes (excluding serial stream start sign)
77
 */
78
static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
79
                                                           mavlink_message_t* msg,
80
                                                           uint8_t breach_status,uint16_t breach_count,uint8_t breach_type,uint32_t breach_time)
81
{
82
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
83
        char buf[8];
84
        _mav_put_uint8_t(buf, 0, breach_status);
85
        _mav_put_uint16_t(buf, 1, breach_count);
86
        _mav_put_uint8_t(buf, 3, breach_type);
87
        _mav_put_uint32_t(buf, 4, breach_time);
88
 
89
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
90
#else
91
        mavlink_fence_status_t packet;
92
        packet.breach_status = breach_status;
93
        packet.breach_count = breach_count;
94
        packet.breach_type = breach_type;
95
        packet.breach_time = breach_time;
96
 
97
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
98
#endif
99
 
100
        msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS;
101
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8);
102
}
103
 
104
/**
105
 * @brief Encode a fence_status 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 fence_status C-struct to read the message contents from
111
 */
112
static inline uint16_t mavlink_msg_fence_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status)
113
{
114
        return mavlink_msg_fence_status_pack(system_id, component_id, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
115
}
116
 
117
/**
118
 * @brief Send a fence_status message
119
 * @param chan MAVLink channel to send the message
120
 *
121
 * @param breach_status 0 if currently inside fence, 1 if outside
122
 * @param breach_count number of fence breaches
123
 * @param breach_type last breach type (see FENCE_BREACH_* enum)
124
 * @param breach_time time of last breach in milliseconds since boot
125
 */
126
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
127
 
128
static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
129
{
130
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
131
        char buf[8];
132
        _mav_put_uint8_t(buf, 0, breach_status);
133
        _mav_put_uint16_t(buf, 1, breach_count);
134
        _mav_put_uint8_t(buf, 3, breach_type);
135
        _mav_put_uint32_t(buf, 4, breach_time);
136
 
137
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, 8);
138
#else
139
        mavlink_fence_status_t packet;
140
        packet.breach_status = breach_status;
141
        packet.breach_count = breach_count;
142
        packet.breach_type = breach_type;
143
        packet.breach_time = breach_time;
144
 
145
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)&packet, 8);
146
#endif
147
}
148
 
149
#endif
150
 
151
// MESSAGE FENCE_STATUS UNPACKING
152
 
153
 
154
/**
155
 * @brief Get field breach_status from fence_status message
156
 *
157
 * @return 0 if currently inside fence, 1 if outside
158
 */
159
static inline uint8_t mavlink_msg_fence_status_get_breach_status(const mavlink_message_t* msg)
160
{
161
        return _MAV_RETURN_uint8_t(msg,  0);
162
}
163
 
164
/**
165
 * @brief Get field breach_count from fence_status message
166
 *
167
 * @return number of fence breaches
168
 */
169
static inline uint16_t mavlink_msg_fence_status_get_breach_count(const mavlink_message_t* msg)
170
{
171
        return _MAV_RETURN_uint16_t(msg,  1);
172
}
173
 
174
/**
175
 * @brief Get field breach_type from fence_status message
176
 *
177
 * @return last breach type (see FENCE_BREACH_* enum)
178
 */
179
static inline uint8_t mavlink_msg_fence_status_get_breach_type(const mavlink_message_t* msg)
180
{
181
        return _MAV_RETURN_uint8_t(msg,  3);
182
}
183
 
184
/**
185
 * @brief Get field breach_time from fence_status message
186
 *
187
 * @return time of last breach in milliseconds since boot
188
 */
189
static inline uint32_t mavlink_msg_fence_status_get_breach_time(const mavlink_message_t* msg)
190
{
191
        return _MAV_RETURN_uint32_t(msg,  4);
192
}
193
 
194
/**
195
 * @brief Decode a fence_status message into a struct
196
 *
197
 * @param msg The message to decode
198
 * @param fence_status C-struct to decode the message contents into
199
 */
200
static inline void mavlink_msg_fence_status_decode(const mavlink_message_t* msg, mavlink_fence_status_t* fence_status)
201
{
202
#if MAVLINK_NEED_BYTE_SWAP
203
        fence_status->breach_status = mavlink_msg_fence_status_get_breach_status(msg);
204
        fence_status->breach_count = mavlink_msg_fence_status_get_breach_count(msg);
205
        fence_status->breach_type = mavlink_msg_fence_status_get_breach_type(msg);
206
        fence_status->breach_time = mavlink_msg_fence_status_get_breach_time(msg);
207
#else
208
        memcpy(fence_status, _MAV_PAYLOAD(msg), 8);
209
#endif
210
}