Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE FENCE_POINT PACKING
2
 
3
#define MAVLINK_MSG_ID_FENCE_POINT 160
4
 
5
typedef struct __mavlink_fence_point_t
6
{
7
 float lat; ///< Latitude of point
8
 float lng; ///< Longitude of point
9
 uint8_t target_system; ///< System ID
10
 uint8_t target_component; ///< Component ID
11
 uint8_t idx; ///< point index (first point is 1, 0 is for return point)
12
 uint8_t count; ///< total number of points (for sanity checking)
13
} mavlink_fence_point_t;
14
 
15
#define MAVLINK_MSG_ID_FENCE_POINT_LEN 12
16
#define MAVLINK_MSG_ID_160_LEN 12
17
 
18
 
19
 
20
#define MAVLINK_MESSAGE_INFO_FENCE_POINT { \
21
        "FENCE_POINT", \
22
        6, \
23
        {  { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_fence_point_t, lat) }, \
24
         { "lng", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_fence_point_t, lng) }, \
25
         { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_point_t, target_system) }, \
26
         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fence_point_t, target_component) }, \
27
         { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fence_point_t, idx) }, \
28
         { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fence_point_t, count) }, \
29
         } \
30
}
31
 
32
 
33
/**
34
 * @brief Pack a fence_point 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 idx point index (first point is 1, 0 is for return point)
42
 * @param count total number of points (for sanity checking)
43
 * @param lat Latitude of point
44
 * @param lng Longitude of point
45
 * @return length of the message in bytes (excluding serial stream start sign)
46
 */
47
static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
48
                                                       uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng)
49
{
50
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
51
        char buf[12];
52
        _mav_put_float(buf, 0, lat);
53
        _mav_put_float(buf, 4, lng);
54
        _mav_put_uint8_t(buf, 8, target_system);
55
        _mav_put_uint8_t(buf, 9, target_component);
56
        _mav_put_uint8_t(buf, 10, idx);
57
        _mav_put_uint8_t(buf, 11, count);
58
 
59
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
60
#else
61
        mavlink_fence_point_t packet;
62
        packet.lat = lat;
63
        packet.lng = lng;
64
        packet.target_system = target_system;
65
        packet.target_component = target_component;
66
        packet.idx = idx;
67
        packet.count = count;
68
 
69
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
70
#endif
71
 
72
        msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
73
        return mavlink_finalize_message(msg, system_id, component_id, 12, 78);
74
}
75
 
76
/**
77
 * @brief Pack a fence_point 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 idx point index (first point is 1, 0 is for return point)
85
 * @param count total number of points (for sanity checking)
86
 * @param lat Latitude of point
87
 * @param lng Longitude of point
88
 * @return length of the message in bytes (excluding serial stream start sign)
89
 */
90
static inline uint16_t mavlink_msg_fence_point_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,uint8_t idx,uint8_t count,float lat,float lng)
93
{
94
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
95
        char buf[12];
96
        _mav_put_float(buf, 0, lat);
97
        _mav_put_float(buf, 4, lng);
98
        _mav_put_uint8_t(buf, 8, target_system);
99
        _mav_put_uint8_t(buf, 9, target_component);
100
        _mav_put_uint8_t(buf, 10, idx);
101
        _mav_put_uint8_t(buf, 11, count);
102
 
103
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
104
#else
105
        mavlink_fence_point_t packet;
106
        packet.lat = lat;
107
        packet.lng = lng;
108
        packet.target_system = target_system;
109
        packet.target_component = target_component;
110
        packet.idx = idx;
111
        packet.count = count;
112
 
113
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
114
#endif
115
 
116
        msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
117
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 78);
118
}
119
 
120
/**
121
 * @brief Encode a fence_point 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 fence_point C-struct to read the message contents from
127
 */
