aboutsummaryrefslogtreecommitdiff
path: root/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h
diff options
context:
space:
mode:
Diffstat (limited to 'mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h')
-rw-r--r--mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h43
1 files changed, 31 insertions, 12 deletions
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h
index aae6fd206..100fabf16 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h
@@ -16,6 +16,9 @@ typedef struct __mavlink_safety_allowed_area_t
#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25
#define MAVLINK_MSG_ID_55_LEN 25
+#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC 3
+#define MAVLINK_MSG_ID_55_CRC 3
+
#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \
@@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, u
uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[25];
+ char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN];
_mav_put_float(buf, 0, p1x);
_mav_put_float(buf, 4, p1y);
_mav_put_float(buf, 8, p1z);
@@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, u
_mav_put_float(buf, 20, p2z);
_mav_put_uint8_t(buf, 24, frame);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#else
mavlink_safety_allowed_area_t packet;
packet.p1x = p1x;
@@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, u
packet.p2z = p2z;
packet.frame = frame;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA;
- return mavlink_finalize_message(msg, system_id, component_id, 25, 3);
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
+#endif
}
/**
@@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_
uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[25];
+ char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN];
_mav_put_float(buf, 0, p1x);
_mav_put_float(buf, 4, p1y);
_mav_put_float(buf, 8, p1z);
@@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_
_mav_put_float(buf, 20, p2z);
_mav_put_uint8_t(buf, 24, frame);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#else
mavlink_safety_allowed_area_t packet;
packet.p1x = p1x;
@@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_
packet.p2z = p2z;
packet.frame = frame;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 3);
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
+#endif
}
/**
@@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id,
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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[25];
+ char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN];
_mav_put_float(buf, 0, p1x);
_mav_put_float(buf, 4, p1y);
_mav_put_float(buf, 8, p1z);
@@ -164,7 +175,11 @@ static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan,
_mav_put_float(buf, 20, p2z);
_mav_put_uint8_t(buf, 24, frame);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, 25, 3);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
+#endif
#else
mavlink_safety_allowed_area_t packet;
packet.p1x = p1x;
@@ -175,7 +190,11 @@ static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan,
packet.p2z = p2z;
packet.frame = frame;
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, 25, 3);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
+#endif
#endif
}
@@ -271,6 +290,6 @@ static inline void mavlink_msg_safety_allowed_area_decode(const mavlink_message_
safety_allowed_area->p2z = mavlink_msg_safety_allowed_area_get_p2z(msg);
safety_allowed_area->frame = mavlink_msg_safety_allowed_area_get_frame(msg);
#else
- memcpy(safety_allowed_area, _MAV_PAYLOAD(msg), 25);
+ memcpy(safety_allowed_area, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#endif
}