From 14f8c719320326ef3c58dcdecf9d12826fac796f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 24 Oct 2011 12:20:46 +1100 Subject: [PATCH] import latest MAVLink 1.0 headers and XML --- .../include_v1.0/ardupilotmega/version.h | 2 +- .../GCS_MAVLink/include_v1.0/common/common.h | 45 +++++++++++++++++++ .../common/mavlink_msg_command_ack.h | 10 ++--- .../common/mavlink_msg_mission_ack.h | 10 ++--- .../common/mavlink_msg_param_set.h | 10 ++--- .../common/mavlink_msg_param_value.h | 10 ++--- .../GCS_MAVLink/include_v1.0/common/version.h | 2 +- .../include_v1.0/minimal/version.h | 2 +- .../include_v1.0/pixhawk/version.h | 2 +- .../GCS_MAVLink/include_v1.0/slugs/version.h | 2 +- .../GCS_MAVLink/include_v1.0/test/version.h | 2 +- .../include_v1.0/ualberta/version.h | 2 +- .../GCS_MAVLink/message_definitions/test.xml | 31 +++++++++++++ 13 files changed, 103 insertions(+), 27 deletions(-) create mode 100644 libraries/GCS_MAVLink/message_definitions/test.xml diff --git a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h index 427f7f857c..6a6ff419ef 100644 --- a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h +++ b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Mon Oct 24 09:45:38 2011" +#define MAVLINK_BUILD_DATE "Mon Oct 24 11:51:38 2011" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/libraries/GCS_MAVLink/include_v1.0/common/common.h b/libraries/GCS_MAVLink/include_v1.0/common/common.h index 2f76efc227..f9bbc878b8 100644 --- a/libraries/GCS_MAVLink/include_v1.0/common/common.h +++ b/libraries/GCS_MAVLink/include_v1.0/common/common.h @@ -300,6 +300,51 @@ enum MAV_CMD_ACK MAV_CMD_ACK_ENUM_END=10, /* | */ }; +/** @brief type of a mavlink parameter */ +enum MAV_VAR +{ + MAV_VAR_FLOAT=0, /* 32 bit float | */ + MAV_VAR_UINT8=1, /* 8 bit unsigned integer | */ + MAV_VAR_INT8=2, /* 8 bit signed integer | */ + MAV_VAR_UINT16=3, /* 16 bit unsigned integer | */ + MAV_VAR_INT16=4, /* 16 bit signed integer | */ + MAV_VAR_UINT32=5, /* 32 bit unsigned integer | */ + MAV_VAR_INT32=6, /* 32 bit signed integer | */ + MAV_VAR_ENUM_END=7, /* | */ +}; + +/** @brief result from a mavlink command */ +enum MAV_RESULT +{ + MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */ + MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */ + MAV_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */ + MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */ + MAV_RESULT_FAILED=4, /* Command executed, but failed | */ + MAV_RESULT_ENUM_END=5, /* | */ +}; + +/** @brief result in a mavlink mission ack */ +enum MAV_MISSION_RESULT +{ + MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */ + MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */ + MAV_MISSION_UNSUPPORTED_FRAME=2, /* coordinate frame is not supported | */ + MAV_MISSION_UNSUPPORTED=3, /* command is not supported | */ + MAV_MISSION_NO_SPACE=4, /* mission item exceeds storage space | */ + MAV_MISSION_INVALID=5, /* one of the parameters has an invalid value | */ + MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value | */ + MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value | */ + MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value | */ + MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value | */ + MAV_MISSION_INVALID_PARAM5_X=10, /* x/param5 has an invalid value | */ + MAV_MISSION_INVALID_PARAM6_Y=11, /* y/param6 has an invalid value | */ + MAV_MISSION_INVALID_PARAM7=12, /* param7 has an invalid value | */ + MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */ + MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */ + MAV_MISSION_RESULT_ENUM_END=15, /* | */ +}; + // MESSAGE DEFINITIONS #include "./mavlink_msg_heartbeat.h" #include "./mavlink_msg_sys_status.h" diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_ack.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_ack.h index 546beec121..2109e32072 100644 --- a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_ack.h +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_ack.h @@ -5,7 +5,7 @@ typedef struct __mavlink_command_ack_t { uint16_t command; ///< Command ID, as defined by MAV_CMD enum. - uint8_t result; ///< 1: Command ACCEPTED and EXECUTED, 1: Command TEMPORARY REJECTED/DENIED, 2: Command PERMANENTLY DENIED, 3: Command UNKNOWN/UNSUPPORTED, 4: Command executed, but failed + uint8_t result; ///< See MAV_RESULT enum } mavlink_command_ack_t; #define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3 @@ -29,7 +29,7 @@ typedef struct __mavlink_command_ack_t * @param msg The MAVLink message to compress the data into * * @param command Command ID, as defined by MAV_CMD enum. - * @param result 1: Command ACCEPTED and EXECUTED, 1: Command TEMPORARY REJECTED/DENIED, 2: Command PERMANENTLY DENIED, 3: Command UNKNOWN/UNSUPPORTED, 4: Command executed, but failed + * @param result See MAV_RESULT enum * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -60,7 +60,7 @@ static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t c * @param chan The MAVLink channel this message was sent over * @param msg The MAVLink message to compress the data into * @param command Command ID, as defined by MAV_CMD enum. - * @param result 1: Command ACCEPTED and EXECUTED, 1: Command TEMPORARY REJECTED/DENIED, 2: Command PERMANENTLY DENIED, 3: Command UNKNOWN/UNSUPPORTED, 4: Command executed, but failed + * @param result See MAV_RESULT enum * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -103,7 +103,7 @@ static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t * @param chan MAVLink channel to send the message * * @param command Command ID, as defined by MAV_CMD enum. - * @param result 1: Command ACCEPTED and EXECUTED, 1: Command TEMPORARY REJECTED/DENIED, 2: Command PERMANENTLY DENIED, 3: Command UNKNOWN/UNSUPPORTED, 4: Command executed, but failed + * @param result See MAV_RESULT enum */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -142,7 +142,7 @@ static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message /** * @brief Get field result from command_ack message * - * @return 1: Command ACCEPTED and EXECUTED, 1: Command TEMPORARY REJECTED/DENIED, 2: Command PERMANENTLY DENIED, 3: Command UNKNOWN/UNSUPPORTED, 4: Command executed, but failed + * @return See MAV_RESULT enum */ static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg) { diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_ack.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_ack.h index 23682fc068..1696e76586 100644 --- a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_ack.h +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_ack.h @@ -6,7 +6,7 @@ typedef struct __mavlink_mission_ack_t { uint8_t target_system; ///< System ID uint8_t target_component; ///< Component ID - uint8_t type; ///< 0: OK, 1: generic error / not accepting mission commands at all right now, 2: coordinate frame is not supported, 3: command is not supported, 4: mission item exceeds storage space, 5: one of the parameters has an invalid value, 6: param1 has an invalid value, 7: param2 has an invalid value, 8: param3 has an invalid value, 9: param4 has an invalid value, 10: x/param5 has an invalid value, 11: y:param6 has an invalid value, 12: z:param7 has an invalid value, 13: received waypoint out of sequence, 14: not accepting any mission commands from this communication partner + uint8_t type; ///< See MAV_MISSION_RESULT enum } mavlink_mission_ack_t; #define MAVLINK_MSG_ID_MISSION_ACK_LEN 3 @@ -32,7 +32,7 @@ typedef struct __mavlink_mission_ack_t * * @param target_system System ID * @param target_component Component ID - * @param type 0: OK, 1: generic error / not accepting mission commands at all right now, 2: coordinate frame is not supported, 3: command is not supported, 4: mission item exceeds storage space, 5: one of the parameters has an invalid value, 6: param1 has an invalid value, 7: param2 has an invalid value, 8: param3 has an invalid value, 9: param4 has an invalid value, 10: x/param5 has an invalid value, 11: y:param6 has an invalid value, 12: z:param7 has an invalid value, 13: received waypoint out of sequence, 14: not accepting any mission commands from this communication partner + * @param type See MAV_MISSION_RESULT enum * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t c * @param msg The MAVLink message to compress the data into * @param target_system System ID * @param target_component Component ID - * @param type 0: OK, 1: generic error / not accepting mission commands at all right now, 2: coordinate frame is not supported, 3: command is not supported, 4: mission item exceeds storage space, 5: one of the parameters has an invalid value, 6: param1 has an invalid value, 7: param2 has an invalid value, 8: param3 has an invalid value, 9: param4 has an invalid value, 10: x/param5 has an invalid value, 11: y:param6 has an invalid value, 12: z:param7 has an invalid value, 13: received waypoint out of sequence, 14: not accepting any mission commands from this communication partner + * @param type See MAV_MISSION_RESULT enum * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -112,7 +112,7 @@ static inline uint16_t mavlink_msg_mission_ack_encode(uint8_t system_id, uint8_t * * @param target_system System ID * @param target_component Component ID - * @param type 0: OK, 1: generic error / not accepting mission commands at all right now, 2: coordinate frame is not supported, 3: command is not supported, 4: mission item exceeds storage space, 5: one of the parameters has an invalid value, 6: param1 has an invalid value, 7: param2 has an invalid value, 8: param3 has an invalid value, 9: param4 has an invalid value, 10: x/param5 has an invalid value, 11: y:param6 has an invalid value, 12: z:param7 has an invalid value, 13: received waypoint out of sequence, 14: not accepting any mission commands from this communication partner + * @param type See MAV_MISSION_RESULT enum */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -163,7 +163,7 @@ static inline uint8_t mavlink_msg_mission_ack_get_target_component(const mavlink /** * @brief Get field type from mission_ack message * - * @return 0: OK, 1: generic error / not accepting mission commands at all right now, 2: coordinate frame is not supported, 3: command is not supported, 4: mission item exceeds storage space, 5: one of the parameters has an invalid value, 6: param1 has an invalid value, 7: param2 has an invalid value, 8: param3 has an invalid value, 9: param4 has an invalid value, 10: x/param5 has an invalid value, 11: y:param6 has an invalid value, 12: z:param7 has an invalid value, 13: received waypoint out of sequence, 14: not accepting any mission commands from this communication partner + * @return See MAV_MISSION_RESULT enum */ static inline uint8_t mavlink_msg_mission_ack_get_type(const mavlink_message_t* msg) { diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_set.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_set.h index 87eab13d96..a463c69458 100644 --- a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_set.h +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_set.h @@ -8,7 +8,7 @@ typedef struct __mavlink_param_set_t uint8_t target_system; ///< System ID uint8_t target_component; ///< Component ID char param_id[16]; ///< Onboard parameter id - uint8_t param_type; ///< Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t + uint8_t param_type; ///< Onboard parameter type: see MAV_VAR enum } mavlink_param_set_t; #define MAVLINK_MSG_ID_PARAM_SET_LEN 23 @@ -38,7 +38,7 @@ typedef struct __mavlink_param_set_t * @param target_component Component ID * @param param_id Onboard parameter id * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t + * @param param_type Onboard parameter type: see MAV_VAR enum * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -76,7 +76,7 @@ static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t com * @param target_component Component ID * @param param_id Onboard parameter id * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t + * @param param_type Onboard parameter type: see MAV_VAR enum * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -126,7 +126,7 @@ static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t c * @param target_component Component ID * @param param_id Onboard parameter id * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t + * @param param_type Onboard parameter type: see MAV_VAR enum */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -199,7 +199,7 @@ static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_ /** * @brief Get field param_type from param_set message * - * @return Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t + * @return Onboard parameter type: see MAV_VAR enum */ static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg) { diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_value.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_value.h index fd9b57bfc5..858921be39 100644 --- a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_value.h +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_value.h @@ -8,7 +8,7 @@ typedef struct __mavlink_param_value_t uint16_t param_count; ///< Total number of onboard parameters uint16_t param_index; ///< Index of this onboard parameter char param_id[16]; ///< Onboard parameter id - uint8_t param_type; ///< Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t + uint8_t param_type; ///< Onboard parameter type: see MAV_VAR enum } mavlink_param_value_t; #define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25 @@ -36,7 +36,7 @@ typedef struct __mavlink_param_value_t * * @param param_id Onboard parameter id * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t + * @param param_type Onboard parameter type: see MAV_VAR enum * @param param_count Total number of onboard parameters * @param param_index Index of this onboard parameter * @return length of the message in bytes (excluding serial stream start sign) @@ -74,7 +74,7 @@ static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t c * @param msg The MAVLink message to compress the data into * @param param_id Onboard parameter id * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t + * @param param_type Onboard parameter type: see MAV_VAR enum * @param param_count Total number of onboard parameters * @param param_index Index of this onboard parameter * @return length of the message in bytes (excluding serial stream start sign) @@ -124,7 +124,7 @@ static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t * * @param param_id Onboard parameter id * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t + * @param param_type Onboard parameter type: see MAV_VAR enum * @param param_count Total number of onboard parameters * @param param_index Index of this onboard parameter */ @@ -179,7 +179,7 @@ static inline float mavlink_msg_param_value_get_param_value(const mavlink_messag /** * @brief Get field param_type from param_value message * - * @return Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t + * @return Onboard parameter type: see MAV_VAR enum */ static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_message_t* msg) { diff --git a/libraries/GCS_MAVLink/include_v1.0/common/version.h b/libraries/GCS_MAVLink/include_v1.0/common/version.h index c5ee06f82f..adcdb5b40b 100644 --- a/libraries/GCS_MAVLink/include_v1.0/common/version.h +++ b/libraries/GCS_MAVLink/include_v1.0/common/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Mon Oct 24 09:45:40 2011" +#define MAVLINK_BUILD_DATE "Mon Oct 24 11:51:40 2011" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/libraries/GCS_MAVLink/include_v1.0/minimal/version.h b/libraries/GCS_MAVLink/include_v1.0/minimal/version.h index 7467c772a8..21894e5572 100644 --- a/libraries/GCS_MAVLink/include_v1.0/minimal/version.h +++ b/libraries/GCS_MAVLink/include_v1.0/minimal/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Mon Oct 24 09:45:39 2011" +#define MAVLINK_BUILD_DATE "Mon Oct 24 11:51:39 2011" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 9 diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/version.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/version.h index 0ddf035df6..32fc0307dd 100644 --- a/libraries/GCS_MAVLink/include_v1.0/pixhawk/version.h +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Mon Oct 24 09:45:39 2011" +#define MAVLINK_BUILD_DATE "Mon Oct 24 11:51:39 2011" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/libraries/GCS_MAVLink/include_v1.0/slugs/version.h b/libraries/GCS_MAVLink/include_v1.0/slugs/version.h index b69d7bb49d..c102da0cde 100644 --- a/libraries/GCS_MAVLink/include_v1.0/slugs/version.h +++ b/libraries/GCS_MAVLink/include_v1.0/slugs/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Mon Oct 24 09:45:40 2011" +#define MAVLINK_BUILD_DATE "Mon Oct 24 11:51:40 2011" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/libraries/GCS_MAVLink/include_v1.0/test/version.h b/libraries/GCS_MAVLink/include_v1.0/test/version.h index 256f7bb167..da1c0e68ad 100644 --- a/libraries/GCS_MAVLink/include_v1.0/test/version.h +++ b/libraries/GCS_MAVLink/include_v1.0/test/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Mon Oct 24 09:45:40 2011" +#define MAVLINK_BUILD_DATE "Mon Oct 24 11:51:40 2011" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 179 diff --git a/libraries/GCS_MAVLink/include_v1.0/ualberta/version.h b/libraries/GCS_MAVLink/include_v1.0/ualberta/version.h index 0792183013..e2860f0d80 100644 --- a/libraries/GCS_MAVLink/include_v1.0/ualberta/version.h +++ b/libraries/GCS_MAVLink/include_v1.0/ualberta/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Mon Oct 24 09:45:40 2011" +#define MAVLINK_BUILD_DATE "Mon Oct 24 11:51:40 2011" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/libraries/GCS_MAVLink/message_definitions/test.xml b/libraries/GCS_MAVLink/message_definitions/test.xml new file mode 100644 index 0000000000..43a11e3d13 --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions/test.xml @@ -0,0 +1,31 @@ + + + 3 + + + Test all field types + char + string + uint8_t + uint16_t + uint32_t + uint64_t + int8_t + int16_t + int32_t + int64_t + float + double + uint8_t_array + uint16_t_array + uint32_t_array + uint64_t_array + int8_t_array + int16_t_array + int32_t_array + int64_t_array + float_array + double_array + + +