128
static inline uint16_t mavlink_msg_fence_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_point_t* fence_point)
129
{
130
        return mavlink_msg_fence_point_pack(system_id, component_id, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
131
}
132
 
133
/**
134
 * @brief Send a fence_point 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 idx point index (first point is 1, 0 is for return point)
140
 * @param count total number of points (for sanity checking)
141
 * @param lat Latitude of point
142
 * @param lng Longitude of point
143
 */
144
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
145
 
146
static inline void mavlink_msg_fence_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng)
147
{
148
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
149
        char buf[12];
150
        _mav_put_float(buf, 0, lat);
151
        _mav_put_float(buf, 4, lng);
152
        _mav_put_uint8_t(buf, 8, target_system);
153
        _mav_put_uint8_t(buf, 9, target_component);
154
        _mav_put_uint8_t(buf, 10, idx);
155
        _mav_put_uint8_t(buf, 11, count);
156
 
157
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, 12, 78);
158
#else
159
        mavlink_fence_point_t packet;
160
        packet.lat = lat;
161
        packet.lng = lng;
162
        packet.target_system = target_system;
163
        packet.target_component = target_component;
164
        packet.idx = idx;
165
        packet.count = count;
166
 
167
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)&packet, 12, 78);
168
#endif
169
}
170
 
171
#endif
172
 
173
// MESSAGE FENCE_POINT UNPACKING
174
 
175
 
176
/**
177
 * @brief Get field target_system from fence_point message
178
 *
179
 * @return System ID
180
 */
181
static inline uint8_t mavlink_msg_fence_point_get_target_system(const mavlink_message_t* msg)
182
{
183
        return _MAV_RETURN_uint8_t(msg,  8);
184
}
185
 
186
/**
187
 * @brief Get field target_component from fence_point message
188
 *
189
 * @return Component ID
190
 */
191
static inline uint8_t mavlink_msg_fence_point_get_target_component(const mavlink_message_t* msg)
192
{
193
        return _MAV_RETURN_uint8_t(msg,  9);
194
}
195
 
196
/**
197
 * @brief Get field idx from fence_point message
198
 *
199
 * @return point index (first point is 1, 0 is for return point)
200
 */
201
static inline uint8_t mavlink_msg_fence_point_get_idx(const mavlink_message_t* msg)
202
{
203
        return _MAV_RETURN_uint8_t(msg,  10);
204
}
205
 
206
/**
207
 * @brief Get field count from fence_point message
208
 *
209
 * @return total number of points (for sanity checking)
210
 */
211
static inline uint8_t mavlink_msg_fence_point_get_count(const mavlink_message_t* msg)
212
{
213
        return _MAV_RETURN_uint8_t(msg,  11);
214
}
215
 
216
/**
217
 * @brief Get field lat from fence_point message
218
 *
219
 * @return Latitude of point
220
 */
221
static inline float mavlink_msg_fence_point_get_lat(const mavlink_message_t* msg)
222
{
223
        return _MAV_RETURN_float(msg,  0);
224
}
225
 
226
/**
227
 * @brief Get field lng from fence_point message
228
 *
229
 * @return Longitude of point
230
 */
231
static inline float mavlink_msg_fence_point_get_lng(const mavlink_message_t* msg)
232
{
233
        return _MAV_RETURN_float(msg,  4);
234
}
235
 
236
/**
237
 * @brief Decode a fence_point message into a struct
238
 *
239
 * @param msg The message to decode
240
 * @param fence_point C-struct to decode the message contents into
241
 */
242
static inline void mavlink_msg_fence_point_decode(const mavlink_message_t* msg, mavlink_fence_point_t* fence_point)
243
{
244
#if MAVLINK_NEED_BYTE_SWAP
245
        fence_point->lat = mavlink_msg_fence_point_get_lat(msg);
246
        fence_point->lng = mavlink_msg_fence_point_get_lng(msg);
247
        fence_point->target_system = mavlink_msg_fence_point_get_target_system(msg);
248
        fence_point->target_component = mavlink_msg_fence_point_get_target_component(msg);
249
        fence_point->idx = mavlink_msg_fence_point_get_idx(msg);
250
        fence_point->count = mavlink_msg_fence_point_get_count(msg);
251
#else
252
        memcpy(fence_point, _MAV_PAYLOAD(msg), 12);
253
#endif
254
}