4#define MAVLINK_MSG_ID_FENCE_POINT 160
7typedef struct __mavlink_fence_point_t {
10 uint8_t target_system;
11 uint8_t target_component;
14}) mavlink_fence_point_t;
16#define MAVLINK_MSG_ID_FENCE_POINT_LEN 12
17#define MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN 12
18#define MAVLINK_MSG_ID_160_LEN 12
19#define MAVLINK_MSG_ID_160_MIN_LEN 12
21#define MAVLINK_MSG_ID_FENCE_POINT_CRC 78
22#define MAVLINK_MSG_ID_160_CRC 78
26#if MAVLINK_COMMAND_24BIT
27#define MAVLINK_MESSAGE_INFO_FENCE_POINT { \
31 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_point_t, target_system) }, \
32 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fence_point_t, target_component) }, \
33 { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fence_point_t, idx) }, \
34 { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fence_point_t, count) }, \
35 { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_fence_point_t, lat) }, \
36 { "lng", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_fence_point_t, lng) }, \
40#define MAVLINK_MESSAGE_INFO_FENCE_POINT { \
43 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_point_t, target_system) }, \
44 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fence_point_t, target_component) }, \
45 { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fence_point_t, idx) }, \
46 { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fence_point_t, count) }, \
47 { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_fence_point_t, lat) }, \
48 { "lng", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_fence_point_t, lng) }, \
67static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
68 uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count,
float lat,
float lng)
70#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
71 char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN];
72 _mav_put_float(buf, 0, lat);
73 _mav_put_float(buf, 4, lng);
74 _mav_put_uint8_t(buf, 8, target_system);
75 _mav_put_uint8_t(buf, 9, target_component);
76 _mav_put_uint8_t(buf, 10, idx);
77 _mav_put_uint8_t(buf, 11, count);
79 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_POINT_LEN);
81 mavlink_fence_point_t packet;
84 packet.target_system = target_system;
85 packet.target_component = target_component;
89 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_POINT_LEN);
92 msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
93 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
110static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
111 mavlink_message_t* msg,
112 uint8_t target_system,uint8_t target_component,uint8_t idx,uint8_t count,
float lat,
float lng)
114#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
115 char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN];
116 _mav_put_float(buf, 0, lat);
117 _mav_put_float(buf, 4, lng);
118 _mav_put_uint8_t(buf, 8, target_system);
119 _mav_put_uint8_t(buf, 9, target_component);
120 _mav_put_uint8_t(buf, 10, idx);
121 _mav_put_uint8_t(buf, 11, count);
123 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_POINT_LEN);
125 mavlink_fence_point_t packet;
128 packet.target_system = target_system;
129 packet.target_component = target_component;
131 packet.count = count;
133 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_POINT_LEN);
136 msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
137 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
148static 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)
150 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);
162static inline uint16_t mavlink_msg_fence_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_fence_point_t* fence_point)
164 return mavlink_msg_fence_point_pack_chan(system_id, component_id, chan, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
178#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
180static 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)
182#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
183 char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN];
184 _mav_put_float(buf, 0, lat);
185 _mav_put_float(buf, 4, lng);
186 _mav_put_uint8_t(buf, 8, target_system);
187 _mav_put_uint8_t(buf, 9, target_component);
188 _mav_put_uint8_t(buf, 10, idx);
189 _mav_put_uint8_t(buf, 11, count);
191 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
193 mavlink_fence_point_t packet;
196 packet.target_system = target_system;
197 packet.target_component = target_component;
199 packet.count = count;
201 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (
const char *)&packet, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
210static inline void mavlink_msg_fence_point_send_struct(mavlink_channel_t chan,
const mavlink_fence_point_t* fence_point)
212#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
213 mavlink_msg_fence_point_send(chan, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
215 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (
const char *)fence_point, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
219#if MAVLINK_MSG_ID_FENCE_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
227static inline void mavlink_msg_fence_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count,
float lat,
float lng)
229#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
230 char *buf = (
char *)msgbuf;
231 _mav_put_float(buf, 0, lat);
232 _mav_put_float(buf, 4, lng);
233 _mav_put_uint8_t(buf, 8, target_system);
234 _mav_put_uint8_t(buf, 9, target_component);
235 _mav_put_uint8_t(buf, 10, idx);
236 _mav_put_uint8_t(buf, 11, count);
238 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
240 mavlink_fence_point_t *packet = (mavlink_fence_point_t *)msgbuf;
243 packet->target_system = target_system;
244 packet->target_component = target_component;
246 packet->count = count;
248 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (
const char *)packet, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
263static inline uint8_t mavlink_msg_fence_point_get_target_system(
const mavlink_message_t* msg)
265 return _MAV_RETURN_uint8_t(msg, 8);
273static inline uint8_t mavlink_msg_fence_point_get_target_component(
const mavlink_message_t* msg)
275 return _MAV_RETURN_uint8_t(msg, 9);
283static inline uint8_t mavlink_msg_fence_point_get_idx(
const mavlink_message_t* msg)
285 return _MAV_RETURN_uint8_t(msg, 10);
293static inline uint8_t mavlink_msg_fence_point_get_count(
const mavlink_message_t* msg)
295 return _MAV_RETURN_uint8_t(msg, 11);
303static inline float mavlink_msg_fence_point_get_lat(
const mavlink_message_t* msg)
305 return _MAV_RETURN_float(msg, 0);
313static inline float mavlink_msg_fence_point_get_lng(
const mavlink_message_t* msg)
315 return _MAV_RETURN_float(msg, 4);
324static inline void mavlink_msg_fence_point_decode(
const mavlink_message_t* msg, mavlink_fence_point_t* fence_point)
326#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
327 fence_point->lat = mavlink_msg_fence_point_get_lat(msg);
328 fence_point->lng = mavlink_msg_fence_point_get_lng(msg);
329 fence_point->target_system = mavlink_msg_fence_point_get_target_system(msg);
330 fence_point->target_component = mavlink_msg_fence_point_get_target_component(msg);
331 fence_point->idx = mavlink_msg_fence_point_get_idx(msg);
332 fence_point->count = mavlink_msg_fence_point_get_count(msg);
334 uint8_t len = msg->len < MAVLINK_MSG_ID_FENCE_POINT_LEN? msg->len : MAVLINK_MSG_ID_FENCE_POINT_LEN;
335 memset(fence_point, 0, MAVLINK_MSG_ID_FENCE_POINT_LEN);
336 memcpy(fence_point, _MAV_PAYLOAD(msg), len);