aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h42
-rw-r--r--mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status_var.h318
-rw-r--r--mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h100
-rw-r--r--mavlink/include/mavlink/v1.0/protocol.h16
4 files changed, 408 insertions, 68 deletions
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h
index 28d6b57d1..719abcce8 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h
@@ -10,11 +10,20 @@ typedef struct __mavlink_gps_status_t
uint8_t satellite_elevation[20]; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite
uint8_t satellite_azimuth[20]; ///< Direction of satellite, 0: 0 deg, 255: 360 deg.
uint8_t satellite_snr[20]; ///< Signal to noise ratio of satellite
+ uint8_t _field_len_satellite_prn;
+ uint8_t _field_len_satellite_used;
+ uint8_t _field_len_satellite_elevation;
+ uint8_t _field_len_satellite_azimuth;
+ uint8_t _field_len_satellite_snr;
} mavlink_gps_status_t;
+#define MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES 5
+
#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101
#define MAVLINK_MSG_ID_25_LEN 101
+#define MAVLINK_MSG_ID_GPS_STATUS_FIXED_LEN 1
+
#define MAVLINK_MSG_ID_GPS_STATUS_CRC 23
#define MAVLINK_MSG_ID_25_CRC 23
@@ -28,11 +37,16 @@ typedef struct __mavlink_gps_status_t
"GPS_STATUS", \
6, \
{ { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \
- { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \
- { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \
- { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \
- { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \
- { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \
+ { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, -1, -1, -1 }, \
+ { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, -2, -2, -2 }, \
+ { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, -3, -3, -3 }, \
+ { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, -4, -4, -4 }, \
+ { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, -5, -5, -5 }, \
+ { "_field_len_satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 0, -1, 1 } \
+ { "_field_len_satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 0, -2, 1 } \
+ { "_field_len_satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 0, -3, 1 } \
+ { "_field_len_satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 0, -4, 1 } \
+ { "_field_len_satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 0, -5, 1 } \
} \
}
@@ -272,6 +286,19 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_me
*/
static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status)
{
+ /* first get the length fields */
+ gps_status->_field_len_satellite_prn = _MAV_RETURN_uint8_t(msg, msg->len - MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES + 0);
+ gps_status->_field_len_satellite_used = _MAV_RETURN_uint8_t(msg, msg->len - MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES + 1);
+ gps_status->_field_len_satellite_elevation = _MAV_RETURN_uint8_t(msg, msg->len - MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES + 2);
+ gps_status->_field_len_satellite_azimuth = _MAV_RETURN_uint8_t(msg, msg->len - MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES + 3);
+ gps_status->_field_len_satellite_snr = _MAV_RETURN_uint8_t(msg, msg->len - MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES + 4);
+
+ uint16_t varlengths = gps_status->_field_len_satellite_prn +
+ gps_status->_field_len_satellite_used +
+ gps_status->_field_len_satellite_elevation +
+ gps_status->_field_len_satellite_azimuth +
+ gps_status->_field_len_satellite_snr;
+
#if MAVLINK_NEED_BYTE_SWAP
gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg);
mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn);
@@ -280,6 +307,9 @@ static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, m
mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth);
mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr);
#else
- memcpy(gps_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_STATUS_LEN);
+ memcpy(gps_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_STATUS_FIXED_LEN);
#endif
+
+ // xxx decode rest
+
}
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status_var.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status_var.h
new file mode 100644
index 000000000..82f65a337
--- /dev/null
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status_var.h
@@ -0,0 +1,318 @@
+// MESSAGE gps_status_var PACKING
+
+#define MAVLINK_MSG_ID_GPS_STATUS_VAR 25
+
+typedef struct __mavlink_gps_status_var_t
+{
+ uint8_t satellites_visible; ///< Number of satellites visible
+ uint8_t satellite_prn[20]; ///< Global satellite ID
+ uint8_t satellite_used[20]; ///< 0: Satellite not used, 1: used for localization
+ uint8_t satellite_elevation[20]; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite
+ uint8_t satellite_azimuth[20]; ///< Direction of satellite, 0: 0 deg, 255: 360 deg.
+ uint8_t satellite_snr[20]; ///< Signal to noise ratio of satellite
+ uint8_t satellite_prn_len; ///< [field length for] Global satellite ID
+ uint8_t satellite_used_len; ///< [field length for] 0: Satellite not used, 1: used for localization
+ uint8_t satellite_elevation_len; ///< [field length for] Elevation (0: right on top of receiver, 90: on the horizon) of satellite
+ uint8_t satellite_azimuth_len; ///< [field length for] Direction of satellite, 0: 0 deg, 255: 360 deg.
+ uint8_t satellite_snr_len; ///< [field length for] Signal to noise ratio of satellite
+} mavlink_gps_status_var_t;
+
+#define MAVLINK_MSG_ID_GPS_STATUS_VAR_LEN 106
+#define MAVLINK_MSG_ID_25_LEN 106
+
+#define MAVLINK_MSG_GPS_STATUS_VAR_FIELD_SATELLITE_PRN_LEN 20
+#define MAVLINK_MSG_GPS_STATUS_VAR_FIELD_SATELLITE_USED_LEN 20
+#define MAVLINK_MSG_GPS_STATUS_VAR_FIELD_SATELLITE_ELEVATION_LEN 20
+#define MAVLINK_MSG_GPS_STATUS_VAR_FIELD_SATELLITE_AZIMUTH_LEN 20
+#define MAVLINK_MSG_GPS_STATUS_VAR_FIELD_SATELLITE_SNR_LEN 20
+
+#define MAVLINK_MESSAGE_INFO_GPS_STATUS_VAR { \
+ "GPS_STATUS", \
+ 11, \
+ { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_var_t, satellites_visible) }, \
+ { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_var_t, satellite_prn) }, \
+ { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_var_t, satellite_used) }, \
+ { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_var_t, satellite_elevation) }, \
+ { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_var_t, satellite_azimuth) }, \
+ { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_var_t, satellite_snr) }, \
+ { "satellite_prn_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_gps_status_var_t, satellite_prn_len) }, \
+ { "satellite_used_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 83, offsetof(mavlink_gps_status_var_t, satellite_used_len) }, \
+ { "satellite_elevation_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 84, offsetof(mavlink_gps_status_var_t, satellite_elevation_len) }, \
+ { "satellite_azimuth_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 85, offsetof(mavlink_gps_status_var_t, satellite_azimuth_len) }, \
+ { "satellite_snr_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 86, offsetof(mavlink_gps_status_var_t, satellite_snr_len) }, \
+ } \
+}
+
+/**
+ * @brief Pack a gps_status_var message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param satellites_visible Number of satellites visible
+ * @param satellite_prn Global satellite ID
+ * @param satellite_used 0: Satellite not used, 1: used for localization
+ * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
+ * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
+ * @param satellite_snr Signal to noise ratio of satellite
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t satellites_visible, const uint8_t *satellite_prn, uint8_t satellite_prn_len, const uint8_t *satellite_used, uint8_t satellite_used_len, const uint8_t *satellite_elevation, uint8_t satellite_elevation_len, const uint8_t *satellite_azimuth, uint8_t satellite_azimuth_len, const uint8_t *satellite_snr, uint8_t satellite_snr_len)
+{
+ char buf[106];
+ _mav_put_uint8_t(buf, 0, satellites_visible);
+ _mav_put_uint8_t_array(buf, 1, satellite_prn, satellite_prn_len);
+ _mav_put_uint8_t_array(buf, 1 + satellite_prn_len, satellite_used, satellite_used_len);
+ _mav_put_uint8_t_array(buf, 1 + satellite_prn_len + satellite_used_len, satellite_elevation, satellite_elevation_len);
+ _mav_put_uint8_t_array(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len, satellite_azimuth, satellite_azimuth_len);
+ _mav_put_uint8_t_array(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len, satellite_snr, satellite_snr_len);
+ /* length fields sorted in the same order as the arrays, but at the end of the message */
+ _mav_put_uint8_t(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len, satellite_prn_len);
+ _mav_put_uint8_t(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len + 1, satellite_used_len);
+ _mav_put_uint8_t(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len + 2, satellite_elevation_len);
+ _mav_put_uint8_t(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len + 3, satellite_azimuth_len);
+ _mav_put_uint8_t(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len + 4, satellite_snr_len);
+ /* calculate checksum and send */
+
+ msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
+ return mavlink_finalize_message(msg, system_id, component_id, 106, 23);
+}
+
+/**
+ * @brief Pack a gps_status_var 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 msg The MAVLink message to compress the data into
+ * @param satellites_visible Number of satellites visible
+ * @param satellite_prn Global satellite ID
+ * @param satellite_used 0: Satellite not used, 1: used for localization
+ * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
+ * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
+ * @param satellite_snr Signal to noise ratio of satellite
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t satellites_visible,const uint8_t *satellite_prn,const uint8_t *satellite_used,const uint8_t *satellite_elevation,const uint8_t *satellite_azimuth,const uint8_t *satellite_snr)
+{
+ char buf[106];
+ _mav_put_uint8_t(buf, 0, satellites_visible);
+ _mav_put_uint8_t_array(buf, 1, satellite_prn, satellite_prn_len);
+ _mav_put_uint8_t_array(buf, 1 + satellite_prn_len, satellite_used, satellite_used_len);
+ _mav_put_uint8_t_array(buf, 1 + satellite_prn_len + satellite_used_len, satellite_elevation, satellite_elevation_len);
+ _mav_put_uint8_t_array(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len, satellite_azimuth, satellite_azimuth_len);
+ _mav_put_uint8_t_array(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len, satellite_snr, satellite_snr_len);
+ /* length fields sorted in the same order as the arrays, but at the end of the message */
+ _mav_put_uint8_t(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len, satellite_prn_len);
+ _mav_put_uint8_t(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len + 1, satellite_used_len);
+ _mav_put_uint8_t(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len + 2, satellite_elevation_len);
+ _mav_put_uint8_t(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len + 3, satellite_azimuth_len);
+ _mav_put_uint8_t(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len + 4, satellite_snr_len);
+ /* calculate checksum and send */
+
+ msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 106, 23);
+}
+
+/**
+ * @brief Encode a gps_status_var struct into a message
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param gps_status_var C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gps_status_var_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_var_t* gps_status)
+{
+ return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellites_visible_len, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr);
+}
+
+/**
+ * @brief Send a gps_status_var message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param satellites_visible Number of satellites visible
+ * @param satellite_prn Global satellite ID
+ * @param satellite_used 0: Satellite not used, 1: used for localization
+ * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
+ * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
+ * @param satellite_snr Signal to noise ratio of satellite
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gps_status_var_send(mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, uint8_t satellite_prn_len, const uint8_t *satellite_used, uint8_t satellite_used_len, const uint8_t *satellite_elevation, uint8_t satellite_elevation_len, const uint8_t *satellite_azimuth, uint8_t satellite_azimuth_len, const uint8_t *satellite_snr, uint8_t satellite_snr_len)
+{
+ char buf[106];
+ _mav_put_uint8_t(buf, 0, satellites_visible);
+ _mav_put_uint8_t_array(buf, 1, satellite_prn, satellite_prn_len);
+ _mav_put_uint8_t_array(buf, 1 + satellite_prn_len, satellite_used, satellite_used_len);
+ _mav_put_uint8_t_array(buf, 1 + satellite_prn_len + satellite_used_len, satellite_elevation, satellite_elevation_len);
+ _mav_put_uint8_t_array(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len, satellite_azimuth, satellite_azimuth_len);
+ _mav_put_uint8_t_array(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len, satellite_snr, satellite_snr_len);
+ /* length fields sorted in the same order as the arrays, but at the end of the message */
+ _mav_put_uint8_t(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len, satellite_prn_len);
+ _mav_put_uint8_t(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len + 1, satellite_used_len);
+ _mav_put_uint8_t(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len + 2, satellite_elevation_len);
+ _mav_put_uint8_t(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len + 3, satellite_azimuth_len);
+ _mav_put_uint8_t(buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len + 4, satellite_snr_len);
+ /* calculate checksum and send */
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, 1 + satellite_prn_len + satellite_used_len + satellite_elevation_len + satellite_azimuth_len + satellite_snr_len + 5, 23);
+}
+
+#endif
+
+// MESSAGE gps_status_var UNPACKING
+
+
+/**
+ * @brief Get field satellites_visible from gps_status_var message
+ *
+ * @return Number of satellites visible
+ */
+static inline uint8_t mavlink_msg_gps_status_var_get_satellites_visible(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field satellite_prn from gps_status_var message
+ *
+ * @return Global satellite ID
+ */
+static inline uint16_t mavlink_msg_gps_status_var_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn)
+{
+ return _MAV_RETURN_uint8_t_array(msg, satellite_prn, mavlink_msg_gps_status_var_get_satellite_prn_len(msg), 1);
+}
+
+/**
+ * @brief Get field satellite_used from gps_status_var message
+ *
+ * @return 0: Satellite not used, 1: used for localization
+ */
+static inline uint16_t mavlink_msg_gps_status_var_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used)
+{
+ return _MAV_RETURN_uint8_t_array(msg, satellite_used, mavlink_msg_gps_status_var_get_satellite_used_len(msg), 1 + mavlink_msg_gps_status_var_get_satellite_prn_len(msg));
+}
+
+/**
+ * @brief Get field satellite_elevation from gps_status_var message
+ *
+ * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite
+ */
+static inline uint16_t mavlink_msg_gps_status_var_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation)
+{
+ return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, mavlink_msg_gps_status_var_get_satellite_elevation_len(msg), 1 + mavlink_msg_gps_status_var_get_satellite_prn_len(msg) + mavlink_msg_gps_status_var_get_satellite_used_len(msg));
+}
+
+/**
+ * @brief Get field satellite_azimuth from gps_status_var message
+ *
+ * @return Direction of satellite, 0: 0 deg, 255: 360 deg.
+ */
+static inline uint16_t mavlink_msg_gps_status_var_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth)
+{
+ return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, mavlink_msg_gps_status_var_get_satellite_azimuth_len(msg), 1 + mavlink_msg_gps_status_var_get_satellite_prn_len(msg) + mavlink_msg_gps_status_var_get_satellite_used_len(msg) + mavlink_msg_gps_status_var_get_satellite_elevation_len(msg);
+}
+
+/**
+ * @brief Get field satellite_snr from gps_status_var message
+ *
+ * @return Signal to noise ratio of satellite
+ */
+static inline uint16_t mavlink_msg_gps_status_var_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr)
+{
+ return _MAV_RETURN_uint8_t_array(msg, satellite_snr, mavlink_msg_gps_status_var_get_satellite_snr_len(msg), 1 + mavlink_msg_gps_status_var_get_satellite_prn_len(msg) + mavlink_msg_gps_status_var_get_satellite_used_len(msg) + mavlink_msg_gps_status_var_get_satellite_elevation_len(msg) + mavlink_msg_gps_status_var_get_satellite_azimuth_len(msg);
+}
+
+/**
+ * @brief Get the length of field satellite_prn from gps_status_var message
+ *
+ * @return Number of items in the array
+ */
+static inline uint8_t mavlink_msg_gps_status_var_get_satellite_prn_len(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, msg->len - 5);
+}
+
+/**
+ * @brief Get the length of field satellite_used from gps_status_var message
+ *
+ * @return Number of items in the array
+ */
+static inline uint8_t mavlink_msg_gps_status_var_get_satellite_used_len(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, msg->len - 4);
+}
+
+/**
+ * @brief Get the length of field satellite_elevation from gps_status_var message
+ *
+ * @return Number of items in the array
+ */
+static inline uint8_t mavlink_msg_gps_status_var_get_satellite_elevation_len(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, msg->len - 3);
+}
+
+/**
+ * @brief Get the length of field satellite_azimuth from gps_status_var message
+ *
+ * @return Number of items in the array
+ */
+static inline uint8_t mavlink_msg_gps_status_var_get_satellite_azimuth_len(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, msg->len - 2);
+}
+
+/**
+ * @brief Get the length of field satellite_snr from gps_status_var message
+ *
+ * @return Number of items in the array
+ */
+static inline uint8_t mavlink_msg_gps_status_var_get_satellite_snr_len(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, msg->len - 1);
+}
+
+/**
+ * @brief Decode a gps_status_var message into a struct
+ *
+ * @param msg The message to decode
+ * @param gps_status_var C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_var_t* gps_status)
+{
+ gps_status->satellites_visible = mavlink_msg_gps_status_var_get_satellites_visible(msg);
+ mavlink_msg_gps_status_var_get_satellite_prn(msg, gps_status->satellite_prn);
+ mavlink_msg_gps_status_var_get_satellite_used(msg, gps_status->satellite_used);
+ mavlink_msg_gps_status_var_get_satellite_elevation(msg, gps_status->satellite_elevation);
+ mavlink_msg_gps_status_var_get_satellite_azimuth(msg, gps_status->satellite_azimuth);
+ mavlink_msg_gps_status_var_get_satellite_snr(msg, gps_status->satellite_snr);
+ gps_status->satellite_prn_len = mavlink_msg_gps_status_var_get_satellite_prn_len(msg);
+ gps_status->satellite_used_len = mavlink_msg_gps_status_var_get_satellite_used_len(msg);
+ gps_status->satellite_elevation_len = mavlink_msg_gps_status_var_get_satellite_elevation_len(msg);
+ gps_status->satellite_azimuth_len = mavlink_msg_gps_status_var_get_satellite_azimuth_len(msg);
+ gps_status->satellite_snr_len = mavlink_msg_gps_status_var_get_satellite_snr_len(msg);
+}
+
+/**
+ * @brief Holds the information necessary to decode the message human-readable
+ */
+#define MAVLINK_MESSAGE_INFO_GPS_STATUS_VAR(_msg) { \
+ "GPS_STATUS", \
+ 11, \
+ { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_var_t, satellites_visible) }, \
+ { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, mavlink_msg_gps_status_var_get_satellite_prn_len(_msg), 1, offsetof(mavlink_gps_status_var_t, satellite_prn) }, \
+ { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, mavlink_msg_gps_status_var_get_satellite_used_len(_msg), 1 + mavlink_msg_gps_status_var_get_satellite_prn_len(_msg), offsetof(mavlink_gps_status_var_t, satellite_used) }, \
+ { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, mavlink_msg_gps_status_var_get_satellite_elevation_len(_msg), 1 + mavlink_msg_gps_status_var_get_satellite_prn_len(_msg) + mavlink_msg_gps_status_var_get_satellite_used_len(_msg), offsetof(mavlink_gps_status_var_t, satellite_elevation) }, \
+ { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, mavlink_msg_gps_status_var_get_satellite_azimuth_len(_msg), 1 + mavlink_msg_gps_status_var_get_satellite_prn_len(_msg) + mavlink_msg_gps_status_var_get_satellite_used_len(_msg) + mavlink_msg_gps_status_var_get_satellite_elevation_len(_msg), offsetof(mavlink_gps_status_var_t, satellite_azimuth) }, \
+ { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, mavlink_msg_gps_status_var_get_satellite_snr_len(_msg), 1 + mavlink_msg_gps_status_var_get_satellite_prn_len(_msg) + mavlink_msg_gps_status_var_get_satellite_used_len(_msg) + mavlink_msg_gps_status_var_get_satellite_elevation_len(_msg) + mavlink_msg_gps_status_var_get_satellite_azimuth_len(_msg), offsetof(mavlink_gps_status_var_t, satellite_snr) }, \
+ { "satellite_prn_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1 + mavlink_msg_gps_status_var_get_satellite_prn_len(_msg) + mavlink_msg_gps_status_var_get_satellite_used_len(_msg) + mavlink_msg_gps_status_var_get_satellite_elevation_len(_msg) + mavlink_msg_gps_status_var_get_satellite_azimuth_len(_msg) + mavlink_msg_gps_status_var_get_satellite_snr_len(_msg), offsetof(mavlink_gps_status_var_t, satellite_prn_len) }, \
+ { "satellite_used_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1 + mavlink_msg_gps_status_var_get_satellite_prn_len(_msg) + mavlink_msg_gps_status_var_get_satellite_used_len(_msg) + mavlink_msg_gps_status_var_get_satellite_elevation_len(_msg) + mavlink_msg_gps_status_var_get_satellite_azimuth_len(_msg) + mavlink_msg_gps_status_var_get_satellite_snr_len(_msg) + 1, offsetof(mavlink_gps_status_var_t, satellite_used_len) }, \
+ { "satellite_elevation_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1 + mavlink_msg_gps_status_var_get_satellite_prn_len(_msg) + mavlink_msg_gps_status_var_get_satellite_used_len(_msg) + mavlink_msg_gps_status_var_get_satellite_elevation_len(_msg) + mavlink_msg_gps_status_var_get_satellite_azimuth_len(_msg) + mavlink_msg_gps_status_var_get_satellite_snr_len(_msg) + 2, offsetof(mavlink_gps_status_var_t, satellite_elevation_len) }, \
+ { "satellite_azimuth_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1 + mavlink_msg_gps_status_var_get_satellite_prn_len(_msg) + mavlink_msg_gps_status_var_get_satellite_used_len(_msg) + mavlink_msg_gps_status_var_get_satellite_elevation_len(_msg) + mavlink_msg_gps_status_var_get_satellite_azimuth_len(_msg) + mavlink_msg_gps_status_var_get_satellite_snr_len(_msg) + 3, offsetof(mavlink_gps_status_var_t, satellite_azimuth_len) }, \
+ { "satellite_snr_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1 + mavlink_msg_gps_status_var_get_satellite_prn_len(_msg) + mavlink_msg_gps_status_var_get_satellite_used_len(_msg) + mavlink_msg_gps_status_var_get_satellite_elevation_len(_msg) + mavlink_msg_gps_status_var_get_satellite_azimuth_len(_msg) + mavlink_msg_gps_status_var_get_satellite_snr_len(_msg) + 4, offsetof(mavlink_gps_status_var_t, satellite_snr_len) }, \
+ } \
+}
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h
index 536ca0634..b10ae2b1d 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h
@@ -2,25 +2,29 @@
#define MAVLINK_MSG_ID_STATUSTEXT 253
-typedef struct __mavlink_statustext_t
-{
- uint8_t severity; ///< Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
- char text[50]; ///< Status text message, without null termination character
-} mavlink_statustext_t;
-
#define MAVLINK_MSG_ID_STATUSTEXT_LEN 51
-#define MAVLINK_MSG_ID_253_LEN 51
+#define MAVLINK_MSG_ID_253_LEN MAVLINK_MSG_ID_STATUSTEXT_LEN
#define MAVLINK_MSG_ID_STATUSTEXT_CRC 83
-#define MAVLINK_MSG_ID_253_CRC 83
+#define MAVLINK_MSG_ID_253_CRC MAVLINK_MSG_ID_STATUSTEXT_CRC
-#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50
+#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 49 ///< Length in bytes
+
+#define MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES 1
+
+typedef struct __mavlink_statustext_t
+{
+ uint8_t severity; ///< Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
+ char text[49]; ///< Status text message, without null termination character
+ uint8_t _field_len_text; ///< Length of status text message
+} mavlink_statustext_t;
#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \
"STATUSTEXT", \
- 2, \
+ 3, \
{ { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \
- { "text", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_statustext_t, text) }, \
+ { "text", NULL, MAVLINK_TYPE_CHAR, -1, -1, -1 }, \
+ { "_field_len_text", NULL, MAVLINK_TYPE_UINT8_T, 0, -1, 1 } \
} \
}
@@ -38,24 +42,16 @@ typedef struct __mavlink_statustext_t
static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t severity, const char *text)
{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ uint8_t _field_len_text;
char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN];
_mav_put_uint8_t(buf, 0, severity);
- _mav_put_char_array(buf, 1, text, 50);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#else
- mavlink_statustext_t packet;
- packet.severity = severity;
- mav_array_memcpy(packet.text, text, sizeof(char)*50);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#endif
+ _field_len_text = mav_string_copy(&buf[1], text, sizeof(char)*49);
+ _mav_put_uint8_t(buf, 1 + _field_len_text, _field_len_text);
+ uint16_t msglen = 1 + _field_len_text + MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, msglen);
msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
-#if MAVLINK_CRC_EXTRA
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC);
-#else
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#endif
+ return mavlink_finalize_message(msg, system_id, component_id, msglen, MAVLINK_MSG_ID_STATUSTEXT_CRC);
}
/**
@@ -72,24 +68,16 @@ static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8
mavlink_message_t* msg,
uint8_t severity,const char *text)
{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ uint8_t _field_len_text;
char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN];
_mav_put_uint8_t(buf, 0, severity);
- _mav_put_char_array(buf, 1, text, 50);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#else
- mavlink_statustext_t packet;
- packet.severity = severity;
- mav_array_memcpy(packet.text, text, sizeof(char)*50);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#endif
+ _field_len_text = mav_string_copy(&buf[1], text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
+ _mav_put_uint8_t(buf, 1 + _field_len_text, _field_len_text);
+ uint16_t msglen = 1 + _field_len_text + MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, msglen);
msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
-#if MAVLINK_CRC_EXTRA
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC);
-#else
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#endif
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, msglen, MAVLINK_MSG_ID_STATUSTEXT_CRC);
}
/**
@@ -130,25 +118,14 @@ static inline uint16_t mavlink_msg_statustext_encode_chan(uint8_t system_id, uin
static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const char *text)
{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ uint8_t _field_len_text;
char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN];
_mav_put_uint8_t(buf, 0, severity);
- _mav_put_char_array(buf, 1, text, 50);
-#if MAVLINK_CRC_EXTRA
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#endif
-#else
- mavlink_statustext_t packet;
- packet.severity = severity;
- mav_array_memcpy(packet.text, text, sizeof(char)*50);
-#if MAVLINK_CRC_EXTRA
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#endif
-#endif
+ _field_len_text = mav_string_copy(&buf[1], text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
+ _mav_put_uint8_t(buf, 1 + _field_len_text, _field_len_text);
+ uint16_t msglen = 1 + _field_len_text + MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, msglen);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, msglen, MAVLINK_MSG_ID_STATUSTEXT_CRC);
}
#endif
@@ -173,7 +150,8 @@ static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_
*/
static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, char *text)
{
- return _MAV_RETURN_char_array(msg, text, 50, 1);
+ uint8_t len = _MAV_RETURN_uint8_t(msg, msg->len - MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES + 0);
+ return _MAV_RETURN_char_array(msg, text, len, 1);
}
/**
@@ -184,10 +162,8 @@ static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t*
*/
static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext)
{
-#if MAVLINK_NEED_BYTE_SWAP
+ statustext->_field_len_text = _MAV_RETURN_uint8_t(msg, msg->len - MAVLINK_MSG_STATUSTEXT_VARLEN_BYTES + 0);
statustext->severity = mavlink_msg_statustext_get_severity(msg);
- mavlink_msg_statustext_get_text(msg, statustext->text);
-#else
- memcpy(statustext, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_STATUSTEXT_LEN);
-#endif
+ /* copy the string, but at maximum to the full field length or the announced string length, depending on which is shorter */
+ strncpy(statustext->text, _MAV_PAYLOAD(msg+1), (statustext->_field_len_text < MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN) ? statustext->_field_len_text : MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
}
diff --git a/mavlink/include/mavlink/v1.0/protocol.h b/mavlink/include/mavlink/v1.0/protocol.h
index 86e7ff588..fd8a07e07 100644
--- a/mavlink/include/mavlink/v1.0/protocol.h
+++ b/mavlink/include/mavlink/v1.0/protocol.h
@@ -171,6 +171,22 @@ static inline void mav_array_memcpy(void *dest, const void *src, size_t n)
}
}
+static int mav_string_copy(void *dest, const void *src, size_t max_n)
+{
+ int i = 0;
+
+ /* copy single chars while not hitting size limit or NUL termination */
+ while (*((char*)src) != 0 && i < (int)max_n) {
+ *((char*)dest) = *((char*)src);
+ i++;
+ }
+
+ /* fill rest with zeros, as strncpy does */
+ memset(((char*)dest) + i, 0, max_n - i);
+
+ return i;
+}
+
/*
* Place a char array into a buffer
*/