diff --git a/ASLUAV/version.h b/ASLUAV/version.h index 1f01aac8f..d909f1269 100644 --- a/ASLUAV/version.h +++ b/ASLUAV/version.h @@ -7,7 +7,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Apr 12 2018" +#define MAVLINK_BUILD_DATE "Mon Apr 16 2018" #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/ardupilotmega/mavlink_msg_camera_feedback.h b/ardupilotmega/mavlink_msg_camera_feedback.h index 6bb67d67a..e14de2cac 100644 --- a/ardupilotmega/mavlink_msg_camera_feedback.h +++ b/ardupilotmega/mavlink_msg_camera_feedback.h @@ -18,11 +18,12 @@ typedef struct __mavlink_camera_feedback_t { uint8_t target_system; /*< System ID*/ uint8_t cam_idx; /*< Camera ID*/ uint8_t flags; /*< See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask*/ + uint16_t completed_captures; /*< Completed image captures*/ }) mavlink_camera_feedback_t; -#define MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN 45 +#define MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN 47 #define MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN 45 -#define MAVLINK_MSG_ID_180_LEN 45 +#define MAVLINK_MSG_ID_180_LEN 47 #define MAVLINK_MSG_ID_180_MIN_LEN 45 #define MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC 52 @@ -34,7 +35,7 @@ typedef struct __mavlink_camera_feedback_t { #define MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK { \ 180, \ "CAMERA_FEEDBACK", \ - 13, \ + 14, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_feedback_t, time_usec) }, \ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_camera_feedback_t, target_system) }, \ { "cam_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_camera_feedback_t, cam_idx) }, \ @@ -48,12 +49,13 @@ typedef struct __mavlink_camera_feedback_t { { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_camera_feedback_t, yaw) }, \ { "foc_len", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_camera_feedback_t, foc_len) }, \ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_camera_feedback_t, flags) }, \ + { "completed_captures", NULL, MAVLINK_TYPE_UINT16_T, 0, 45, offsetof(mavlink_camera_feedback_t, completed_captures) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK { \ "CAMERA_FEEDBACK", \ - 13, \ + 14, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_feedback_t, time_usec) }, \ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_camera_feedback_t, target_system) }, \ { "cam_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_camera_feedback_t, cam_idx) }, \ @@ -67,6 +69,7 @@ typedef struct __mavlink_camera_feedback_t { { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_camera_feedback_t, yaw) }, \ { "foc_len", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_camera_feedback_t, foc_len) }, \ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_camera_feedback_t, flags) }, \ + { "completed_captures", NULL, MAVLINK_TYPE_UINT16_T, 0, 45, offsetof(mavlink_camera_feedback_t, completed_captures) }, \ } \ } #endif @@ -90,10 +93,11 @@ typedef struct __mavlink_camera_feedback_t { * @param yaw Camera Yaw (earth frame, degrees, 0-360, true) * @param foc_len Focal Length (mm) * @param flags See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask + * @param completed_captures Completed image captures * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_camera_feedback_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt_msl, float alt_rel, float roll, float pitch, float yaw, float foc_len, uint8_t flags) + uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt_msl, float alt_rel, float roll, float pitch, float yaw, float foc_len, uint8_t flags, uint16_t completed_captures) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN]; @@ -110,6 +114,7 @@ static inline uint16_t mavlink_msg_camera_feedback_pack(uint8_t system_id, uint8 _mav_put_uint8_t(buf, 42, target_system); _mav_put_uint8_t(buf, 43, cam_idx); _mav_put_uint8_t(buf, 44, flags); + _mav_put_uint16_t(buf, 45, completed_captures); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); #else @@ -127,6 +132,7 @@ static inline uint16_t mavlink_msg_camera_feedback_pack(uint8_t system_id, uint8 packet.target_system = target_system; packet.cam_idx = cam_idx; packet.flags = flags; + packet.completed_captures = completed_captures; memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); #endif @@ -154,11 +160,12 @@ static inline uint16_t mavlink_msg_camera_feedback_pack(uint8_t system_id, uint8 * @param yaw Camera Yaw (earth frame, degrees, 0-360, true) * @param foc_len Focal Length (mm) * @param flags See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask + * @param completed_captures Completed image captures * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_camera_feedback_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, - uint64_t time_usec,uint8_t target_system,uint8_t cam_idx,uint16_t img_idx,int32_t lat,int32_t lng,float alt_msl,float alt_rel,float roll,float pitch,float yaw,float foc_len,uint8_t flags) + uint64_t time_usec,uint8_t target_system,uint8_t cam_idx,uint16_t img_idx,int32_t lat,int32_t lng,float alt_msl,float alt_rel,float roll,float pitch,float yaw,float foc_len,uint8_t flags,uint16_t completed_captures) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN]; @@ -175,6 +182,7 @@ static inline uint16_t mavlink_msg_camera_feedback_pack_chan(uint8_t system_id, _mav_put_uint8_t(buf, 42, target_system); _mav_put_uint8_t(buf, 43, cam_idx); _mav_put_uint8_t(buf, 44, flags); + _mav_put_uint16_t(buf, 45, completed_captures); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); #else @@ -192,6 +200,7 @@ static inline uint16_t mavlink_msg_camera_feedback_pack_chan(uint8_t system_id, packet.target_system = target_system; packet.cam_idx = cam_idx; packet.flags = flags; + packet.completed_captures = completed_captures; memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); #endif @@ -210,7 +219,7 @@ static inline uint16_t mavlink_msg_camera_feedback_pack_chan(uint8_t system_id, */ static inline uint16_t mavlink_msg_camera_feedback_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_feedback_t* camera_feedback) { - return mavlink_msg_camera_feedback_pack(system_id, component_id, msg, camera_feedback->time_usec, camera_feedback->target_system, camera_feedback->cam_idx, camera_feedback->img_idx, camera_feedback->lat, camera_feedback->lng, camera_feedback->alt_msl, camera_feedback->alt_rel, camera_feedback->roll, camera_feedback->pitch, camera_feedback->yaw, camera_feedback->foc_len, camera_feedback->flags); + return mavlink_msg_camera_feedback_pack(system_id, component_id, msg, camera_feedback->time_usec, camera_feedback->target_system, camera_feedback->cam_idx, camera_feedback->img_idx, camera_feedback->lat, camera_feedback->lng, camera_feedback->alt_msl, camera_feedback->alt_rel, camera_feedback->roll, camera_feedback->pitch, camera_feedback->yaw, camera_feedback->foc_len, camera_feedback->flags, camera_feedback->completed_captures); } /** @@ -224,7 +233,7 @@ static inline uint16_t mavlink_msg_camera_feedback_encode(uint8_t system_id, uin */ static inline uint16_t mavlink_msg_camera_feedback_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_feedback_t* camera_feedback) { - return mavlink_msg_camera_feedback_pack_chan(system_id, component_id, chan, msg, camera_feedback->time_usec, camera_feedback->target_system, camera_feedback->cam_idx, camera_feedback->img_idx, camera_feedback->lat, camera_feedback->lng, camera_feedback->alt_msl, camera_feedback->alt_rel, camera_feedback->roll, camera_feedback->pitch, camera_feedback->yaw, camera_feedback->foc_len, camera_feedback->flags); + return mavlink_msg_camera_feedback_pack_chan(system_id, component_id, chan, msg, camera_feedback->time_usec, camera_feedback->target_system, camera_feedback->cam_idx, camera_feedback->img_idx, camera_feedback->lat, camera_feedback->lng, camera_feedback->alt_msl, camera_feedback->alt_rel, camera_feedback->roll, camera_feedback->pitch, camera_feedback->yaw, camera_feedback->foc_len, camera_feedback->flags, camera_feedback->completed_captures); } /** @@ -244,10 +253,11 @@ static inline uint16_t mavlink_msg_camera_feedback_encode_chan(uint8_t system_id * @param yaw Camera Yaw (earth frame, degrees, 0-360, true) * @param foc_len Focal Length (mm) * @param flags See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask + * @param completed_captures Completed image captures */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_camera_feedback_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt_msl, float alt_rel, float roll, float pitch, float yaw, float foc_len, uint8_t flags) +static inline void mavlink_msg_camera_feedback_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt_msl, float alt_rel, float roll, float pitch, float yaw, float foc_len, uint8_t flags, uint16_t completed_captures) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN]; @@ -264,6 +274,7 @@ static inline void mavlink_msg_camera_feedback_send(mavlink_channel_t chan, uint _mav_put_uint8_t(buf, 42, target_system); _mav_put_uint8_t(buf, 43, cam_idx); _mav_put_uint8_t(buf, 44, flags); + _mav_put_uint16_t(buf, 45, completed_captures); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC); #else @@ -281,6 +292,7 @@ static inline void mavlink_msg_camera_feedback_send(mavlink_channel_t chan, uint packet.target_system = target_system; packet.cam_idx = cam_idx; packet.flags = flags; + packet.completed_captures = completed_captures; _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC); #endif @@ -294,7 +306,7 @@ static inline void mavlink_msg_camera_feedback_send(mavlink_channel_t chan, uint static inline void mavlink_msg_camera_feedback_send_struct(mavlink_channel_t chan, const mavlink_camera_feedback_t* camera_feedback) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_camera_feedback_send(chan, camera_feedback->time_usec, camera_feedback->target_system, camera_feedback->cam_idx, camera_feedback->img_idx, camera_feedback->lat, camera_feedback->lng, camera_feedback->alt_msl, camera_feedback->alt_rel, camera_feedback->roll, camera_feedback->pitch, camera_feedback->yaw, camera_feedback->foc_len, camera_feedback->flags); + mavlink_msg_camera_feedback_send(chan, camera_feedback->time_usec, camera_feedback->target_system, camera_feedback->cam_idx, camera_feedback->img_idx, camera_feedback->lat, camera_feedback->lng, camera_feedback->alt_msl, camera_feedback->alt_rel, camera_feedback->roll, camera_feedback->pitch, camera_feedback->yaw, camera_feedback->foc_len, camera_feedback->flags, camera_feedback->completed_captures); #else _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, (const char *)camera_feedback, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC); #endif @@ -308,7 +320,7 @@ static inline void mavlink_msg_camera_feedback_send_struct(mavlink_channel_t cha is usually the receive buffer for the channel, and allows a reply to an incoming message with minimum stack space usage. */ -static inline void mavlink_msg_camera_feedback_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt_msl, float alt_rel, float roll, float pitch, float yaw, float foc_len, uint8_t flags) +static inline void mavlink_msg_camera_feedback_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt_msl, float alt_rel, float roll, float pitch, float yaw, float foc_len, uint8_t flags, uint16_t completed_captures) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char *buf = (char *)msgbuf; @@ -325,6 +337,7 @@ static inline void mavlink_msg_camera_feedback_send_buf(mavlink_message_t *msgbu _mav_put_uint8_t(buf, 42, target_system); _mav_put_uint8_t(buf, 43, cam_idx); _mav_put_uint8_t(buf, 44, flags); + _mav_put_uint16_t(buf, 45, completed_captures); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC); #else @@ -342,6 +355,7 @@ static inline void mavlink_msg_camera_feedback_send_buf(mavlink_message_t *msgbu packet->target_system = target_system; packet->cam_idx = cam_idx; packet->flags = flags; + packet->completed_captures = completed_captures; _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, (const char *)packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC); #endif @@ -483,6 +497,16 @@ static inline uint8_t mavlink_msg_camera_feedback_get_flags(const mavlink_messag return _MAV_RETURN_uint8_t(msg, 44); } +/** + * @brief Get field completed_captures from camera_feedback message + * + * @return Completed image captures + */ +static inline uint16_t mavlink_msg_camera_feedback_get_completed_captures(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 45); +} + /** * @brief Decode a camera_feedback message into a struct * @@ -505,6 +529,7 @@ static inline void mavlink_msg_camera_feedback_decode(const mavlink_message_t* m camera_feedback->target_system = mavlink_msg_camera_feedback_get_target_system(msg); camera_feedback->cam_idx = mavlink_msg_camera_feedback_get_cam_idx(msg); camera_feedback->flags = mavlink_msg_camera_feedback_get_flags(msg); + camera_feedback->completed_captures = mavlink_msg_camera_feedback_get_completed_captures(msg); #else uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN; memset(camera_feedback, 0, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); diff --git a/ardupilotmega/mavlink_msg_ekf_status_report.h b/ardupilotmega/mavlink_msg_ekf_status_report.h index 902660f82..acdf2c938 100644 --- a/ardupilotmega/mavlink_msg_ekf_status_report.h +++ b/ardupilotmega/mavlink_msg_ekf_status_report.h @@ -11,11 +11,12 @@ typedef struct __mavlink_ekf_status_report_t { float compass_variance; /*< Compass variance*/ float terrain_alt_variance; /*< Terrain Altitude variance*/ uint16_t flags; /*< Flags*/ + float airspeed_variance; /*< Airspeed variance*/ }) mavlink_ekf_status_report_t; -#define MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN 22 +#define MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN 26 #define MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN 22 -#define MAVLINK_MSG_ID_193_LEN 22 +#define MAVLINK_MSG_ID_193_LEN 26 #define MAVLINK_MSG_ID_193_MIN_LEN 22 #define MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC 71 @@ -27,25 +28,27 @@ typedef struct __mavlink_ekf_status_report_t { #define MAVLINK_MESSAGE_INFO_EKF_STATUS_REPORT { \ 193, \ "EKF_STATUS_REPORT", \ - 6, \ + 7, \ { { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_ekf_status_report_t, flags) }, \ { "velocity_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ekf_status_report_t, velocity_variance) }, \ { "pos_horiz_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ekf_status_report_t, pos_horiz_variance) }, \ { "pos_vert_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ekf_status_report_t, pos_vert_variance) }, \ { "compass_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ekf_status_report_t, compass_variance) }, \ { "terrain_alt_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ekf_status_report_t, terrain_alt_variance) }, \ + { "airspeed_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_ekf_status_report_t, airspeed_variance) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_EKF_STATUS_REPORT { \ "EKF_STATUS_REPORT", \ - 6, \ + 7, \ { { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_ekf_status_report_t, flags) }, \ { "velocity_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ekf_status_report_t, velocity_variance) }, \ { "pos_horiz_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ekf_status_report_t, pos_horiz_variance) }, \ { "pos_vert_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ekf_status_report_t, pos_vert_variance) }, \ { "compass_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ekf_status_report_t, compass_variance) }, \ { "terrain_alt_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ekf_status_report_t, terrain_alt_variance) }, \ + { "airspeed_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_ekf_status_report_t, airspeed_variance) }, \ } \ } #endif @@ -62,10 +65,11 @@ typedef struct __mavlink_ekf_status_report_t { * @param pos_vert_variance Vertical Position variance * @param compass_variance Compass variance * @param terrain_alt_variance Terrain Altitude variance + * @param airspeed_variance Airspeed variance * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_ekf_status_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t flags, float velocity_variance, float pos_horiz_variance, float pos_vert_variance, float compass_variance, float terrain_alt_variance) + uint16_t flags, float velocity_variance, float pos_horiz_variance, float pos_vert_variance, float compass_variance, float terrain_alt_variance, float airspeed_variance) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN]; @@ -75,6 +79,7 @@ static inline uint16_t mavlink_msg_ekf_status_report_pack(uint8_t system_id, uin _mav_put_float(buf, 12, compass_variance); _mav_put_float(buf, 16, terrain_alt_variance); _mav_put_uint16_t(buf, 20, flags); + _mav_put_float(buf, 22, airspeed_variance); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN); #else @@ -85,6 +90,7 @@ static inline uint16_t mavlink_msg_ekf_status_report_pack(uint8_t system_id, uin packet.compass_variance = compass_variance; packet.terrain_alt_variance = terrain_alt_variance; packet.flags = flags; + packet.airspeed_variance = airspeed_variance; memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN); #endif @@ -105,11 +111,12 @@ static inline uint16_t mavlink_msg_ekf_status_report_pack(uint8_t system_id, uin * @param pos_vert_variance Vertical Position variance * @param compass_variance Compass variance * @param terrain_alt_variance Terrain Altitude variance + * @param airspeed_variance Airspeed variance * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_ekf_status_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, - uint16_t flags,float velocity_variance,float pos_horiz_variance,float pos_vert_variance,float compass_variance,float terrain_alt_variance) + uint16_t flags,float velocity_variance,float pos_horiz_variance,float pos_vert_variance,float compass_variance,float terrain_alt_variance,float airspeed_variance) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN]; @@ -119,6 +126,7 @@ static inline uint16_t mavlink_msg_ekf_status_report_pack_chan(uint8_t system_id _mav_put_float(buf, 12, compass_variance); _mav_put_float(buf, 16, terrain_alt_variance); _mav_put_uint16_t(buf, 20, flags); + _mav_put_float(buf, 22, airspeed_variance); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN); #else @@ -129,6 +137,7 @@ static inline uint16_t mavlink_msg_ekf_status_report_pack_chan(uint8_t system_id packet.compass_variance = compass_variance; packet.terrain_alt_variance = terrain_alt_variance; packet.flags = flags; + packet.airspeed_variance = airspeed_variance; memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN); #endif @@ -147,7 +156,7 @@ static inline uint16_t mavlink_msg_ekf_status_report_pack_chan(uint8_t system_id */ static inline uint16_t mavlink_msg_ekf_status_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ekf_status_report_t* ekf_status_report) { - return mavlink_msg_ekf_status_report_pack(system_id, component_id, msg, ekf_status_report->flags, ekf_status_report->velocity_variance, ekf_status_report->pos_horiz_variance, ekf_status_report->pos_vert_variance, ekf_status_report->compass_variance, ekf_status_report->terrain_alt_variance); + return mavlink_msg_ekf_status_report_pack(system_id, component_id, msg, ekf_status_report->flags, ekf_status_report->velocity_variance, ekf_status_report->pos_horiz_variance, ekf_status_report->pos_vert_variance, ekf_status_report->compass_variance, ekf_status_report->terrain_alt_variance, ekf_status_report->airspeed_variance); } /** @@ -161,7 +170,7 @@ static inline uint16_t mavlink_msg_ekf_status_report_encode(uint8_t system_id, u */ static inline uint16_t mavlink_msg_ekf_status_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ekf_status_report_t* ekf_status_report) { - return mavlink_msg_ekf_status_report_pack_chan(system_id, component_id, chan, msg, ekf_status_report->flags, ekf_status_report->velocity_variance, ekf_status_report->pos_horiz_variance, ekf_status_report->pos_vert_variance, ekf_status_report->compass_variance, ekf_status_report->terrain_alt_variance); + return mavlink_msg_ekf_status_report_pack_chan(system_id, component_id, chan, msg, ekf_status_report->flags, ekf_status_report->velocity_variance, ekf_status_report->pos_horiz_variance, ekf_status_report->pos_vert_variance, ekf_status_report->compass_variance, ekf_status_report->terrain_alt_variance, ekf_status_report->airspeed_variance); } /** @@ -174,10 +183,11 @@ static inline uint16_t mavlink_msg_ekf_status_report_encode_chan(uint8_t system_ * @param pos_vert_variance Vertical Position variance * @param compass_variance Compass variance * @param terrain_alt_variance Terrain Altitude variance + * @param airspeed_variance Airspeed variance */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_ekf_status_report_send(mavlink_channel_t chan, uint16_t flags, float velocity_variance, float pos_horiz_variance, float pos_vert_variance, float compass_variance, float terrain_alt_variance) +static inline void mavlink_msg_ekf_status_report_send(mavlink_channel_t chan, uint16_t flags, float velocity_variance, float pos_horiz_variance, float pos_vert_variance, float compass_variance, float terrain_alt_variance, float airspeed_variance) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN]; @@ -187,6 +197,7 @@ static inline void mavlink_msg_ekf_status_report_send(mavlink_channel_t chan, ui _mav_put_float(buf, 12, compass_variance); _mav_put_float(buf, 16, terrain_alt_variance); _mav_put_uint16_t(buf, 20, flags); + _mav_put_float(buf, 22, airspeed_variance); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, buf, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC); #else @@ -197,6 +208,7 @@ static inline void mavlink_msg_ekf_status_report_send(mavlink_channel_t chan, ui packet.compass_variance = compass_variance; packet.terrain_alt_variance = terrain_alt_variance; packet.flags = flags; + packet.airspeed_variance = airspeed_variance; _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, (const char *)&packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC); #endif @@ -210,7 +222,7 @@ static inline void mavlink_msg_ekf_status_report_send(mavlink_channel_t chan, ui static inline void mavlink_msg_ekf_status_report_send_struct(mavlink_channel_t chan, const mavlink_ekf_status_report_t* ekf_status_report) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_ekf_status_report_send(chan, ekf_status_report->flags, ekf_status_report->velocity_variance, ekf_status_report->pos_horiz_variance, ekf_status_report->pos_vert_variance, ekf_status_report->compass_variance, ekf_status_report->terrain_alt_variance); + mavlink_msg_ekf_status_report_send(chan, ekf_status_report->flags, ekf_status_report->velocity_variance, ekf_status_report->pos_horiz_variance, ekf_status_report->pos_vert_variance, ekf_status_report->compass_variance, ekf_status_report->terrain_alt_variance, ekf_status_report->airspeed_variance); #else _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, (const char *)ekf_status_report, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC); #endif @@ -224,7 +236,7 @@ static inline void mavlink_msg_ekf_status_report_send_struct(mavlink_channel_t c is usually the receive buffer for the channel, and allows a reply to an incoming message with minimum stack space usage. */ -static inline void mavlink_msg_ekf_status_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t flags, float velocity_variance, float pos_horiz_variance, float pos_vert_variance, float compass_variance, float terrain_alt_variance) +static inline void mavlink_msg_ekf_status_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t flags, float velocity_variance, float pos_horiz_variance, float pos_vert_variance, float compass_variance, float terrain_alt_variance, float airspeed_variance) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char *buf = (char *)msgbuf; @@ -234,6 +246,7 @@ static inline void mavlink_msg_ekf_status_report_send_buf(mavlink_message_t *msg _mav_put_float(buf, 12, compass_variance); _mav_put_float(buf, 16, terrain_alt_variance); _mav_put_uint16_t(buf, 20, flags); + _mav_put_float(buf, 22, airspeed_variance); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, buf, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC); #else @@ -244,6 +257,7 @@ static inline void mavlink_msg_ekf_status_report_send_buf(mavlink_message_t *msg packet->compass_variance = compass_variance; packet->terrain_alt_variance = terrain_alt_variance; packet->flags = flags; + packet->airspeed_variance = airspeed_variance; _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, (const char *)packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC); #endif @@ -315,6 +329,16 @@ static inline float mavlink_msg_ekf_status_report_get_terrain_alt_variance(const return _MAV_RETURN_float(msg, 16); } +/** + * @brief Get field airspeed_variance from ekf_status_report message + * + * @return Airspeed variance + */ +static inline float mavlink_msg_ekf_status_report_get_airspeed_variance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 22); +} + /** * @brief Decode a ekf_status_report message into a struct * @@ -330,6 +354,7 @@ static inline void mavlink_msg_ekf_status_report_decode(const mavlink_message_t* ekf_status_report->compass_variance = mavlink_msg_ekf_status_report_get_compass_variance(msg); ekf_status_report->terrain_alt_variance = mavlink_msg_ekf_status_report_get_terrain_alt_variance(msg); ekf_status_report->flags = mavlink_msg_ekf_status_report_get_flags(msg); + ekf_status_report->airspeed_variance = mavlink_msg_ekf_status_report_get_airspeed_variance(msg); #else uint8_t len = msg->len < MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN? msg->len : MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN; memset(ekf_status_report, 0, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN); diff --git a/ardupilotmega/testsuite.h b/ardupilotmega/testsuite.h index c615ecb18..bc33a1085 100644 --- a/ardupilotmega/testsuite.h +++ b/ardupilotmega/testsuite.h @@ -1756,7 +1756,7 @@ static void mavlink_test_camera_feedback(uint8_t system_id, uint8_t component_id uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_camera_feedback_t packet_in = { - 93372036854775807ULL,963497880,963498088,129.0,157.0,185.0,213.0,241.0,269.0,19315,3,70,137 + 93372036854775807ULL,963497880,963498088,129.0,157.0,185.0,213.0,241.0,269.0,19315,3,70,137,19575 }; mavlink_camera_feedback_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -1773,6 +1773,7 @@ static void mavlink_test_camera_feedback(uint8_t system_id, uint8_t component_id packet1.target_system = packet_in.target_system; packet1.cam_idx = packet_in.cam_idx; packet1.flags = packet_in.flags; + packet1.completed_captures = packet_in.completed_captures; #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 @@ -1787,12 +1788,12 @@ static void mavlink_test_camera_feedback(uint8_t system_id, uint8_t component_id MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_feedback_pack(system_id, component_id, &msg , packet1.time_usec , packet1.target_system , packet1.cam_idx , packet1.img_idx , packet1.lat , packet1.lng , packet1.alt_msl , packet1.alt_rel , packet1.roll , packet1.pitch , packet1.yaw , packet1.foc_len , packet1.flags ); + mavlink_msg_camera_feedback_pack(system_id, component_id, &msg , packet1.time_usec , packet1.target_system , packet1.cam_idx , packet1.img_idx , packet1.lat , packet1.lng , packet1.alt_msl , packet1.alt_rel , packet1.roll , packet1.pitch , packet1.yaw , packet1.foc_len , packet1.flags , packet1.completed_captures ); mavlink_msg_camera_feedback_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_feedback_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.target_system , packet1.cam_idx , packet1.img_idx , packet1.lat , packet1.lng , packet1.alt_msl , packet1.alt_rel , packet1.roll , packet1.pitch , packet1.yaw , packet1.foc_len , packet1.flags ); + mavlink_msg_camera_feedback_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.target_system , packet1.cam_idx , packet1.img_idx , packet1.lat , packet1.lng , packet1.alt_msl , packet1.alt_rel , packet1.roll , packet1.pitch , packet1.yaw , packet1.foc_len , packet1.flags , packet1.completed_captures ); mavlink_msg_camera_feedback_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); @@ -1805,7 +1806,7 @@ static void mavlink_test_camera_feedback(uint8_t system_id, uint8_t component_id MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_feedback_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.target_system , packet1.cam_idx , packet1.img_idx , packet1.lat , packet1.lng , packet1.alt_msl , packet1.alt_rel , packet1.roll , packet1.pitch , packet1.yaw , packet1.foc_len , packet1.flags ); + mavlink_msg_camera_feedback_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.target_system , packet1.cam_idx , packet1.img_idx , packet1.lat , packet1.lng , packet1.alt_msl , packet1.alt_rel , packet1.roll , packet1.pitch , packet1.yaw , packet1.foc_len , packet1.flags , packet1.completed_captures ); mavlink_msg_camera_feedback_decode(last_msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } @@ -2297,7 +2298,7 @@ static void mavlink_test_ekf_status_report(uint8_t system_id, uint8_t component_ uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_ekf_status_report_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,18275 + 17.0,45.0,73.0,101.0,129.0,18275,171.0 }; mavlink_ekf_status_report_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2307,6 +2308,7 @@ static void mavlink_test_ekf_status_report(uint8_t system_id, uint8_t component_ packet1.compass_variance = packet_in.compass_variance; packet1.terrain_alt_variance = packet_in.terrain_alt_variance; packet1.flags = packet_in.flags; + packet1.airspeed_variance = packet_in.airspeed_variance; #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 @@ -2321,12 +2323,12 @@ static void mavlink_test_ekf_status_report(uint8_t system_id, uint8_t component_ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ekf_status_report_pack(system_id, component_id, &msg , packet1.flags , packet1.velocity_variance , packet1.pos_horiz_variance , packet1.pos_vert_variance , packet1.compass_variance , packet1.terrain_alt_variance ); + mavlink_msg_ekf_status_report_pack(system_id, component_id, &msg , packet1.flags , packet1.velocity_variance , packet1.pos_horiz_variance , packet1.pos_vert_variance , packet1.compass_variance , packet1.terrain_alt_variance , packet1.airspeed_variance ); mavlink_msg_ekf_status_report_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ekf_status_report_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.flags , packet1.velocity_variance , packet1.pos_horiz_variance , packet1.pos_vert_variance , packet1.compass_variance , packet1.terrain_alt_variance ); + mavlink_msg_ekf_status_report_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.flags , packet1.velocity_variance , packet1.pos_horiz_variance , packet1.pos_vert_variance , packet1.compass_variance , packet1.terrain_alt_variance , packet1.airspeed_variance ); mavlink_msg_ekf_status_report_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); @@ -2339,7 +2341,7 @@ static void mavlink_test_ekf_status_report(uint8_t system_id, uint8_t component_ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ekf_status_report_send(MAVLINK_COMM_1 , packet1.flags , packet1.velocity_variance , packet1.pos_horiz_variance , packet1.pos_vert_variance , packet1.compass_variance , packet1.terrain_alt_variance ); + mavlink_msg_ekf_status_report_send(MAVLINK_COMM_1 , packet1.flags , packet1.velocity_variance , packet1.pos_horiz_variance , packet1.pos_vert_variance , packet1.compass_variance , packet1.terrain_alt_variance , packet1.airspeed_variance ); mavlink_msg_ekf_status_report_decode(last_msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } diff --git a/ardupilotmega/version.h b/ardupilotmega/version.h index e655421b4..06858504a 100644 --- a/ardupilotmega/version.h +++ b/ardupilotmega/version.h @@ -7,7 +7,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Apr 12 2018" +#define MAVLINK_BUILD_DATE "Mon Apr 16 2018" #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/autoquad/version.h b/autoquad/version.h index 5080aa280..a36282956 100644 --- a/autoquad/version.h +++ b/autoquad/version.h @@ -7,7 +7,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Apr 12 2018" +#define MAVLINK_BUILD_DATE "Mon Apr 16 2018" #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/common/version.h b/common/version.h index 819e5d26a..c94bfe7d2 100644 --- a/common/version.h +++ b/common/version.h @@ -7,7 +7,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Apr 12 2018" +#define MAVLINK_BUILD_DATE "Mon Apr 16 2018" #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/icarous/version.h b/icarous/version.h index b98233ac8..328fdffbb 100644 --- a/icarous/version.h +++ b/icarous/version.h @@ -7,7 +7,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Apr 12 2018" +#define MAVLINK_BUILD_DATE "Mon Apr 16 2018" #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/matrixpilot/version.h b/matrixpilot/version.h index 377b19968..6f885a6b1 100644 --- a/matrixpilot/version.h +++ b/matrixpilot/version.h @@ -7,7 +7,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Apr 12 2018" +#define MAVLINK_BUILD_DATE "Mon Apr 16 2018" #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/message_definitions/ardupilotmega.xml b/message_definitions/ardupilotmega.xml index 7c4fed8f2..377bb0b8c 100644 --- a/message_definitions/ardupilotmega.xml +++ b/message_definitions/ardupilotmega.xml @@ -1298,6 +1298,8 @@ See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask + + Completed image captures 2nd Battery status @@ -1386,6 +1388,8 @@ Vertical Position variance Compass variance Terrain Altitude variance + + Airspeed variance diff --git a/minimal/version.h b/minimal/version.h index 944ec208a..2005cf676 100644 --- a/minimal/version.h +++ b/minimal/version.h @@ -7,7 +7,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Apr 12 2018" +#define MAVLINK_BUILD_DATE "Mon Apr 16 2018" #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 9 diff --git a/slugs/version.h b/slugs/version.h index f2dfe5b12..fce58b4bd 100644 --- a/slugs/version.h +++ b/slugs/version.h @@ -7,7 +7,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Apr 12 2018" +#define MAVLINK_BUILD_DATE "Mon Apr 16 2018" #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/standard/version.h b/standard/version.h index 299819457..5ed8e9bc8 100644 --- a/standard/version.h +++ b/standard/version.h @@ -7,7 +7,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Apr 12 2018" +#define MAVLINK_BUILD_DATE "Mon Apr 16 2018" #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/test/version.h b/test/version.h index fef8e019b..54ae5d0ec 100644 --- a/test/version.h +++ b/test/version.h @@ -7,7 +7,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Apr 12 2018" +#define MAVLINK_BUILD_DATE "Mon Apr 16 2018" #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 179 diff --git a/uAvionix/version.h b/uAvionix/version.h index d456f7e6b..f0ec197cd 100644 --- a/uAvionix/version.h +++ b/uAvionix/version.h @@ -7,7 +7,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Apr 12 2018" +#define MAVLINK_BUILD_DATE "Mon Apr 16 2018" #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255