3 #define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55
16 #define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25
17 #define MAVLINK_MSG_ID_55_LEN 25
19 #define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC 3
20 #define MAVLINK_MSG_ID_55_CRC 3
24 #define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \
25 "SAFETY_ALLOWED_AREA", \
27 { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \
28 { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \
29 { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \
30 { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \
31 { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \
32 { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \
33 { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \
53 static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
54 uint8_t frame,
float p1x,
float p1y,
float p1z,
float p2x,
float p2y,
float p2z)
56 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
103 static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
104 mavlink_message_t* msg,
105 uint8_t frame,
float p1x,
float p1y,
float p1z,
float p2x,
float p2y,
float p2z)
107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
126 packet.
frame = frame;
132 #if MAVLINK_CRC_EXTRA
147 static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_safety_allowed_area_t* safety_allowed_area)
149 return mavlink_msg_safety_allowed_area_pack(system_id, component_id, msg, safety_allowed_area->
frame, safety_allowed_area->
p1x, safety_allowed_area->
p1y, safety_allowed_area->
p1z, safety_allowed_area->
p2x, safety_allowed_area->
p2y, safety_allowed_area->
p2z);
161 static inline uint16_t mavlink_msg_safety_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_safety_allowed_area_t* safety_allowed_area)
163 return mavlink_msg_safety_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_allowed_area->
frame, safety_allowed_area->
p1x, safety_allowed_area->
p1y, safety_allowed_area->
p1z, safety_allowed_area->
p2x, safety_allowed_area->
p2y, safety_allowed_area->
p2z);
178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
180 static inline void mavlink_msg_safety_allowed_area_send(
mavlink_channel_t chan, uint8_t frame,
float p1x,
float p1y,
float p1z,
float p2x,
float p2y,
float p2z)
182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
192 #if MAVLINK_CRC_EXTRA
205 packet.
frame = frame;
207 #if MAVLINK_CRC_EXTRA
215 #if MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
223 static inline void mavlink_msg_safety_allowed_area_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint8_t frame,
float p1x,
float p1y,
float p1z,
float p2x,
float p2y,
float p2z)
225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
226 char *buf = (
char *)msgbuf;
235 #if MAVLINK_CRC_EXTRA
248 packet->
frame = frame;
250 #if MAVLINK_CRC_EXTRA
269 static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(
const mavlink_message_t* msg)
279 static inline float mavlink_msg_safety_allowed_area_get_p1x(
const mavlink_message_t* msg)
281 return _MAV_RETURN_float(msg, 0);
289 static inline float mavlink_msg_safety_allowed_area_get_p1y(
const mavlink_message_t* msg)
291 return _MAV_RETURN_float(msg, 4);
299 static inline float mavlink_msg_safety_allowed_area_get_p1z(
const mavlink_message_t* msg)
301 return _MAV_RETURN_float(msg, 8);
309 static inline float mavlink_msg_safety_allowed_area_get_p2x(
const mavlink_message_t* msg)
311 return _MAV_RETURN_float(msg, 12);
319 static inline float mavlink_msg_safety_allowed_area_get_p2y(
const mavlink_message_t* msg)
321 return _MAV_RETURN_float(msg, 16);
329 static inline float mavlink_msg_safety_allowed_area_get_p2z(
const mavlink_message_t* msg)
331 return _MAV_RETURN_float(msg, 20);
342 #if MAVLINK_NEED_BYTE_SWAP
343 safety_allowed_area->
p1x = mavlink_msg_safety_allowed_area_get_p1x(msg);
344 safety_allowed_area->
p1y = mavlink_msg_safety_allowed_area_get_p1y(msg);
345 safety_allowed_area->
p1z = mavlink_msg_safety_allowed_area_get_p1z(msg);
346 safety_allowed_area->
p2x = mavlink_msg_safety_allowed_area_get_p2x(msg);
347 safety_allowed_area->
p2y = mavlink_msg_safety_allowed_area_get_p2y(msg);
348 safety_allowed_area->
p2z = mavlink_msg_safety_allowed_area_get_p2z(msg);
349 safety_allowed_area->
frame = mavlink_msg_safety_allowed_area_get_frame(msg);
float p2x
x position 2 / Latitude 2
Definition: mavlink_msg_safety_allowed_area.h:10
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN
Definition: mavlink_msg_safety_allowed_area.h:16
float p1x
x position 1 / Latitude 1
Definition: mavlink_msg_safety_allowed_area.h:7
float p1z
z position 1 / Altitude 1
Definition: mavlink_msg_safety_allowed_area.h:9
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA
Definition: mavlink_msg_safety_allowed_area.h:3
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
float p2y
y position 2 / Longitude 2
Definition: mavlink_msg_safety_allowed_area.h:11
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
uint8_t frame
Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
Definition: mavlink_msg_safety_allowed_area.h:13
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
float p1y
y position 1 / Longitude 1
Definition: mavlink_msg_safety_allowed_area.h:8
Definition: mavlink_msg_safety_allowed_area.h:5
#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC
Definition: mavlink_msg_safety_allowed_area.h:19
struct __mavlink_safety_allowed_area_t mavlink_safety_allowed_area_t
float p2z
z position 2 / Altitude 2
Definition: mavlink_msg_safety_allowed_area.h:12
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71