aboutsummaryrefslogtreecommitdiff
path: root/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-07-04 15:40:20 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-07-04 15:40:20 +0200
commit9aee41932458bf85473334cb430c1b00607dd7f4 (patch)
treee890a7d893ac737549056f23148eea0392ff90fe /mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h
parent5691c64ff068b849319e714d9719079bd4bc14d2 (diff)
downloadpx4-firmware-9aee41932458bf85473334cb430c1b00607dd7f4.tar.gz
px4-firmware-9aee41932458bf85473334cb430c1b00607dd7f4.tar.bz2
px4-firmware-9aee41932458bf85473334cb430c1b00607dd7f4.zip
Updated mavlink version, massive improvements in mission lib, fixes to HIL (state and sensor level)
Diffstat (limited to 'mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h')
-rw-r--r--mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h43
1 files changed, 31 insertions, 12 deletions
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h
index b31319c74..b3c4706ee 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h
@@ -15,6 +15,9 @@ typedef struct __mavlink_fence_point_t
#define MAVLINK_MSG_ID_FENCE_POINT_LEN 12
#define MAVLINK_MSG_ID_160_LEN 12
+#define MAVLINK_MSG_ID_FENCE_POINT_CRC 78
+#define MAVLINK_MSG_ID_160_CRC 78
+
#define MAVLINK_MESSAGE_INFO_FENCE_POINT { \
@@ -48,7 +51,7 @@ static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t c
uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[12];
+ char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN];
_mav_put_float(buf, 0, lat);
_mav_put_float(buf, 4, lng);
_mav_put_uint8_t(buf, 8, target_system);
@@ -56,7 +59,7 @@ static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t c
_mav_put_uint8_t(buf, 10, idx);
_mav_put_uint8_t(buf, 11, count);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_POINT_LEN);
#else
mavlink_fence_point_t packet;
packet.lat = lat;
@@ -66,11 +69,15 @@ static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t c
packet.idx = idx;
packet.count = count;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_POINT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
- return mavlink_finalize_message(msg, system_id, component_id, 12, 78);
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_POINT_LEN);
+#endif
}
/**
@@ -92,7 +99,7 @@ static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint
uint8_t target_system,uint8_t target_component,uint8_t idx,uint8_t count,float lat,float lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[12];
+ char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN];
_mav_put_float(buf, 0, lat);
_mav_put_float(buf, 4, lng);
_mav_put_uint8_t(buf, 8, target_system);
@@ -100,7 +107,7 @@ static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint
_mav_put_uint8_t(buf, 10, idx);
_mav_put_uint8_t(buf, 11, count);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_POINT_LEN);
#else
mavlink_fence_point_t packet;
packet.lat = lat;
@@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint
packet.idx = idx;
packet.count = count;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_POINT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 78);
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_POINT_LEN);
+#endif
}
/**
@@ -146,7 +157,7 @@ static inline uint16_t mavlink_msg_fence_point_encode(uint8_t system_id, uint8_t
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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[12];
+ char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN];
_mav_put_float(buf, 0, lat);
_mav_put_float(buf, 4, lng);
_mav_put_uint8_t(buf, 8, target_system);
@@ -154,7 +165,11 @@ static inline void mavlink_msg_fence_point_send(mavlink_channel_t chan, uint8_t
_mav_put_uint8_t(buf, 10, idx);
_mav_put_uint8_t(buf, 11, count);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, 12, 78);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_LEN);
+#endif
#else
mavlink_fence_point_t packet;
packet.lat = lat;
@@ -164,7 +179,11 @@ static inline void mavlink_msg_fence_point_send(mavlink_channel_t chan, uint8_t
packet.idx = idx;
packet.count = count;
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)&packet, 12, 78);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)&packet, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)&packet, MAVLINK_MSG_ID_FENCE_POINT_LEN);
+#endif
#endif
}
@@ -249,6 +268,6 @@ static inline void mavlink_msg_fence_point_decode(const mavlink_message_t* msg,
fence_point->idx = mavlink_msg_fence_point_get_idx(msg);
fence_point->count = mavlink_msg_fence_point_get_count(msg);
#else
- memcpy(fence_point, _MAV_PAYLOAD(msg), 12);
+ memcpy(fence_point, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FENCE_POINT_LEN);
#endif
}