From 90f00ebd01798506df0b928ab92eafa79e5c46a3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 11 Aug 2012 11:58:06 +1000 Subject: [PATCH] MAVLink: re-generate MAVLink C code --- .../v1.0/ardupilotmega/ardupilotmega.h | 4 +- .../v1.0/ardupilotmega/mavlink_msg_simstate.h | 82 ++++++++++++++----- .../mavlink/v1.0/ardupilotmega/testsuite.h | 10 ++- .../mavlink/v1.0/ardupilotmega/version.h | 2 +- .../include/mavlink/v1.0/common/version.h | 2 +- 5 files changed, 74 insertions(+), 26 deletions(-) diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h index 0d6cb4ce13..ca0434a763 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h @@ -12,11 +12,11 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 9, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 42, 21, 21, 144, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 111, 21, 21, 144, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} #endif #ifndef MAVLINK_MESSAGE_INFO diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h index dfcddfc2b6..8ee447c778 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h @@ -13,16 +13,18 @@ typedef struct __mavlink_simstate_t float xgyro; ///< Angular speed around X axis rad/s float ygyro; ///< Angular speed around Y axis rad/s float zgyro; ///< Angular speed around Z axis rad/s + float lat; ///< Latitude in degrees + float lng; ///< Longitude in degrees } mavlink_simstate_t; -#define MAVLINK_MSG_ID_SIMSTATE_LEN 36 -#define MAVLINK_MSG_ID_164_LEN 36 +#define MAVLINK_MSG_ID_SIMSTATE_LEN 44 +#define MAVLINK_MSG_ID_164_LEN 44 #define MAVLINK_MESSAGE_INFO_SIMSTATE { \ "SIMSTATE", \ - 9, \ + 11, \ { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_simstate_t, roll) }, \ { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_simstate_t, pitch) }, \ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_simstate_t, yaw) }, \ @@ -32,6 +34,8 @@ typedef struct __mavlink_simstate_t { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_simstate_t, xgyro) }, \ { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_simstate_t, ygyro) }, \ { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_simstate_t, zgyro) }, \ + { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_simstate_t, lat) }, \ + { "lng", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_simstate_t, lng) }, \ } \ } @@ -51,13 +55,15 @@ typedef struct __mavlink_simstate_t * @param xgyro Angular speed around X axis rad/s * @param ygyro Angular speed around Y axis rad/s * @param zgyro Angular speed around Z axis rad/s + * @param lat Latitude in degrees + * @param lng Longitude in degrees * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro) + float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lng) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[36]; + char buf[44]; _mav_put_float(buf, 0, roll); _mav_put_float(buf, 4, pitch); _mav_put_float(buf, 8, yaw); @@ -67,8 +73,10 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp _mav_put_float(buf, 24, xgyro); _mav_put_float(buf, 28, ygyro); _mav_put_float(buf, 32, zgyro); + _mav_put_float(buf, 36, lat); + _mav_put_float(buf, 40, lng); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 44); #else mavlink_simstate_t packet; packet.roll = roll; @@ -80,12 +88,14 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp packet.xgyro = xgyro; packet.ygyro = ygyro; packet.zgyro = zgyro; + packet.lat = lat; + packet.lng = lng; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 44); #endif msg->msgid = MAVLINK_MSG_ID_SIMSTATE; - return mavlink_finalize_message(msg, system_id, component_id, 36, 42); + return mavlink_finalize_message(msg, system_id, component_id, 44, 111); } /** @@ -103,14 +113,16 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp * @param xgyro Angular speed around X axis rad/s * @param ygyro Angular speed around Y axis rad/s * @param zgyro Angular speed around Z axis rad/s + * @param lat Latitude in degrees + * @param lng Longitude in degrees * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, - float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro) + float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lng) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[36]; + char buf[44]; _mav_put_float(buf, 0, roll); _mav_put_float(buf, 4, pitch); _mav_put_float(buf, 8, yaw); @@ -120,8 +132,10 @@ static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t _mav_put_float(buf, 24, xgyro); _mav_put_float(buf, 28, ygyro); _mav_put_float(buf, 32, zgyro); + _mav_put_float(buf, 36, lat); + _mav_put_float(buf, 40, lng); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 44); #else mavlink_simstate_t packet; packet.roll = roll; @@ -133,12 +147,14 @@ static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t packet.xgyro = xgyro; packet.ygyro = ygyro; packet.zgyro = zgyro; + packet.lat = lat; + packet.lng = lng; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 44); #endif msg->msgid = MAVLINK_MSG_ID_SIMSTATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36, 42); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 44, 111); } /** @@ -151,7 +167,7 @@ static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t */ static inline uint16_t mavlink_msg_simstate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_simstate_t* simstate) { - return mavlink_msg_simstate_pack(system_id, component_id, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro); + return mavlink_msg_simstate_pack(system_id, component_id, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro, simstate->lat, simstate->lng); } /** @@ -167,13 +183,15 @@ static inline uint16_t mavlink_msg_simstate_encode(uint8_t system_id, uint8_t co * @param xgyro Angular speed around X axis rad/s * @param ygyro Angular speed around Y axis rad/s * @param zgyro Angular speed around Z axis rad/s + * @param lat Latitude in degrees + * @param lng Longitude in degrees */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro) +static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lng) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[36]; + char buf[44]; _mav_put_float(buf, 0, roll); _mav_put_float(buf, 4, pitch); _mav_put_float(buf, 8, yaw); @@ -183,8 +201,10 @@ static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, _mav_put_float(buf, 24, xgyro); _mav_put_float(buf, 28, ygyro); _mav_put_float(buf, 32, zgyro); + _mav_put_float(buf, 36, lat); + _mav_put_float(buf, 40, lng); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, 36, 42); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, 44, 111); #else mavlink_simstate_t packet; packet.roll = roll; @@ -196,8 +216,10 @@ static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, packet.xgyro = xgyro; packet.ygyro = ygyro; packet.zgyro = zgyro; + packet.lat = lat; + packet.lng = lng; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)&packet, 36, 42); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)&packet, 44, 111); #endif } @@ -296,6 +318,26 @@ static inline float mavlink_msg_simstate_get_zgyro(const mavlink_message_t* msg) return _MAV_RETURN_float(msg, 32); } +/** + * @brief Get field lat from simstate message + * + * @return Latitude in degrees + */ +static inline float mavlink_msg_simstate_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field lng from simstate message + * + * @return Longitude in degrees + */ +static inline float mavlink_msg_simstate_get_lng(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + /** * @brief Decode a simstate message into a struct * @@ -314,7 +356,9 @@ static inline void mavlink_msg_simstate_decode(const mavlink_message_t* msg, mav simstate->xgyro = mavlink_msg_simstate_get_xgyro(msg); simstate->ygyro = mavlink_msg_simstate_get_ygyro(msg); simstate->zgyro = mavlink_msg_simstate_get_zgyro(msg); + simstate->lat = mavlink_msg_simstate_get_lat(msg); + simstate->lng = mavlink_msg_simstate_get_lng(msg); #else - memcpy(simstate, _MAV_PAYLOAD(msg), 36); + memcpy(simstate, _MAV_PAYLOAD(msg), 44); #endif } diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/testsuite.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/testsuite.h index 08221a87c2..def7992113 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/testsuite.h +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/testsuite.h @@ -738,6 +738,8 @@ static void mavlink_test_simstate(uint8_t system_id, uint8_t component_id, mavli 185.0, 213.0, 241.0, + 269.0, + 297.0, }; mavlink_simstate_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -750,6 +752,8 @@ static void mavlink_test_simstate(uint8_t system_id, uint8_t component_id, mavli packet1.xgyro = packet_in.xgyro; packet1.ygyro = packet_in.ygyro; packet1.zgyro = packet_in.zgyro; + packet1.lat = packet_in.lat; + packet1.lng = packet_in.lng; @@ -759,12 +763,12 @@ static void mavlink_test_simstate(uint8_t system_id, uint8_t component_id, mavli MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_simstate_pack(system_id, component_id, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro ); + mavlink_msg_simstate_pack(system_id, component_id, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.lat , packet1.lng ); mavlink_msg_simstate_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_simstate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro ); + mavlink_msg_simstate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.lat , packet1.lng ); mavlink_msg_simstate_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); @@ -777,7 +781,7 @@ static void mavlink_test_simstate(uint8_t system_id, uint8_t component_id, mavli MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_simstate_send(MAVLINK_COMM_1 , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro ); + mavlink_msg_simstate_send(MAVLINK_COMM_1 , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.lat , packet1.lng ); mavlink_msg_simstate_decode(last_msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h index 50e26bafec..8889f7977e 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Fri Jul 20 11:32:18 2012" +#define MAVLINK_BUILD_DATE "Sat Aug 11 11:25:19 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h index 80e33f1ba1..8d1b83688c 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Fri Jul 20 11:32:18 2012" +#define MAVLINK_BUILD_DATE "Sat Aug 11 11:25:19 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101