Commit 477a5b6d authored by PX4BuildBot's avatar PX4BuildBot

autogenerated headers for rev...

autogenerated headers for rev https://github.com/mavlink/mavlink/tree/6e06b09b9ceb1d03c8f54e91494ab84901d33d9c
parent 2a9615b7
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Jul 10 2019"
#define MAVLINK_BUILD_DATE "Thu Jul 11 2019"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Jul 10 2019"
#define MAVLINK_BUILD_DATE "Thu Jul 11 2019"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Jul 10 2019"
#define MAVLINK_BUILD_DATE "Thu Jul 11 2019"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Jul 10 2019"
#define MAVLINK_BUILD_DATE "Thu Jul 11 2019"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Jul 10 2019"
#define MAVLINK_BUILD_DATE "Thu Jul 11 2019"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Jul 10 2019"
#define MAVLINK_BUILD_DATE "Thu Jul 11 2019"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -381,6 +381,14 @@
<description>Component for handling system messages (e.g. to ARM, takeoff, etc.).</description>
</entry>
</enum>
<enum name="MAV_CMD">
<description>Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries</description>
<entry value="519" name="MAV_CMD_REQUEST_PROTOCOL_VERSION" hasLocation="false" isDestination="false">
<description>Request MAVLink protocol version compatibility</description>
<param index="1" label="Protocol">1: Request supported protocol versions by all nodes on the network</param>
<param index="2">Reserved (all remaining params)</param>
</entry>
</enum>
</enums>
<messages>
<message id="0" name="HEARTBEAT">
......@@ -392,5 +400,15 @@
<field type="uint8_t" name="system_status" enum="MAV_STATE">System status flag.</field>
<field type="uint8_t_mavlink_version" name="mavlink_version">MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version</field>
</message>
<message id="300" name="PROTOCOL_VERSION">
<wip/>
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>Version and capability of protocol version. This message is the response to REQUEST_PROTOCOL_VERSION and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to REQUEST_PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly.</description>
<field type="uint16_t" name="version">Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.</field>
<field type="uint16_t" name="min_version">Minimum MAVLink version supported</field>
<field type="uint16_t" name="max_version">Maximum MAVLink version supported (set to the same value as version by default)</field>
<field type="uint8_t[8]" name="spec_version_hash">The first 8 bytes (not characters printed in hex!) of the git hash.</field>
<field type="uint8_t[8]" name="library_version_hash">The first 8 bytes (not characters printed in hex!) of the git hash.</field>
</message>
</messages>
</mavlink>
#pragma once
// MESSAGE PROTOCOL_VERSION PACKING
#define MAVLINK_MSG_ID_PROTOCOL_VERSION 300
MAVPACKED(
typedef struct __mavlink_protocol_version_t {
uint16_t version; /*< Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.*/
uint16_t min_version; /*< Minimum MAVLink version supported*/
uint16_t max_version; /*< Maximum MAVLink version supported (set to the same value as version by default)*/
uint8_t spec_version_hash[8]; /*< The first 8 bytes (not characters printed in hex!) of the git hash.*/
uint8_t library_version_hash[8]; /*< The first 8 bytes (not characters printed in hex!) of the git hash.*/
}) mavlink_protocol_version_t;
#define MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN 22
#define MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN 22
#define MAVLINK_MSG_ID_300_LEN 22
#define MAVLINK_MSG_ID_300_MIN_LEN 22
#define MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC 217
#define MAVLINK_MSG_ID_300_CRC 217
#define MAVLINK_MSG_PROTOCOL_VERSION_FIELD_SPEC_VERSION_HASH_LEN 8
#define MAVLINK_MSG_PROTOCOL_VERSION_FIELD_LIBRARY_VERSION_HASH_LEN 8
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION { \
300, \
"PROTOCOL_VERSION", \
5, \
{ { "version", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_protocol_version_t, version) }, \
{ "min_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_protocol_version_t, min_version) }, \
{ "max_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_protocol_version_t, max_version) }, \
{ "spec_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 6, offsetof(mavlink_protocol_version_t, spec_version_hash) }, \
{ "library_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 14, offsetof(mavlink_protocol_version_t, library_version_hash) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION { \
"PROTOCOL_VERSION", \
5, \
{ { "version", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_protocol_version_t, version) }, \
{ "min_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_protocol_version_t, min_version) }, \
{ "max_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_protocol_version_t, max_version) }, \
{ "spec_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 6, offsetof(mavlink_protocol_version_t, spec_version_hash) }, \
{ "library_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 14, offsetof(mavlink_protocol_version_t, library_version_hash) }, \
} \
}
#endif
/**
* @brief Pack a protocol_version 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 version Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.
* @param min_version Minimum MAVLink version supported
* @param max_version Maximum MAVLink version supported (set to the same value as version by default)
* @param spec_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
* @param library_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_protocol_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t version, uint16_t min_version, uint16_t max_version, const uint8_t *spec_version_hash, const uint8_t *library_version_hash)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN];
_mav_put_uint16_t(buf, 0, version);
_mav_put_uint16_t(buf, 2, min_version);
_mav_put_uint16_t(buf, 4, max_version);
_mav_put_uint8_t_array(buf, 6, spec_version_hash, 8);
_mav_put_uint8_t_array(buf, 14, library_version_hash, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN);
#else
mavlink_protocol_version_t packet;
packet.version = version;
packet.min_version = min_version;
packet.max_version = max_version;
mav_array_memcpy(packet.spec_version_hash, spec_version_hash, sizeof(uint8_t)*8);
mav_array_memcpy(packet.library_version_hash, library_version_hash, sizeof(uint8_t)*8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PROTOCOL_VERSION;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC);
}
/**
* @brief Pack a protocol_version 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param version Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.
* @param min_version Minimum MAVLink version supported
* @param max_version Maximum MAVLink version supported (set to the same value as version by default)
* @param spec_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
* @param library_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_protocol_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t version,uint16_t min_version,uint16_t max_version,const uint8_t *spec_version_hash,const uint8_t *library_version_hash)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN];
_mav_put_uint16_t(buf, 0, version);
_mav_put_uint16_t(buf, 2, min_version);
_mav_put_uint16_t(buf, 4, max_version);
_mav_put_uint8_t_array(buf, 6, spec_version_hash, 8);
_mav_put_uint8_t_array(buf, 14, library_version_hash, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN);
#else
mavlink_protocol_version_t packet;
packet.version = version;
packet.min_version = min_version;
packet.max_version = max_version;
mav_array_memcpy(packet.spec_version_hash, spec_version_hash, sizeof(uint8_t)*8);
mav_array_memcpy(packet.library_version_hash, library_version_hash, sizeof(uint8_t)*8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PROTOCOL_VERSION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC);
}
/**
* @brief Encode a protocol_version struct
*
* @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 protocol_version C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_protocol_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_protocol_version_t* protocol_version)
{
return mavlink_msg_protocol_version_pack(system_id, component_id, msg, protocol_version->version, protocol_version->min_version, protocol_version->max_version, protocol_version->spec_version_hash, protocol_version->library_version_hash);
}
/**
* @brief Encode a protocol_version struct on a channel
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param protocol_version C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_protocol_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_protocol_version_t* protocol_version)
{
return mavlink_msg_protocol_version_pack_chan(system_id, component_id, chan, msg, protocol_version->version, protocol_version->min_version, protocol_version->max_version, protocol_version->spec_version_hash, protocol_version->library_version_hash);
}
/**
* @brief Send a protocol_version message
* @param chan MAVLink channel to send the message
*
* @param version Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.
* @param min_version Minimum MAVLink version supported
* @param max_version Maximum MAVLink version supported (set to the same value as version by default)
* @param spec_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
* @param library_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_protocol_version_send(mavlink_channel_t chan, uint16_t version, uint16_t min_version, uint16_t max_version, const uint8_t *spec_version_hash, const uint8_t *library_version_hash)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN];
_mav_put_uint16_t(buf, 0, version);
_mav_put_uint16_t(buf, 2, min_version);
_mav_put_uint16_t(buf, 4, max_version);
_mav_put_uint8_t_array(buf, 6, spec_version_hash, 8);
_mav_put_uint8_t_array(buf, 14, library_version_hash, 8);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PROTOCOL_VERSION, buf, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC);
#else
mavlink_protocol_version_t packet;
packet.version = version;
packet.min_version = min_version;
packet.max_version = max_version;
mav_array_memcpy(packet.spec_version_hash, spec_version_hash, sizeof(uint8_t)*8);
mav_array_memcpy(packet.library_version_hash, library_version_hash, sizeof(uint8_t)*8);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PROTOCOL_VERSION, (const char *)&packet, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC);
#endif
}
/**
* @brief Send a protocol_version message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_protocol_version_send_struct(mavlink_channel_t chan, const mavlink_protocol_version_t* protocol_version)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_protocol_version_send(chan, protocol_version->version, protocol_version->min_version, protocol_version->max_version, protocol_version->spec_version_hash, protocol_version->library_version_hash);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PROTOCOL_VERSION, (const char *)protocol_version, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC);
#endif
}
#if MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
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_protocol_version_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t version, uint16_t min_version, uint16_t max_version, const uint8_t *spec_version_hash, const uint8_t *library_version_hash)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, version);
_mav_put_uint16_t(buf, 2, min_version);
_mav_put_uint16_t(buf, 4, max_version);
_mav_put_uint8_t_array(buf, 6, spec_version_hash, 8);
_mav_put_uint8_t_array(buf, 14, library_version_hash, 8);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PROTOCOL_VERSION, buf, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC);
#else
mavlink_protocol_version_t *packet = (mavlink_protocol_version_t *)msgbuf;
packet->version = version;
packet->min_version = min_version;
packet->max_version = max_version;
mav_array_memcpy(packet->spec_version_hash, spec_version_hash, sizeof(uint8_t)*8);
mav_array_memcpy(packet->library_version_hash, library_version_hash, sizeof(uint8_t)*8);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PROTOCOL_VERSION, (const char *)packet, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC);
#endif
}
#endif
#endif
// MESSAGE PROTOCOL_VERSION UNPACKING
/**
* @brief Get field version from protocol_version message
*
* @return Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.
*/
static inline uint16_t mavlink_msg_protocol_version_get_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field min_version from protocol_version message
*
* @return Minimum MAVLink version supported
*/
static inline uint16_t mavlink_msg_protocol_version_get_min_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Get field max_version from protocol_version message
*
* @return Maximum MAVLink version supported (set to the same value as version by default)
*/
static inline uint16_t mavlink_msg_protocol_version_get_max_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Get field spec_version_hash from protocol_version message
*
* @return The first 8 bytes (not characters printed in hex!) of the git hash.
*/
static inline uint16_t mavlink_msg_protocol_version_get_spec_version_hash(const mavlink_message_t* msg, uint8_t *spec_version_hash)
{
return _MAV_RETURN_uint8_t_array(msg, spec_version_hash, 8, 6);
}
/**
* @brief Get field library_version_hash from protocol_version message
*
* @return The first 8 bytes (not characters printed in hex!) of the git hash.
*/
static inline uint16_t mavlink_msg_protocol_version_get_library_version_hash(const mavlink_message_t* msg, uint8_t *library_version_hash)
{
return _MAV_RETURN_uint8_t_array(msg, library_version_hash, 8, 14);
}
/**
* @brief Decode a protocol_version message into a struct
*
* @param msg The message to decode
* @param protocol_version C-struct to decode the message contents into
*/
static inline void mavlink_msg_protocol_version_decode(const mavlink_message_t* msg, mavlink_protocol_version_t* protocol_version)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
protocol_version->version = mavlink_msg_protocol_version_get_version(msg);
protocol_version->min_version = mavlink_msg_protocol_version_get_min_version(msg);
protocol_version->max_version = mavlink_msg_protocol_version_get_max_version(msg);
mavlink_msg_protocol_version_get_spec_version_hash(msg, protocol_version->spec_version_hash);
mavlink_msg_protocol_version_get_library_version_hash(msg, protocol_version->library_version_hash);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN? msg->len : MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN;
memset(protocol_version, 0, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN);
memcpy(protocol_version, _MAV_PAYLOAD(msg), len);
#endif
}
......@@ -24,7 +24,7 @@ extern "C" {
#endif
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {{0, 50, 9, 9, 0, 0, 0}}
#define MAVLINK_MESSAGE_CRCS {{0, 50, 9, 9, 0, 0, 0}, {300, 217, 22, 22, 0, 0, 0}}
#endif
#include "../protocol.h"
......@@ -209,6 +209,16 @@ typedef enum MAV_COMPONENT
} MAV_COMPONENT;
#endif
/** @brief Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries */
#ifndef HAVE_ENUM_MAV_CMD
#define HAVE_ENUM_MAV_CMD
typedef enum MAV_CMD
{
MAV_CMD_REQUEST_PROTOCOL_VERSION=519, /* Request MAVLink protocol version compatibility |1: Request supported protocol versions by all nodes on the network| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
MAV_CMD_ENUM_END=520, /* | */
} MAV_CMD;
#endif
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
......@@ -222,6 +232,7 @@ typedef enum MAV_COMPONENT
// MESSAGE DEFINITIONS
#include "./mavlink_msg_heartbeat.h"
#include "./mavlink_msg_protocol_version.h"
// base include
......@@ -230,8 +241,8 @@ typedef enum MAV_COMPONENT
#define MAVLINK_THIS_XML_IDX 0
#if MAVLINK_THIS_XML_IDX == MAVLINK_PRIMARY_XML_IDX
# define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT}
# define MAVLINK_MESSAGE_NAMES {{ "HEARTBEAT", 0 }}
# define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION}
# define MAVLINK_MESSAGE_NAMES {{ "HEARTBEAT", 0 }, { "PROTOCOL_VERSION", 300 }}
# if MAVLINK_COMMAND_24BIT
# include "../mavlink_get_info.h"
# endif
......
......@@ -84,9 +84,68 @@ static void mavlink_test_heartbeat(uint8_t system_id, uint8_t component_id, mavl
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_protocol_version(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PROTOCOL_VERSION >= 256) {
return;
}
#endif
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_protocol_version_t packet_in = {
17235,17339,17443,{ 151, 152, 153, 154, 155, 156, 157, 158 },{ 175, 176, 177, 178, 179, 180, 181, 182 }
};
mavlink_protocol_version_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.version = packet_in.version;
packet1.min_version = packet_in.min_version;
packet1.max_version = packet_in.max_version;
mav_array_memcpy(packet1.spec_version_hash, packet_in.spec_version_hash, sizeof(uint8_t)*8);
mav_array_memcpy(packet1.library_version_hash, packet_in.library_version_hash, sizeof(uint8_t)*8);
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
// cope with extensions
memset(MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN);
}
#endif
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_protocol_version_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_protocol_version_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_protocol_version_pack(system_id, component_id, &msg , packet1.version , packet1.min_version , packet1.max_version , packet1.spec_version_hash , packet1.library_version_hash );
mavlink_msg_protocol_version_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_protocol_version_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.version , packet1.min_version , packet1.max_version , packet1.spec_version_hash , packet1.library_version_hash );
mavlink_msg_protocol_version_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_protocol_version_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_protocol_version_send(MAVLINK_COMM_1 , packet1.version , packet1.min_version , packet1.max_version , packet1.spec_version_hash , packet1.library_version_hash );
mavlink_msg_protocol_version_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_minimal(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_heartbeat(system_id, component_id, last_msg);
mavlink_test_protocol_version(system_id, component_id, last_msg);
}
#ifdef __cplusplus
......
......@@ -7,8 +7,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Jul 10 2019"
#define MAVLINK_BUILD_DATE "Thu Jul 11 2019"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 9
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22
#endif // MAVLINK_VERSION_H
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Jul 10 2019"
#define MAVLINK_BUILD_DATE "Thu Jul 11 2019"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Jul 10 2019"
#define MAVLINK_BUILD_DATE "Thu Jul 11 2019"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Jul 10 2019"
#define MAVLINK_BUILD_DATE "Thu Jul 11 2019"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 179
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Jul 10 2019"
#define MAVLINK_BUILD_DATE "Thu Jul 11 2019"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
Markdown is supported
0%
or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment