Commit f36b9c4c authored by PX4BuildBot's avatar PX4BuildBot

autogenerated headers for rev...

autogenerated headers for rev https://github.com/mavlink/mavlink/tree/2e7281d157145ff63339e621fb818120e63bc22d
parent 201e0c9d
This diff is collapsed.
...@@ -14,18 +14,21 @@ extern "C" { ...@@ -14,18 +14,21 @@ extern "C" {
#define MAVLINK_TEST_ALL #define MAVLINK_TEST_ALL
static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg);
static void mavlink_test_uAvionix(uint8_t, uint8_t, mavlink_message_t *last_msg); static void mavlink_test_uAvionix(uint8_t, uint8_t, mavlink_message_t *last_msg);
static void mavlink_test_icarous(uint8_t, uint8_t, mavlink_message_t *last_msg);
static void mavlink_test_ardupilotmega(uint8_t, uint8_t, mavlink_message_t *last_msg); static void mavlink_test_ardupilotmega(uint8_t, uint8_t, mavlink_message_t *last_msg);
static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{ {
mavlink_test_common(system_id, component_id, last_msg); mavlink_test_common(system_id, component_id, last_msg);
mavlink_test_uAvionix(system_id, component_id, last_msg); mavlink_test_uAvionix(system_id, component_id, last_msg);
mavlink_test_icarous(system_id, component_id, last_msg);
mavlink_test_ardupilotmega(system_id, component_id, last_msg); mavlink_test_ardupilotmega(system_id, component_id, last_msg);
} }
#endif #endif
#include "../common/testsuite.h" #include "../common/testsuite.h"
#include "../uAvionix/testsuite.h" #include "../uAvionix/testsuite.h"
#include "../icarous/testsuite.h"
static void mavlink_test_sensor_offsets(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) static void mavlink_test_sensor_offsets(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
......
/** @file
* @brief MAVLink comm protocol generated from icarous.xml
* @see http://mavlink.org
*/
#pragma once
#ifndef MAVLINK_ICAROUS_H
#define MAVLINK_ICAROUS_H
#ifndef MAVLINK_H
#error Wrong include order: MAVLINK_ICAROUS.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
#endif
#undef MAVLINK_THIS_XML_IDX
#define MAVLINK_THIS_XML_IDX 3
#ifdef __cplusplus
extern "C" {
#endif
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS {}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {{42000, 227, 1, 0, 0, 0}, {42001, 239, 46, 0, 0, 0}}
#endif
#include "../protocol.h"
#define MAVLINK_ENABLED_ICAROUS
// ENUM DEFINITIONS
/** @brief */
#ifndef HAVE_ENUM_ICAROUS_TRACK_BAND_TYPES
#define HAVE_ENUM_ICAROUS_TRACK_BAND_TYPES
typedef enum ICAROUS_TRACK_BAND_TYPES
{
ICAROUS_TRACK_BAND_TYPE_NONE=0, /* | */
ICAROUS_TRACK_BAND_TYPE_NEAR=1, /* | */
ICAROUS_TRACK_BAND_TYPE_RECOVERY=2, /* | */
ICAROUS_TRACK_BAND_TYPES_ENUM_END=3, /* | */
} ICAROUS_TRACK_BAND_TYPES;
#endif
/** @brief */
#ifndef HAVE_ENUM_ICAROUS_FMS_STATE
#define HAVE_ENUM_ICAROUS_FMS_STATE
typedef enum ICAROUS_FMS_STATE
{
ICAROUS_FMS_STATE_IDLE=0, /* | */
ICAROUS_FMS_STATE_TAKEOFF=1, /* | */
ICAROUS_FMS_STATE_CLIMB=2, /* | */
ICAROUS_FMS_STATE_CRUISE=3, /* | */
ICAROUS_FMS_STATE_APPROACH=4, /* | */
ICAROUS_FMS_STATE_LAND=5, /* | */
ICAROUS_FMS_STATE_ENUM_END=6, /* | */
} ICAROUS_FMS_STATE;
#endif
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
// MESSAGE DEFINITIONS
#include "./mavlink_msg_icarous_heartbeat.h"
#include "./mavlink_msg_icarous_kinematic_bands.h"
// base include
#undef MAVLINK_THIS_XML_IDX
#define MAVLINK_THIS_XML_IDX 3
#if MAVLINK_THIS_XML_IDX == MAVLINK_PRIMARY_XML_IDX
# define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_ICAROUS_HEARTBEAT, MAVLINK_MESSAGE_INFO_ICAROUS_KINEMATIC_BANDS}
# define MAVLINK_MESSAGE_NAMES {{ "ICAROUS_HEARTBEAT", 42000 }, { "ICAROUS_KINEMATIC_BANDS", 42001 }}
# if MAVLINK_COMMAND_24BIT
# include "../mavlink_get_info.h"
# endif
#endif
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // MAVLINK_ICAROUS_H
/** @file
* @brief MAVLink comm protocol built from icarous.xml
* @see http://mavlink.org
*/
#pragma once
#ifndef MAVLINK_H
#define MAVLINK_H
#define MAVLINK_PRIMARY_XML_IDX 3
#ifndef MAVLINK_STX
#define MAVLINK_STX 253
#endif
#ifndef MAVLINK_ENDIAN
#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
#endif
#ifndef MAVLINK_ALIGNED_FIELDS
#define MAVLINK_ALIGNED_FIELDS 1
#endif
#ifndef MAVLINK_CRC_EXTRA
#define MAVLINK_CRC_EXTRA 1
#endif
#ifndef MAVLINK_COMMAND_24BIT
#define MAVLINK_COMMAND_24BIT 1
#endif
#include "version.h"
#include "icarous.h"
#endif // MAVLINK_H
#pragma once
// MESSAGE ICAROUS_HEARTBEAT PACKING
#define MAVLINK_MSG_ID_ICAROUS_HEARTBEAT 42000
MAVPACKED(
typedef struct __mavlink_icarous_heartbeat_t {
uint8_t status; /*< See the FMS_STATE enum.*/
}) mavlink_icarous_heartbeat_t;
#define MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN 1
#define MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN 1
#define MAVLINK_MSG_ID_42000_LEN 1
#define MAVLINK_MSG_ID_42000_MIN_LEN 1
#define MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC 227
#define MAVLINK_MSG_ID_42000_CRC 227
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ICAROUS_HEARTBEAT { \
42000, \
"ICAROUS_HEARTBEAT", \
1, \
{ { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_icarous_heartbeat_t, status) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ICAROUS_HEARTBEAT { \
"ICAROUS_HEARTBEAT", \
1, \
{ { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_icarous_heartbeat_t, status) }, \
} \
}
#endif
/**
* @brief Pack a icarous_heartbeat 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 status See the FMS_STATE enum.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_icarous_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN];
_mav_put_uint8_t(buf, 0, status);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN);
#else
mavlink_icarous_heartbeat_t packet;
packet.status = status;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ICAROUS_HEARTBEAT;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC);
}
/**
* @brief Pack a icarous_heartbeat 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 status See the FMS_STATE enum.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_icarous_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN];
_mav_put_uint8_t(buf, 0, status);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN);
#else
mavlink_icarous_heartbeat_t packet;
packet.status = status;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ICAROUS_HEARTBEAT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC);
}
/**
* @brief Encode a icarous_heartbeat 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 icarous_heartbeat C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_icarous_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_icarous_heartbeat_t* icarous_heartbeat)
{
return mavlink_msg_icarous_heartbeat_pack(system_id, component_id, msg, icarous_heartbeat->status);
}
/**
* @brief Encode a icarous_heartbeat 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 icarous_heartbeat C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_icarous_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_icarous_heartbeat_t* icarous_heartbeat)
{
return mavlink_msg_icarous_heartbeat_pack_chan(system_id, component_id, chan, msg, icarous_heartbeat->status);
}
/**
* @brief Send a icarous_heartbeat message
* @param chan MAVLink channel to send the message
*
* @param status See the FMS_STATE enum.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_icarous_heartbeat_send(mavlink_channel_t chan, uint8_t status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN];
_mav_put_uint8_t(buf, 0, status);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT, buf, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC);
#else
mavlink_icarous_heartbeat_t packet;
packet.status = status;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC);
#endif
}
/**
* @brief Send a icarous_heartbeat message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_icarous_heartbeat_send_struct(mavlink_channel_t chan, const mavlink_icarous_heartbeat_t* icarous_heartbeat)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_icarous_heartbeat_send(chan, icarous_heartbeat->status);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT, (const char *)icarous_heartbeat, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC);
#endif
}
#if MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_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_icarous_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, status);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT, buf, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC);
#else
mavlink_icarous_heartbeat_t *packet = (mavlink_icarous_heartbeat_t *)msgbuf;
packet->status = status;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC);
#endif
}
#endif
#endif
// MESSAGE ICAROUS_HEARTBEAT UNPACKING
/**
* @brief Get field status from icarous_heartbeat message
*
* @return See the FMS_STATE enum.
*/
static inline uint8_t mavlink_msg_icarous_heartbeat_get_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Decode a icarous_heartbeat message into a struct
*
* @param msg The message to decode
* @param icarous_heartbeat C-struct to decode the message contents into
*/
static inline void mavlink_msg_icarous_heartbeat_decode(const mavlink_message_t* msg, mavlink_icarous_heartbeat_t* icarous_heartbeat)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
icarous_heartbeat->status = mavlink_msg_icarous_heartbeat_get_status(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN? msg->len : MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN;
memset(icarous_heartbeat, 0, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN);
memcpy(icarous_heartbeat, _MAV_PAYLOAD(msg), len);
#endif
}
This diff is collapsed.
/** @file
* @brief MAVLink comm protocol testsuite generated from icarous.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#pragma once
#ifndef ICAROUS_TESTSUITE_H
#define ICAROUS_TESTSUITE_H
#ifdef __cplusplus
extern "C" {
#endif
#ifndef MAVLINK_TEST_ALL
#define MAVLINK_TEST_ALL
static void mavlink_test_icarous(uint8_t, uint8_t, mavlink_message_t *last_msg);
static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_icarous(system_id, component_id, last_msg);
}
#endif
static void mavlink_test_icarous_heartbeat(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_ICAROUS_HEARTBEAT >= 256) {
return;
}
#endif
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_icarous_heartbeat_t packet_in = {
5
};
mavlink_icarous_heartbeat_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.status = packet_in.status;
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
// cope with extensions
memset(MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN);
}
#endif
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_icarous_heartbeat_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_icarous_heartbeat_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_icarous_heartbeat_pack(system_id, component_id, &msg , packet1.status );
mavlink_msg_icarous_heartbeat_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_icarous_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.status );
mavlink_msg_icarous_heartbeat_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_icarous_heartbeat_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_icarous_heartbeat_send(MAVLINK_COMM_1 , packet1.status );
mavlink_msg_icarous_heartbeat_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_icarous_kinematic_bands(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_ICAROUS_KINEMATIC_BANDS >= 256) {
return;
}
#endif
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_icarous_kinematic_bands_t packet_in = {
17.0,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,125,192,3,70,137,204
};
mavlink_icarous_kinematic_bands_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.min1 = packet_in.min1;
packet1.max1 = packet_in.max1;
packet1.min2 = packet_in.min2;
packet1.max2 = packet_in.max2;
packet1.min3 = packet_in.min3;
packet1.max3 = packet_in.max3;
packet1.min4 = packet_in.min4;
packet1.max4 = packet_in.max4;
packet1.min5 = packet_in.min5;
packet1.max5 = packet_in.max5;
packet1.numBands = packet_in.numBands;
packet1.type1 = packet_in.type1;
packet1.type2 = packet_in.type2;
packet1.type3 = packet_in.type3;
packet1.type4 = packet_in.type4;
packet1.type5 = packet_in.type5;
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
// cope with extensions
memset(MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN);
}
#endif
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_icarous_kinematic_bands_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_icarous_kinematic_bands_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_icarous_kinematic_bands_pack(system_id, component_id, &msg , packet1.numBands , packet1.type1 , packet1.min1 , packet1.max1 , packet1.type2 , packet1.min2 , packet1.max2 , packet1.type3 , packet1.min3 , packet1.max3 , packet1.type4 , packet1.min4 , packet1.max4 , packet1.type5 , packet1.min5 , packet1.max5 );
mavlink_msg_icarous_kinematic_bands_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_icarous_kinematic_bands_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.numBands , packet1.type1 , packet1.min1 , packet1.max1 , packet1.type2 , packet1.min2 , packet1.max2 , packet1.type3 , packet1.min3 , packet1.max3 , packet1.type4 , packet1.min4 , packet1.max4 , packet1.type5 , packet1.min5 , packet1.max5 );
mavlink_msg_icarous_kinematic_bands_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_icarous_kinematic_bands_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_icarous_kinematic_bands_send(MAVLINK_COMM_1 , packet1.numBands , packet1.type1 , packet1.min1 , packet1.max1 , packet1.type2 , packet1.min2 , packet1.max2 , packet1.type3 , packet1.min3 , packet1.max3 , packet1.type4 , packet1.min4 , packet1.max4 , packet1.type5 , packet1.min5 , packet1.max5 );
mavlink_msg_icarous_kinematic_bands_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_icarous(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_icarous_heartbeat(system_id, component_id, last_msg);
mavlink_test_icarous_kinematic_bands(system_id, component_id, last_msg);
}
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // ICAROUS_TESTSUITE_H
/** @file
* @brief MAVLink comm protocol built from icarous.xml
* @see http://mavlink.org
*/
#pragma once
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Feb 08 2018"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
#endif // MAVLINK_VERSION_H
...@@ -678,7 +678,11 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, ...@@ -678,7 +678,11 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
rxmsg->msgid = c; rxmsg->msgid = c;
mavlink_update_checksum(rxmsg, c); mavlink_update_checksum(rxmsg, c);
if (status->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) { if (status->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) {
status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID3; if(rxmsg->len > 0){
status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID3;
} else {
status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
}
#ifdef MAVLINK_CHECK_MESSAGE_LENGTH #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(rxmsg->msgid)) if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(rxmsg->msgid))
{ {
...@@ -699,9 +703,13 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, ...@@ -699,9 +703,13 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
break; break;
case MAVLINK_PARSE_STATE_GOT_MSGID2: case MAVLINK_PARSE_STATE_GOT_MSGID2:
rxmsg->msgid |= c<<16; rxmsg->msgid |= ((uint32_t)c)<<16;
mavlink_update_checksum(rxmsg, c); mavlink_update_checksum(rxmsg, c);
status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID3; if(rxmsg->len > 0){
status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID3;
} else {
status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
}
#ifdef MAVLINK_CHECK_MESSAGE_LENGTH #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(rxmsg->msgid)) if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(rxmsg->msgid))
{ {
......
...@@ -51,7 +51,7 @@ namespace mavlink { ...@@ -51,7 +51,7 @@ namespace mavlink {
#endif #endif
typedef struct { typedef struct {
unsigned int sz[2]; uint32_t sz[2];
uint32_t counter[8]; uint32_t counter[8];
union { union {
unsigned char save_bytes[64]; unsigned char save_bytes[64];
......
...@@ -3,6 +3,7 @@ ...@@ -3,6 +3,7 @@
<include>common.xml</include> <include>common.xml</include>
<!-- vendors --> <!-- vendors -->
<include>uAvionix.xml</include> <include>uAvionix.xml</include>
<include>icarous.xml</include>
<dialect>2</dialect> <dialect>2</dialect>
<!-- note that APM specific messages should use the command id range from 150 to 250, to leave plenty of room for growth of common.xml If you prototype a message here, then you should consider if it is general enough to move into common.xml later --> <!-- note that APM specific messages should use the command id range from 150 to 250, to leave plenty of room for growth of common.xml If you prototype a message here, then you should consider if it is general enough to move into common.xml later -->
<enums> <enums>
...@@ -918,6 +919,84 @@ ...@@ -918,6 +919,84 @@
<description>Stalling and steering towards the land point</description> <description>Stalling and steering towards the land point</description>
</entry> </entry>
</enum> </enum>
<enum name="PLANE_MODE">
<description>A mapping of plane flight modes for custom_mode field of heartbeat</description>
<entry value="0" name="PLANE_MODE_MANUAL"/>
<entry value="1" name="PLANE_MODE_CIRCLE"/>
<entry value="2" name="PLANE_MODE_STABILIZE"/>
<entry value="3" name="PLANE_MODE_TRAINING"/>
<entry value="4" name="PLANE_MODE_ACRO"/>
<entry value="5" name="PLANE_MODE_FLY_BY_WIRE_A"/>
<entry value="6" name="PLANE_MODE_FLY_BY_WIRE_B"/>
<entry value="7" name="PLANE_MODE_CRUISE"/>
<entry value="8" name="PLANE_MODE_AUTOTUNE"/>
<entry value="10" name="PLANE_MODE_AUTO"/>
<entry value="11" name="PLANE_MODE_RTL"/>
<entry value="12" name="PLANE_MODE_LOITER"/>
<entry value="14" name="PLANE_MODE_AVOID_ADSB"/>
<entry value="15" name="PLANE_MODE_GUIDED"/>
<entry value="16" name="PLANE_MODE_INITIALIZING"/>
<entry value="17" name="PLANE_MODE_QSTABILIZE"/>
<entry value="18" name="PLANE_MODE_QHOVER"/>
<entry value="19" name="PLANE_MODE_QLOITER"/>
<entry value="20" name="PLANE_MODE_QLAND"/>
<entry value="21" name="PLANE_MODE_QRTL"/>
</enum>
<enum name="COPTER_MODE">
<description>A mapping of copter flight modes for custom_mode field of heartbeat</description>
<entry value="0" name="COPTER_MODE_STABILIZE"/>
<entry value="1" name="COPTER_MODE_ACRO"/>
<entry value="2" name="COPTER_MODE_ALT_HOLD"/>
<entry value="3" name="COPTER_MODE_AUTO"/>
<entry value="4" name="COPTER_MODE_GUIDED"/>
<entry value="5" name="COPTER_MODE_LOITER"/>
<entry value="6" name="COPTER_MODE_RTL"/>
<entry value="7" name="COPTER_MODE_CIRCLE"/>
<entry value="9" name="COPTER_MODE_LAND"/>
<entry value="11" name="COPTER_MODE_DRIFT"/>
<entry value="13" name="COPTER_MODE_SPORT"/>
<entry value="14" name="COPTER_MODE_FLIP"/>
<entry value="15" name="COPTER_MODE_AUTOTUNE"/>
<entry value="16" name="COPTER_MODE_POSHOLD"/>
<entry value="17" name="COPTER_MODE_BRAKE"/>
<entry value="18" name="COPTER_MODE_THROW"/>
<entry value="19" name="COPTER_MODE_AVOID_ADSB"/>
<entry value="20" name="COPTER_MODE_GUIDED_NOGPS"/>
<entry value="21" name="COPTER_MODE_SMART_RTL"/>
</enum>
<enum name="SUB_MODE">
<description>A mapping of sub flight modes for custom_mode field of heartbeat</description>
<entry value="0" name="SUB_MODE_STABILIZE"/>
<entry value="1" name="SUB_MODE_ACRO"/>
<entry value="2" name="SUB_MODE_ALT_HOLD"/>
<entry value="3" name="SUB_MODE_AUTO"/>
<entry value="4" name="SUB_MODE_GUIDED"/>
<entry value="7" name="SUB_MODE_CIRCLE"/>
<entry value="9" name="SUB_MODE_SURFACE"/>
<entry value="16" name="SUB_MODE_POSHOLD"/>
<entry value="19" name="SUB_MODE_MANUAL"/>
</enum>
<enum name="ROVER_MODE">
<description>A mapping of rover flight modes for custom_mode field of heartbeat</description>
<entry value="0" name="ROVER_MODE_MANUAL"/>
<entry value="1" name="ROVER_MODE_ACRO"/>
<entry value="3" name="ROVER_MODE_STEERING"/>
<entry value="4" name="ROVER_MODE_HOLD"/>
<entry value="10" name="ROVER_MODE_AUTO"/>
<entry value="11" name="ROVER_MODE_RTL"/>
<entry value="12" name="ROVER_MODE_SMART_RTL"/>
<entry value="15" name="ROVER_MODE_GUIDED"/>
<entry value="16" name="ROVER_MODE_INITIALIZING"/>
</enum>
<enum name="TRACKER_MODE">
<description>A mapping of antenna tracker flight modes for custom_mode field of heartbeat</description>
<entry value="0" name="TRACKER_MODE_MANUAL"/>
<entry value="1" name="TRACKER_MODE_STOP"/>
<entry value="2" name="TRACKER_MODE_SCAN"/>
<entry value="3" name="TRACKER_MODE_SERVO_TEST"/>
<entry value="10" name="TRACKER_MODE_AUTO"/>
<entry value="16" name="TRACKER_MODE_INITIALIZING"/>
</enum>
</enums> </enums>
<messages> <messages>
<message id="150" name="SENSOR_OFFSETS"> <message id="150" name="SENSOR_OFFSETS">
...@@ -1460,18 +1539,18 @@ ...@@ -1460,18 +1539,18 @@
<!-- camera vision based attitude and position delta message --> <!-- camera vision based attitude and position delta message -->
<message id="11011" name="VISION_POSITION_DELTA"> <message id="11011" name="VISION_POSITION_DELTA">
<description>camera vision based attitude and position deltas</description> <description>camera vision based attitude and position deltas</description>
<field name="time_usec" type="uint64_t">Timestamp (microseconds, synced to UNIX time or since system boot)</field> <field name="time_usec" type="uint64_t" units="us">Timestamp (microseconds, synced to UNIX time or since system boot)</field>
<field name="time_delta_usec" type="uint64_t">Time in microseconds since the last reported camera frame</field> <field name="time_delta_usec" type="uint64_t" units="us">Time in microseconds since the last reported camera frame</field>
<field type="float[3]" name="angle_delta">Defines a rotation vector in body frame that rotates the vehicle from the previous to the current orientation</field> <field type="float[3]" name="angle_delta">Defines a rotation vector in body frame that rotates the vehicle from the previous to the current orientation</field>
<field type="float[3]" name="position_delta">Change in position in meters from previous to current frame rotated into body frame (0=forward, 1=right, 2=down)</field> <field type="float[3]" name="position_delta" units="m">Change in position in meters from previous to current frame rotated into body frame (0=forward, 1=right, 2=down)</field>
<field type="float" name="confidence">normalised confidence value from 0 to 100</field> <field type="float" name="confidence" units="%">normalised confidence value from 0 to 100</field>
</message> </message>
<!-- Angle of Attack and Side Slip Angle message --> <!-- Angle of Attack and Side Slip Angle message -->
<message id="11020" name="AOA_SSA"> <message id="11020" name="AOA_SSA">
<description>Angle of Attack and Side Slip Angle</description> <description>Angle of Attack and Side Slip Angle</description>
<field type="uint64_t" name="time_usec">Timestamp (micros since boot or Unix epoch)</field> <field type="uint64_t" name="time_usec" units="us">Timestamp (micros since boot or Unix epoch)</field>
<field name="AOA" type="float">Angle of Attack (degrees)</field> <field name="AOA" type="float" units="deg">Angle of Attack (degrees)</field>
<field name="SSA" type="float">Side Slip Angle (degrees)</field> <field name="SSA" type="float" units="deg">Side Slip Angle (degrees)</field>
</message> </message>
</messages> </messages>
</mavlink> </mavlink>
This diff is collapsed.
<?xml version="1.0"?>
<mavlink>
<!-- ICAROUS message definitions -->
<!-- https://github.com/nasa/icarous -->
<!-- email contacts: Swee Balachandran: swee.balachandran@nianet.org -->
<!-- Cesar Munoz: cesar.a.munoz@nasa.gov -->
<!-- mavlink ID range 42000 - 42099 -->
<enums>
<enum name="ICAROUS_TRACK_BAND_TYPES">
<entry name="ICAROUS_TRACK_BAND_TYPE_NONE" value="0"/>
<entry name="ICAROUS_TRACK_BAND_TYPE_NEAR" value="1"/>
<entry name="ICAROUS_TRACK_BAND_TYPE_RECOVERY" value="2"/>
</enum>
<enum name="ICAROUS_FMS_STATE">
<entry name="ICAROUS_FMS_STATE_IDLE" value="0"/>
<entry name="ICAROUS_FMS_STATE_TAKEOFF" value="1"/>
<entry name="ICAROUS_FMS_STATE_CLIMB" value="2"/>
<entry name="ICAROUS_FMS_STATE_CRUISE" value="3"/>
<entry name="ICAROUS_FMS_STATE_APPROACH" value="4"/>
<entry name="ICAROUS_FMS_STATE_LAND" value="5"/>
</enum>
</enums>
<messages>
<message id="42000" name="ICAROUS_HEARTBEAT">
<description>ICAROUS heartbeat</description>
<field type="uint8_t" name="status" enum="ICAROUS_FMS_STATE">See the FMS_STATE enum.</field>
</message>
<message id="42001" name="ICAROUS_KINEMATIC_BANDS">
<description>Kinematic multi bands (track) output from Daidalus</description>
<field type="int8_t" name="numBands">Number of track bands</field>
<field type="uint8_t" name="type1" enum="ICAROUS_TRACK_BAND_TYPES">See the TRACK_BAND_TYPES enum.</field>
<field type="float" name="min1" units="deg">min angle (degrees)</field>
<field type="float" name="max1" units="deg">max angle (degrees)</field>
<field type="uint8_t" name="type2" enum="ICAROUS_TRACK_BAND_TYPES">See the TRACK_BAND_TYPES enum.</field>
<field type="float" name="min2" units="deg">min angle (degrees)</field>
<field type="float" name="max2" units="deg">max angle (degrees)</field>
<field type="uint8_t" name="type3" enum="ICAROUS_TRACK_BAND_TYPES">See the TRACK_BAND_TYPES enum.</field>
<field type="float" name="min3" units="deg">min angle (degrees)</field>
<field type="float" name="max3" units="deg">max angle (degrees)</field>
<field type="uint8_t" name="type4" enum="ICAROUS_TRACK_BAND_TYPES">See the TRACK_BAND_TYPES enum.</field>
<field type="float" name="min4" units="deg">min angle (degrees)</field>
<field type="float" name="max4" units="deg">max angle (degrees)</field>
<field type="uint8_t" name="type5" enum="ICAROUS_TRACK_BAND_TYPES">See the TRACK_BAND_TYPES enum.</field>
<field type="float" name="min5" units="deg">min angle (degrees)</field>
<field type="float" name="max5" units="deg">max angle (degrees)</field>
</message>
</messages>
</mavlink>
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