aboutsummaryrefslogtreecommitdiff
path: root/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h
diff options
context:
space:
mode:
Diffstat (limited to 'mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h')
-rw-r--r--mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h61
1 files changed, 47 insertions, 14 deletions
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h
index 9bb1e3369..4debb6e66 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h
@@ -15,6 +15,9 @@ typedef struct __mavlink_omnidirectional_flow_t
#define MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN 54
#define MAVLINK_MSG_ID_106_LEN 54
+#define MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC 211
+#define MAVLINK_MSG_ID_106_CRC 211
+
#define MAVLINK_MSG_OMNIDIRECTIONAL_FLOW_FIELD_LEFT_LEN 10
#define MAVLINK_MSG_OMNIDIRECTIONAL_FLOW_FIELD_RIGHT_LEN 10
@@ -49,14 +52,14 @@ static inline uint16_t mavlink_msg_omnidirectional_flow_pack(uint8_t system_id,
uint64_t time_usec, uint8_t sensor_id, const int16_t *left, const int16_t *right, uint8_t quality, float front_distance_m)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[54];
+ char buf[MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, front_distance_m);
_mav_put_uint8_t(buf, 52, sensor_id);
_mav_put_uint8_t(buf, 53, quality);
_mav_put_int16_t_array(buf, 12, left, 10);
_mav_put_int16_t_array(buf, 32, right, 10);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 54);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
#else
mavlink_omnidirectional_flow_t packet;
packet.time_usec = time_usec;
@@ -65,18 +68,22 @@ static inline uint16_t mavlink_msg_omnidirectional_flow_pack(uint8_t system_id,
packet.quality = quality;
mav_array_memcpy(packet.left, left, sizeof(int16_t)*10);
mav_array_memcpy(packet.right, right, sizeof(int16_t)*10);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 54);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW;
- return mavlink_finalize_message(msg, system_id, component_id, 54, 211);
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
+#endif
}
/**
* @brief Pack a omnidirectional_flow message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param sensor_id Sensor ID
@@ -91,14 +98,14 @@ static inline uint16_t mavlink_msg_omnidirectional_flow_pack_chan(uint8_t system
uint64_t time_usec,uint8_t sensor_id,const int16_t *left,const int16_t *right,uint8_t quality,float front_distance_m)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[54];
+ char buf[MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, front_distance_m);
_mav_put_uint8_t(buf, 52, sensor_id);
_mav_put_uint8_t(buf, 53, quality);
_mav_put_int16_t_array(buf, 12, left, 10);
_mav_put_int16_t_array(buf, 32, right, 10);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 54);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
#else
mavlink_omnidirectional_flow_t packet;
packet.time_usec = time_usec;
@@ -107,15 +114,19 @@ static inline uint16_t mavlink_msg_omnidirectional_flow_pack_chan(uint8_t system
packet.quality = quality;
mav_array_memcpy(packet.left, left, sizeof(int16_t)*10);
mav_array_memcpy(packet.right, right, sizeof(int16_t)*10);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 54);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 54, 211);
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
+#endif
}
/**
- * @brief Encode a omnidirectional_flow struct into a message
+ * @brief Encode a omnidirectional_flow struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -128,6 +139,20 @@ static inline uint16_t mavlink_msg_omnidirectional_flow_encode(uint8_t system_id
}
/**
+ * @brief Encode a omnidirectional_flow struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param omnidirectional_flow C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_omnidirectional_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_omnidirectional_flow_t* omnidirectional_flow)
+{
+ return mavlink_msg_omnidirectional_flow_pack_chan(system_id, component_id, chan, msg, omnidirectional_flow->time_usec, omnidirectional_flow->sensor_id, omnidirectional_flow->left, omnidirectional_flow->right, omnidirectional_flow->quality, omnidirectional_flow->front_distance_m);
+}
+
+/**
* @brief Send a omnidirectional_flow message
* @param chan MAVLink channel to send the message
*
@@ -143,14 +168,18 @@ static inline uint16_t mavlink_msg_omnidirectional_flow_encode(uint8_t system_id
static inline void mavlink_msg_omnidirectional_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, const int16_t *left, const int16_t *right, uint8_t quality, float front_distance_m)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[54];
+ char buf[MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, front_distance_m);
_mav_put_uint8_t(buf, 52, sensor_id);
_mav_put_uint8_t(buf, 53, quality);
_mav_put_int16_t_array(buf, 12, left, 10);
_mav_put_int16_t_array(buf, 32, right, 10);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, 54, 211);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
+#endif
#else
mavlink_omnidirectional_flow_t packet;
packet.time_usec = time_usec;
@@ -159,7 +188,11 @@ static inline void mavlink_msg_omnidirectional_flow_send(mavlink_channel_t chan,
packet.quality = quality;
mav_array_memcpy(packet.left, left, sizeof(int16_t)*10);
mav_array_memcpy(packet.right, right, sizeof(int16_t)*10);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (const char *)&packet, 54, 211);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
+#endif
#endif
}
@@ -244,6 +277,6 @@ static inline void mavlink_msg_omnidirectional_flow_decode(const mavlink_message
omnidirectional_flow->sensor_id = mavlink_msg_omnidirectional_flow_get_sensor_id(msg);
omnidirectional_flow->quality = mavlink_msg_omnidirectional_flow_get_quality(msg);
#else
- memcpy(omnidirectional_flow, _MAV_PAYLOAD(msg), 54);
+ memcpy(omnidirectional_flow, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
#endif
}