Add files via upload

pull/431/head
JohhnGoblin 2025-01-05 01:12:24 -06:00 committed by GitHub
parent cbeb0b8f7c
commit 4ebf8be203
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
18 changed files with 4023 additions and 0 deletions

View File

@ -0,0 +1,95 @@
#pragma once
#if defined(MAVLINK_USE_CXX_NAMESPACE)
namespace mavlink {
#elif defined(__cplusplus)
extern "C" {
#endif
// Visual Studio versions before 2010 don't have stdint.h, so we just error out.
#if (defined _MSC_VER) && (_MSC_VER < 1600)
#error "The C-MAVLink implementation requires Visual Studio 2010 or greater"
#endif
#include <stdint.h>
/**
*
* CALCULATE THE CHECKSUM
*
*/
#define X25_INIT_CRC 0xffff
#define X25_VALIDATE_CRC 0xf0b8
#ifndef HAVE_CRC_ACCUMULATE
/**
* @brief Accumulate the CRC16_MCRF4XX checksum by adding one char at a time.
*
* The checksum function adds the hash of one char at a time to the
* 16 bit checksum (uint16_t).
*
* @param data new char to hash
* @param crcAccum the already accumulated checksum
**/
static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
{
/*Accumulate one byte of data into the CRC*/
uint8_t tmp;
tmp = data ^ (uint8_t)(*crcAccum &0xff);
tmp ^= (tmp<<4);
*crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
}
#endif
/**
* @brief Initialize the buffer for the MCRF4XX CRC16
*
* @param crcAccum the 16 bit MCRF4XX CRC16
*/
static inline void crc_init(uint16_t* crcAccum)
{
*crcAccum = X25_INIT_CRC;
}
/**
* @brief Calculates the CRC16_MCRF4XX checksum on a byte buffer
*
* @param pBuffer buffer containing the byte array to hash
* @param length length of the byte array
* @return the checksum over the buffer bytes
**/
static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
{
uint16_t crcTmp;
crc_init(&crcTmp);
while (length--) {
crc_accumulate(*pBuffer++, &crcTmp);
}
return crcTmp;
}
/**
* @brief Accumulate the MCRF4XX CRC16 by adding an array of bytes
*
* The checksum function adds the hash of one char at a time to the
* 16 bit checksum (uint16_t).
*
* @param data new bytes to hash
* @param crcAccum the already accumulated checksum
**/
static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length)
{
const uint8_t *p = (const uint8_t *)pBuffer;
while (length--) {
crc_accumulate(*p++, crcAccum);
}
}
#if defined(MAVLINK_USE_CXX_NAMESPACE) || defined(__cplusplus)
}
#endif

View File

@ -0,0 +1,212 @@
#pragma once
#ifndef MAVLINK_NO_CONVERSION_HELPERS
/* enable math defines on Windows */
#ifdef _MSC_VER
#ifndef _USE_MATH_DEFINES
#define _USE_MATH_DEFINES
#endif
#endif
#include <math.h>
#ifndef M_PI_2
#define M_PI_2 ((float)asin(1))
#endif
/**
* @file mavlink_conversions.h
*
* These conversion functions follow the NASA rotation standards definition file
* available online.
*
* Their intent is to lower the barrier for MAVLink adopters to use gimbal-lock free
* (both rotation matrices, sometimes called DCM, and quaternions are gimbal-lock free)
* rotation representations. Euler angles (roll, pitch, yaw) will be phased out of the
* protocol as widely as possible.
*
* @author James Goppert
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
/**
* Converts a quaternion to a rotation matrix
*
* @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
* @param dcm a 3x3 rotation matrix
*/
MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3])
{
double a = (double)quaternion[0];
double b = (double)quaternion[1];
double c = (double)quaternion[2];
double d = (double)quaternion[3];
double aSq = a * a;
double bSq = b * b;
double cSq = c * c;
double dSq = d * d;
dcm[0][0] = aSq + bSq - cSq - dSq;
dcm[0][1] = 2 * (b * c - a * d);
dcm[0][2] = 2 * (a * c + b * d);
dcm[1][0] = 2 * (b * c + a * d);
dcm[1][1] = aSq - bSq + cSq - dSq;
dcm[1][2] = 2 * (c * d - a * b);
dcm[2][0] = 2 * (b * d - a * c);
dcm[2][1] = 2 * (a * b + c * d);
dcm[2][2] = aSq - bSq - cSq + dSq;
}
/**
* Converts a rotation matrix to euler angles
*
* @param dcm a 3x3 rotation matrix
* @param roll the roll angle in radians
* @param pitch the pitch angle in radians
* @param yaw the yaw angle in radians
*/
MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw)
{
float phi, theta, psi;
theta = asinf(-dcm[2][0]);
if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) {
phi = 0.0f;
psi = (atan2f(dcm[1][2] - dcm[0][1],
dcm[0][2] + dcm[1][1]) + phi);
} else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) {
phi = 0.0f;
psi = atan2f(dcm[1][2] - dcm[0][1],
dcm[0][2] + dcm[1][1] - phi);
} else {
phi = atan2f(dcm[2][1], dcm[2][2]);
psi = atan2f(dcm[1][0], dcm[0][0]);
}
*roll = phi;
*pitch = theta;
*yaw = psi;
}
/**
* Converts a quaternion to euler angles
*
* @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
* @param roll the roll angle in radians
* @param pitch the pitch angle in radians
* @param yaw the yaw angle in radians
*/
MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float* roll, float* pitch, float* yaw)
{
float dcm[3][3];
mavlink_quaternion_to_dcm(quaternion, dcm);
mavlink_dcm_to_euler((const float(*)[3])dcm, roll, pitch, yaw);
}
/**
* Converts euler angles to a quaternion
*
* @param roll the roll angle in radians
* @param pitch the pitch angle in radians
* @param yaw the yaw angle in radians
* @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
*/
MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4])
{
float cosPhi_2 = cosf(roll / 2);
float sinPhi_2 = sinf(roll / 2);
float cosTheta_2 = cosf(pitch / 2);
float sinTheta_2 = sinf(pitch / 2);
float cosPsi_2 = cosf(yaw / 2);
float sinPsi_2 = sinf(yaw / 2);
quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 +
sinPhi_2 * sinTheta_2 * sinPsi_2);
quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 -
cosPhi_2 * sinTheta_2 * sinPsi_2);
quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 +
sinPhi_2 * cosTheta_2 * sinPsi_2);
quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 -
sinPhi_2 * sinTheta_2 * cosPsi_2);
}
/**
* Converts a rotation matrix to a quaternion
* Reference:
* - Shoemake, Quaternions,
* http://www.cs.ucr.edu/~vbz/resources/quatut.pdf
*
* @param dcm a 3x3 rotation matrix
* @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
*/
MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4])
{
float tr = dcm[0][0] + dcm[1][1] + dcm[2][2];
if (tr > 0.0f) {
float s = sqrtf(tr + 1.0f);
quaternion[0] = s * 0.5f;
s = 0.5f / s;
quaternion[1] = (dcm[2][1] - dcm[1][2]) * s;
quaternion[2] = (dcm[0][2] - dcm[2][0]) * s;
quaternion[3] = (dcm[1][0] - dcm[0][1]) * s;
} else {
/* Find maximum diagonal element in dcm
* store index in dcm_i */
int dcm_i = 0;
int i;
for (i = 1; i < 3; i++) {
if (dcm[i][i] > dcm[dcm_i][dcm_i]) {
dcm_i = i;
}
}
int dcm_j = (dcm_i + 1) % 3;
int dcm_k = (dcm_i + 2) % 3;
float s = sqrtf((dcm[dcm_i][dcm_i] - dcm[dcm_j][dcm_j] -
dcm[dcm_k][dcm_k]) + 1.0f);
quaternion[dcm_i + 1] = s * 0.5f;
s = 0.5f / s;
quaternion[dcm_j + 1] = (dcm[dcm_i][dcm_j] + dcm[dcm_j][dcm_i]) * s;
quaternion[dcm_k + 1] = (dcm[dcm_k][dcm_i] + dcm[dcm_i][dcm_k]) * s;
quaternion[0] = (dcm[dcm_k][dcm_j] - dcm[dcm_j][dcm_k]) * s;
}
}
/**
* Converts euler angles to a rotation matrix
*
* @param roll the roll angle in radians
* @param pitch the pitch angle in radians
* @param yaw the yaw angle in radians
* @param dcm a 3x3 rotation matrix
*/
MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3])
{
float cosPhi = cosf(roll);
float sinPhi = sinf(roll);
float cosThe = cosf(pitch);
float sinThe = sinf(pitch);
float cosPsi = cosf(yaw);
float sinPsi = sinf(yaw);
dcm[0][0] = cosThe * cosPsi;
dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi;
dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi;
dcm[1][0] = cosThe * sinPsi;
dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi;
dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi;
dcm[2][0] = -sinThe;
dcm[2][1] = sinPhi * cosThe;
dcm[2][2] = cosPhi * cosThe;
}
#endif // MAVLINK_NO_CONVERSION_HELPERS

View File

@ -0,0 +1,83 @@
#pragma once
#ifdef MAVLINK_USE_MESSAGE_INFO
#define MAVLINK_HAVE_GET_MESSAGE_INFO
/*
return the message_info struct for a message
*/
MAVLINK_HELPER const mavlink_message_info_t *mavlink_get_message_info_by_id(uint32_t msgid)
{
static const mavlink_message_info_t mavlink_message_info[] = MAVLINK_MESSAGE_INFO;
/*
use a bisection search to find the right entry. A perfect hash may be better
Note that this assumes the table is sorted with primary key msgid
*/
const uint32_t count = sizeof(mavlink_message_info)/sizeof(mavlink_message_info[0]);
if (count == 0) {
return NULL;
}
uint32_t low=0, high=count-1;
while (low < high) {
uint32_t mid = (low+high)/2;
if (msgid < mavlink_message_info[mid].msgid) {
high = mid;
continue;
}
if (msgid > mavlink_message_info[mid].msgid) {
low = mid+1;
continue;
}
return &mavlink_message_info[mid];
}
if (mavlink_message_info[low].msgid == msgid) {
return &mavlink_message_info[low];
}
return NULL;
}
/*
return the message_info struct for a message
*/
MAVLINK_HELPER const mavlink_message_info_t *mavlink_get_message_info(const mavlink_message_t *msg)
{
return mavlink_get_message_info_by_id(msg->msgid);
}
/*
return the message_info struct for a message
*/
MAVLINK_HELPER const mavlink_message_info_t *mavlink_get_message_info_by_name(const char *name)
{
static const struct { const char *name; uint32_t msgid; } mavlink_message_names[] = MAVLINK_MESSAGE_NAMES;
/*
use a bisection search to find the right entry. A perfect hash may be better
Note that this assumes the table is sorted with primary key name
*/
const uint32_t count = sizeof(mavlink_message_names)/sizeof(mavlink_message_names[0]);
if (count == 0) {
return NULL;
}
uint32_t low=0, high=count-1;
while (low < high) {
uint32_t mid = (low+high)/2;
int cmp = strcmp(mavlink_message_names[mid].name, name);
if (cmp > 0) {
high = mid;
continue;
}
if (cmp < 0) {
low = mid+1;
continue;
}
low = mid;
break;
}
if (strcmp(mavlink_message_names[low].name, name) == 0) {
return mavlink_get_message_info_by_id(mavlink_message_names[low].msgid);
}
return NULL;
}
#endif // MAVLINK_USE_MESSAGE_INFO

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,235 @@
#pragma once
/*
sha-256 implementation for MAVLink based on Heimdal sources, with
modifications to suit mavlink headers
*/
/*
* Copyright (c) 1995 - 2001 Kungliga Tekniska Högskolan
* (Royal Institute of Technology, Stockholm, Sweden).
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the Institute nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*/
/*
allow implementation to provide their own sha256 with the same API
*/
#ifndef HAVE_MAVLINK_SHA256
#ifdef MAVLINK_USE_CXX_NAMESPACE
namespace mavlink {
#endif
#ifndef MAVLINK_HELPER
#define MAVLINK_HELPER
#endif
typedef struct {
uint32_t sz[2];
uint32_t counter[8];
union {
unsigned char save_bytes[64];
uint32_t save_u32[16];
} u;
} mavlink_sha256_ctx;
#define Ch(x,y,z) (((x) & (y)) ^ ((~(x)) & (z)))
#define Maj(x,y,z) (((x) & (y)) ^ ((x) & (z)) ^ ((y) & (z)))
#define ROTR(x,n) (((x)>>(n)) | ((x) << (32 - (n))))
#define Sigma0(x) (ROTR(x,2) ^ ROTR(x,13) ^ ROTR(x,22))
#define Sigma1(x) (ROTR(x,6) ^ ROTR(x,11) ^ ROTR(x,25))
#define sigma0(x) (ROTR(x,7) ^ ROTR(x,18) ^ ((x)>>3))
#define sigma1(x) (ROTR(x,17) ^ ROTR(x,19) ^ ((x)>>10))
static const uint32_t mavlink_sha256_constant_256[64] = {
0x428a2f98, 0x71374491, 0xb5c0fbcf, 0xe9b5dba5,
0x3956c25b, 0x59f111f1, 0x923f82a4, 0xab1c5ed5,
0xd807aa98, 0x12835b01, 0x243185be, 0x550c7dc3,
0x72be5d74, 0x80deb1fe, 0x9bdc06a7, 0xc19bf174,
0xe49b69c1, 0xefbe4786, 0x0fc19dc6, 0x240ca1cc,
0x2de92c6f, 0x4a7484aa, 0x5cb0a9dc, 0x76f988da,
0x983e5152, 0xa831c66d, 0xb00327c8, 0xbf597fc7,
0xc6e00bf3, 0xd5a79147, 0x06ca6351, 0x14292967,
0x27b70a85, 0x2e1b2138, 0x4d2c6dfc, 0x53380d13,
0x650a7354, 0x766a0abb, 0x81c2c92e, 0x92722c85,
0xa2bfe8a1, 0xa81a664b, 0xc24b8b70, 0xc76c51a3,
0xd192e819, 0xd6990624, 0xf40e3585, 0x106aa070,
0x19a4c116, 0x1e376c08, 0x2748774c, 0x34b0bcb5,
0x391c0cb3, 0x4ed8aa4a, 0x5b9cca4f, 0x682e6ff3,
0x748f82ee, 0x78a5636f, 0x84c87814, 0x8cc70208,
0x90befffa, 0xa4506ceb, 0xbef9a3f7, 0xc67178f2
};
MAVLINK_HELPER void mavlink_sha256_init(mavlink_sha256_ctx *m)
{
m->sz[0] = 0;
m->sz[1] = 0;
m->counter[0] = 0x6a09e667;
m->counter[1] = 0xbb67ae85;
m->counter[2] = 0x3c6ef372;
m->counter[3] = 0xa54ff53a;
m->counter[4] = 0x510e527f;
m->counter[5] = 0x9b05688c;
m->counter[6] = 0x1f83d9ab;
m->counter[7] = 0x5be0cd19;
}
static inline void mavlink_sha256_calc(mavlink_sha256_ctx *m, uint32_t *in)
{
uint32_t AA, BB, CC, DD, EE, FF, GG, HH;
uint32_t data[64];
int i;
AA = m->counter[0];
BB = m->counter[1];
CC = m->counter[2];
DD = m->counter[3];
EE = m->counter[4];
FF = m->counter[5];
GG = m->counter[6];
HH = m->counter[7];
for (i = 0; i < 16; ++i)
data[i] = in[i];
for (i = 16; i < 64; ++i)
data[i] = sigma1(data[i-2]) + data[i-7] +
sigma0(data[i-15]) + data[i - 16];
for (i = 0; i < 64; i++) {
uint32_t T1, T2;
T1 = HH + Sigma1(EE) + Ch(EE, FF, GG) + mavlink_sha256_constant_256[i] + data[i];
T2 = Sigma0(AA) + Maj(AA,BB,CC);
HH = GG;
GG = FF;
FF = EE;
EE = DD + T1;
DD = CC;
CC = BB;
BB = AA;
AA = T1 + T2;
}
m->counter[0] += AA;
m->counter[1] += BB;
m->counter[2] += CC;
m->counter[3] += DD;
m->counter[4] += EE;
m->counter[5] += FF;
m->counter[6] += GG;
m->counter[7] += HH;
}
MAVLINK_HELPER void mavlink_sha256_update(mavlink_sha256_ctx *m, const void *v, uint32_t len)
{
const unsigned char *p = (const unsigned char *)v;
uint32_t old_sz = m->sz[0];
uint32_t offset;
m->sz[0] += len * 8;
if (m->sz[0] < old_sz)
++m->sz[1];
offset = (old_sz / 8) % 64;
while(len > 0){
uint32_t l = 64 - offset;
if (len < l) {
l = len;
}
memcpy(m->u.save_bytes + offset, p, l);
offset += l;
p += l;
len -= l;
if(offset == 64){
int i;
uint32_t current[16];
const uint32_t *u = m->u.save_u32;
for (i = 0; i < 16; i++){
const uint8_t *p1 = (const uint8_t *)&u[i];
uint8_t *p2 = (uint8_t *)&current[i];
p2[0] = p1[3];
p2[1] = p1[2];
p2[2] = p1[1];
p2[3] = p1[0];
}
mavlink_sha256_calc(m, current);
offset = 0;
}
}
}
/*
get first 48 bits of final sha256 hash
*/
MAVLINK_HELPER void mavlink_sha256_final_48(mavlink_sha256_ctx *m, uint8_t result[6])
{
unsigned char zeros[72];
unsigned offset = (m->sz[0] / 8) % 64;
unsigned int dstart = (120 - offset - 1) % 64 + 1;
uint8_t *p = (uint8_t *)&m->counter[0];
*zeros = 0x80;
memset (zeros + 1, 0, sizeof(zeros) - 1);
zeros[dstart+7] = (m->sz[0] >> 0) & 0xff;
zeros[dstart+6] = (m->sz[0] >> 8) & 0xff;
zeros[dstart+5] = (m->sz[0] >> 16) & 0xff;
zeros[dstart+4] = (m->sz[0] >> 24) & 0xff;
zeros[dstart+3] = (m->sz[1] >> 0) & 0xff;
zeros[dstart+2] = (m->sz[1] >> 8) & 0xff;
zeros[dstart+1] = (m->sz[1] >> 16) & 0xff;
zeros[dstart+0] = (m->sz[1] >> 24) & 0xff;
mavlink_sha256_update(m, zeros, dstart + 8);
// this ordering makes the result consistent with taking the first
// 6 bytes of more conventional sha256 functions. It assumes
// little-endian ordering of m->counter
result[0] = p[3];
result[1] = p[2];
result[2] = p[1];
result[3] = p[0];
result[4] = p[7];
result[5] = p[6];
}
// prevent conflicts with users of the header
#undef Ch
#undef ROTR
#undef Sigma0
#undef Sigma1
#undef sigma0
#undef sigma1
#ifdef MAVLINK_USE_CXX_NAMESPACE
} // namespace mavlink
#endif
#endif // HAVE_MAVLINK_SHA256

View File

@ -0,0 +1,312 @@
#pragma once
// Visual Studio versions before 2010 don't have stdint.h, so we just error out.
#if (defined _MSC_VER) && (_MSC_VER < 1600)
#error "The C-MAVLink implementation requires Visual Studio 2010 or greater"
#endif
#include <stdbool.h>
#include <stdint.h>
#ifdef MAVLINK_USE_CXX_NAMESPACE
namespace mavlink {
#endif
// Macro to define packed structures
#ifdef __GNUC__
#define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed))
#else
#define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) )
#endif
#ifndef MAVLINK_MAX_PAYLOAD_LEN
// it is possible to override this, but be careful!
#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
#endif
#define MAVLINK_CORE_HEADER_LEN 9 ///< Length of core header (of the comm. layer)
#define MAVLINK_CORE_HEADER_MAVLINK1_LEN 5 ///< Length of MAVLink1 core header (of the comm. layer)
#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and stx
#define MAVLINK_NUM_CHECKSUM_BYTES 2
#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
#define MAVLINK_SIGNATURE_BLOCK_LEN 13
#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_SIGNATURE_BLOCK_LEN) ///< Maximum packet length
/**
* Old-style 4 byte param union
*
* This struct is the data format to be used when sending
* parameters. The parameter should be copied to the native
* type (without type conversion)
* and re-instanted on the receiving side using the
* native type as well.
*/
MAVPACKED(
typedef struct param_union {
union {
float param_float;
int32_t param_int32;
uint32_t param_uint32;
int16_t param_int16;
uint16_t param_uint16;
int8_t param_int8;
uint8_t param_uint8;
uint8_t bytes[4];
};
uint8_t type;
}) mavlink_param_union_t;
/**
* New-style 8 byte param union
* mavlink_param_union_double_t will be 8 bytes long, and treated as needing 8 byte alignment for the purposes of MAVLink 1.0 field ordering.
* The mavlink_param_union_double_t will be treated as a little-endian structure.
*
* If is_double is 1 then the type is a double, and the remaining 63 bits are the double, with the lowest bit of the mantissa zero.
* The intention is that by replacing the is_double bit with 0 the type can be directly used as a double (as the is_double bit corresponds to the
* lowest mantissa bit of a double). If is_double is 0 then mavlink_type gives the type in the union.
* The mavlink_types.h header will also need to have shifts/masks to define the bit boundaries in the above,
* as bitfield ordering isn't consistent between platforms. The above is intended to be for gcc on x86,
* which should be the same as gcc on little-endian arm. When using shifts/masks the value will be treated as a 64 bit unsigned number,
* and the bits pulled out using the shifts/masks.
*/
MAVPACKED(
typedef struct param_union_extended {
union {
struct {
uint8_t is_double:1;
uint8_t mavlink_type:7;
union {
char c;
uint8_t uint8;
int8_t int8;
uint16_t uint16;
int16_t int16;
uint32_t uint32;
int32_t int32;
float f;
uint8_t align[7];
};
};
uint8_t data[8];
};
}) mavlink_param_union_double_t;
/**
* This structure is required to make the mavlink_send_xxx convenience functions
* work, as it tells the library what the current system and component ID are.
*/
MAVPACKED(
typedef struct __mavlink_system {
uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function
uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function
}) mavlink_system_t;
MAVPACKED(
typedef struct __mavlink_message {
uint16_t checksum; ///< sent at end of packet
uint8_t magic; ///< protocol magic marker
uint8_t len; ///< Length of payload
uint8_t incompat_flags; ///< flags that must be understood
uint8_t compat_flags; ///< flags that can be ignored if not understood
uint8_t seq; ///< Sequence of packet
uint8_t sysid; ///< ID of message sender system/aircraft
uint8_t compid; ///< ID of the message sender component
uint32_t msgid:24; ///< ID of message in payload
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
uint8_t ck[2]; ///< incoming checksum bytes
uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN];
}) mavlink_message_t;
typedef enum {
MAVLINK_TYPE_CHAR = 0,
MAVLINK_TYPE_UINT8_T = 1,
MAVLINK_TYPE_INT8_T = 2,
MAVLINK_TYPE_UINT16_T = 3,
MAVLINK_TYPE_INT16_T = 4,
MAVLINK_TYPE_UINT32_T = 5,
MAVLINK_TYPE_INT32_T = 6,
MAVLINK_TYPE_UINT64_T = 7,
MAVLINK_TYPE_INT64_T = 8,
MAVLINK_TYPE_FLOAT = 9,
MAVLINK_TYPE_DOUBLE = 10
} mavlink_message_type_t;
#define MAVLINK_MAX_FIELDS 64
typedef struct __mavlink_field_info {
const char *name; // name of this field
const char *print_format; // printing format hint, or NULL
mavlink_message_type_t type; // type of this field
unsigned int array_length; // if non-zero, field is an array
unsigned int wire_offset; // offset of each field in the payload
unsigned int structure_offset; // offset in a C structure
} mavlink_field_info_t;
// note that in this structure the order of fields is the order
// in the XML file, not necessary the wire order
typedef struct __mavlink_message_info {
uint32_t msgid; // message ID
const char *name; // name of the message
unsigned num_fields; // how many fields in this message
mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
} mavlink_message_info_t;
#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0])))
#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
// checksum is immediately after the payload bytes
#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
#ifndef HAVE_MAVLINK_CHANNEL_T
typedef enum {
MAVLINK_COMM_0,
MAVLINK_COMM_1,
MAVLINK_COMM_2,
MAVLINK_COMM_3
} mavlink_channel_t;
#endif
/*
* applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number
* of buffers they will use. If more are used, then the result will be
* a stack overrun
*/
#ifndef MAVLINK_COMM_NUM_BUFFERS
#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
# define MAVLINK_COMM_NUM_BUFFERS 16
#else
# define MAVLINK_COMM_NUM_BUFFERS 4
#endif
#endif
typedef enum {
MAVLINK_PARSE_STATE_UNINIT=0,
MAVLINK_PARSE_STATE_IDLE,
MAVLINK_PARSE_STATE_GOT_STX,
MAVLINK_PARSE_STATE_GOT_LENGTH,
MAVLINK_PARSE_STATE_GOT_INCOMPAT_FLAGS,
MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS,
MAVLINK_PARSE_STATE_GOT_SEQ,
MAVLINK_PARSE_STATE_GOT_SYSID,
MAVLINK_PARSE_STATE_GOT_COMPID,
MAVLINK_PARSE_STATE_GOT_MSGID1,
MAVLINK_PARSE_STATE_GOT_MSGID2,
MAVLINK_PARSE_STATE_GOT_MSGID3,
MAVLINK_PARSE_STATE_GOT_PAYLOAD,
MAVLINK_PARSE_STATE_GOT_CRC1,
MAVLINK_PARSE_STATE_GOT_BAD_CRC1,
MAVLINK_PARSE_STATE_SIGNATURE_WAIT
} mavlink_parse_state_t; ///< The state machine for the comm parser
typedef enum {
MAVLINK_FRAMING_INCOMPLETE=0,
MAVLINK_FRAMING_OK=1,
MAVLINK_FRAMING_BAD_CRC=2,
MAVLINK_FRAMING_BAD_SIGNATURE=3
} mavlink_framing_t;
#define MAVLINK_STATUS_FLAG_IN_MAVLINK1 1 // last incoming packet was MAVLink1
#define MAVLINK_STATUS_FLAG_OUT_MAVLINK1 2 // generate MAVLink1 by default
#define MAVLINK_STATUS_FLAG_IN_SIGNED 4 // last incoming packet was signed and validated
#define MAVLINK_STATUS_FLAG_IN_BADSIG 8 // last incoming packet had a bad signature
#define MAVLINK_STX_MAVLINK1 0xFE // marker for old protocol
typedef struct __mavlink_status {
uint8_t msg_received; ///< Number of received messages
uint8_t buffer_overrun; ///< Number of buffer overruns
uint8_t parse_error; ///< Number of parse errors
mavlink_parse_state_t parse_state; ///< Parsing state machine
uint8_t packet_idx; ///< Index in current packet
uint8_t current_rx_seq; ///< Sequence number of last packet received
uint8_t current_tx_seq; ///< Sequence number of last packet sent
uint16_t packet_rx_success_count; ///< Received packets
uint16_t packet_rx_drop_count; ///< Number of packet drops
uint8_t flags; ///< MAVLINK_STATUS_FLAG_*
uint8_t signature_wait; ///< number of signature bytes left to receive
struct __mavlink_signing *signing; ///< optional signing state
struct __mavlink_signing_streams *signing_streams; ///< global record of stream timestamps
} mavlink_status_t;
/*
a callback function to allow for accepting unsigned packets
*/
typedef bool (*mavlink_accept_unsigned_t)(const mavlink_status_t *status, uint32_t msgid);
/*
flags controlling signing
*/
#define MAVLINK_SIGNING_FLAG_SIGN_OUTGOING 1 ///< Enable outgoing signing
typedef enum {
MAVLINK_SIGNING_STATUS_NONE=0,
MAVLINK_SIGNING_STATUS_OK=1,
MAVLINK_SIGNING_STATUS_BAD_SIGNATURE=2,
MAVLINK_SIGNING_STATUS_NO_STREAMS=3,
MAVLINK_SIGNING_STATUS_TOO_MANY_STREAMS=4,
MAVLINK_SIGNING_STATUS_OLD_TIMESTAMP=5,
MAVLINK_SIGNING_STATUS_REPLAY=6,
} mavlink_signing_status_t;
/*
state of MAVLink signing for this channel
*/
typedef struct __mavlink_signing {
uint8_t flags; ///< MAVLINK_SIGNING_FLAG_*
uint8_t link_id; ///< Same as MAVLINK_CHANNEL
uint64_t timestamp; ///< Timestamp, in microseconds since UNIX epoch GMT
uint8_t secret_key[32];
mavlink_accept_unsigned_t accept_unsigned_callback;
mavlink_signing_status_t last_status;
} mavlink_signing_t;
/*
timestamp state of each logical signing stream. This needs to be the same structure for all
connections in order to be secure
*/
#ifndef MAVLINK_MAX_SIGNING_STREAMS
#define MAVLINK_MAX_SIGNING_STREAMS 16
#endif
typedef struct __mavlink_signing_streams {
uint16_t num_signing_streams;
struct __mavlink_signing_stream {
uint8_t link_id; ///< ID of the link (MAVLINK_CHANNEL)
uint8_t sysid; ///< Remote system ID
uint8_t compid; ///< Remote component ID
uint8_t timestamp_bytes[6]; ///< Timestamp, in microseconds since UNIX epoch GMT
} stream[MAVLINK_MAX_SIGNING_STREAMS];
} mavlink_signing_streams_t;
#define MAVLINK_BIG_ENDIAN 0
#define MAVLINK_LITTLE_ENDIAN 1
#define MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM 1
#define MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT 2
/*
entry in table of information about each message type
*/
typedef struct __mavlink_msg_entry {
uint32_t msgid;
uint8_t crc_extra;
uint8_t min_msg_len; // minimum message length
uint8_t max_msg_len; // maximum message length (e.g. including mavlink2 extensions)
uint8_t flags; // MAV_MSG_ENTRY_FLAG_*
uint8_t target_system_ofs; // payload offset to target_system, or 0
uint8_t target_component_ofs; // payload offset to target_component, or 0
} mavlink_msg_entry_t;
/*
incompat_flags bits
*/
#define MAVLINK_IFLAG_SIGNED 0x01
#define MAVLINK_IFLAG_MASK 0x01 // mask of all understood bits
#ifdef MAVLINK_USE_CXX_NAMESPACE
} // namespace mavlink
#endif

View File

@ -0,0 +1,34 @@
/** @file
* @brief MAVLink comm protocol built from minimal.xml
* @see http://mavlink.org
*/
#pragma once
#ifndef MAVLINK_H
#define MAVLINK_H
#define MAVLINK_PRIMARY_XML_HASH 3620580151627289427
#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 "minimal.h"
#endif // MAVLINK_H

View File

@ -0,0 +1,335 @@
#pragma once
// MESSAGE HEARTBEAT PACKING
#define MAVLINK_MSG_ID_HEARTBEAT 0
typedef struct __mavlink_heartbeat_t {
uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags*/
uint8_t type; /*< Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.*/
uint8_t autopilot; /*< Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.*/
uint8_t base_mode; /*< System mode bitmap.*/
uint8_t system_status; /*< System status flag.*/
uint8_t mavlink_version; /*< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version*/
} mavlink_heartbeat_t;
#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9
#define MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN 9
#define MAVLINK_MSG_ID_0_LEN 9
#define MAVLINK_MSG_ID_0_MIN_LEN 9
#define MAVLINK_MSG_ID_HEARTBEAT_CRC 50
#define MAVLINK_MSG_ID_0_CRC 50
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \
0, \
"HEARTBEAT", \
6, \
{ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \
{ "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \
{ "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \
{ "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
{ "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \
{ "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \
"HEARTBEAT", \
6, \
{ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \
{ "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \
{ "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \
{ "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
{ "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \
{ "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
} \
}
#endif
/**
* @brief Pack a 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 type Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.
* @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
* @param base_mode System mode bitmap.
* @param custom_mode A bitfield for use for autopilot-specific flags
* @param system_status System status flag.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN];
_mav_put_uint32_t(buf, 0, custom_mode);
_mav_put_uint8_t(buf, 4, type);
_mav_put_uint8_t(buf, 5, autopilot);
_mav_put_uint8_t(buf, 6, base_mode);
_mav_put_uint8_t(buf, 7, system_status);
_mav_put_uint8_t(buf, 8, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#else
mavlink_heartbeat_t packet;
packet.custom_mode = custom_mode;
packet.type = type;
packet.autopilot = autopilot;
packet.base_mode = base_mode;
packet.system_status = system_status;
packet.mavlink_version = 3;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
}
/**
* @brief Pack a 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 type Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.
* @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
* @param base_mode System mode bitmap.
* @param custom_mode A bitfield for use for autopilot-specific flags
* @param system_status System status flag.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN];
_mav_put_uint32_t(buf, 0, custom_mode);
_mav_put_uint8_t(buf, 4, type);
_mav_put_uint8_t(buf, 5, autopilot);
_mav_put_uint8_t(buf, 6, base_mode);
_mav_put_uint8_t(buf, 7, system_status);
_mav_put_uint8_t(buf, 8, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#else
mavlink_heartbeat_t packet;
packet.custom_mode = custom_mode;
packet.type = type;
packet.autopilot = autopilot;
packet.base_mode = base_mode;
packet.system_status = system_status;
packet.mavlink_version = 3;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
}
/**
* @brief Encode a 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 heartbeat C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
{
return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
}
/**
* @brief Encode a 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 heartbeat C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
{
return mavlink_msg_heartbeat_pack_chan(system_id, component_id, chan, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
}
/**
* @brief Send a heartbeat message
* @param chan MAVLink channel to send the message
*
* @param type Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.
* @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
* @param base_mode System mode bitmap.
* @param custom_mode A bitfield for use for autopilot-specific flags
* @param system_status System status flag.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN];
_mav_put_uint32_t(buf, 0, custom_mode);
_mav_put_uint8_t(buf, 4, type);
_mav_put_uint8_t(buf, 5, autopilot);
_mav_put_uint8_t(buf, 6, base_mode);
_mav_put_uint8_t(buf, 7, system_status);
_mav_put_uint8_t(buf, 8, 3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
#else
mavlink_heartbeat_t packet;
packet.custom_mode = custom_mode;
packet.type = type;
packet.autopilot = autopilot;
packet.base_mode = base_mode;
packet.system_status = system_status;
packet.mavlink_version = 3;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
#endif
}
/**
* @brief Send a heartbeat message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_heartbeat_send_struct(mavlink_channel_t chan, const mavlink_heartbeat_t* heartbeat)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_heartbeat_send(chan, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)heartbeat, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
#endif
}
#if MAVLINK_MSG_ID_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant 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_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, custom_mode);
_mav_put_uint8_t(buf, 4, type);
_mav_put_uint8_t(buf, 5, autopilot);
_mav_put_uint8_t(buf, 6, base_mode);
_mav_put_uint8_t(buf, 7, system_status);
_mav_put_uint8_t(buf, 8, 3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
#else
mavlink_heartbeat_t *packet = (mavlink_heartbeat_t *)msgbuf;
packet->custom_mode = custom_mode;
packet->type = type;
packet->autopilot = autopilot;
packet->base_mode = base_mode;
packet->system_status = system_status;
packet->mavlink_version = 3;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
#endif
}
#endif
#endif
// MESSAGE HEARTBEAT UNPACKING
/**
* @brief Get field type from heartbeat message
*
* @return Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.
*/
static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field autopilot from heartbeat message
*
* @return Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
*/
static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field base_mode from heartbeat message
*
* @return System mode bitmap.
*/
static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field custom_mode from heartbeat message
*
* @return A bitfield for use for autopilot-specific flags
*/
static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field system_status from heartbeat message
*
* @return System status flag.
*/
static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
/**
* @brief Get field mavlink_version from heartbeat message
*
* @return MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version
*/
static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
* @brief Decode a heartbeat message into a struct
*
* @param msg The message to decode
* @param heartbeat C-struct to decode the message contents into
*/
static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg);
heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg);
heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg);
heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_HEARTBEAT_LEN? msg->len : MAVLINK_MSG_ID_HEARTBEAT_LEN;
memset(heartbeat, 0, MAVLINK_MSG_ID_HEARTBEAT_LEN);
memcpy(heartbeat, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@ -0,0 +1,306 @@
#pragma once
// MESSAGE PROTOCOL_VERSION PACKING
#define MAVLINK_MSG_ID_PROTOCOL_VERSION 300
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 variant 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
}

View File

@ -0,0 +1,346 @@
/** @file
* @brief MAVLink comm protocol generated from minimal.xml
* @see http://mavlink.org
*/
#pragma once
#ifndef MAVLINK_MINIMAL_H
#define MAVLINK_MINIMAL_H
#ifndef MAVLINK_H
#error Wrong include order: MAVLINK_MINIMAL.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
#define MAVLINK_MINIMAL_XML_HASH 3620580151627289427
#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 {{0, 50, 9, 9, 0, 0, 0}, {300, 217, 22, 22, 0, 0, 0}}
#endif
#include "../protocol.h"
#define MAVLINK_ENABLED_MINIMAL
// ENUM DEFINITIONS
/** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */
#ifndef HAVE_ENUM_MAV_AUTOPILOT
#define HAVE_ENUM_MAV_AUTOPILOT
typedef enum MAV_AUTOPILOT
{
MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */
MAV_AUTOPILOT_RESERVED=1, /* Reserved for future use. | */
MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */
MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilot - Plane/Copter/Rover/Sub/Tracker, https://ardupilot.org | */
MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */
MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */
MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */
MAV_AUTOPILOT_GENERIC_MISSION_FULL=7, /* Generic autopilot supporting the full mission command set | */
MAV_AUTOPILOT_INVALID=8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */
MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */
MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */
MAV_AUTOPILOT_FP=11, /* FlexiPilot | */
MAV_AUTOPILOT_PX4=12, /* PX4 Autopilot - http://px4.io/ | */
MAV_AUTOPILOT_SMACCMPILOT=13, /* SMACCMPilot - http://smaccmpilot.org | */
MAV_AUTOPILOT_AUTOQUAD=14, /* AutoQuad -- http://autoquad.org | */
MAV_AUTOPILOT_ARMAZILA=15, /* Armazila -- http://armazila.com | */
MAV_AUTOPILOT_AEROB=16, /* Aerob -- http://aerob.ru | */
MAV_AUTOPILOT_ASLUAV=17, /* ASLUAV autopilot -- http://www.asl.ethz.ch | */
MAV_AUTOPILOT_SMARTAP=18, /* SmartAP Autopilot - http://sky-drones.com | */
MAV_AUTOPILOT_AIRRAILS=19, /* AirRails - http://uaventure.com | */
MAV_AUTOPILOT_REFLEX=20, /* Fusion Reflex - https://fusion.engineering | */
MAV_AUTOPILOT_ENUM_END=21, /* | */
} MAV_AUTOPILOT;
#endif
/** @brief MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA). */
#ifndef HAVE_ENUM_MAV_TYPE
#define HAVE_ENUM_MAV_TYPE
typedef enum MAV_TYPE
{
MAV_TYPE_GENERIC=0, /* Generic micro air vehicle | */
MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */
MAV_TYPE_QUADROTOR=2, /* Quadrotor | */
MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */
MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */
MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */
MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */
MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */
MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */
MAV_TYPE_ROCKET=9, /* Rocket | */
MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */
MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */
MAV_TYPE_SUBMARINE=12, /* Submarine | */
MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */
MAV_TYPE_OCTOROTOR=14, /* Octorotor | */
MAV_TYPE_TRICOPTER=15, /* Tricopter | */
MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */
MAV_TYPE_KITE=17, /* Kite | */
MAV_TYPE_ONBOARD_CONTROLLER=18, /* Onboard companion controller | */
MAV_TYPE_VTOL_TAILSITTER_DUOROTOR=19, /* Two-rotor Tailsitter VTOL that additionally uses control surfaces in vertical operation. Note, value previously named MAV_TYPE_VTOL_DUOROTOR. | */
MAV_TYPE_VTOL_TAILSITTER_QUADROTOR=20, /* Quad-rotor Tailsitter VTOL using a V-shaped quad config in vertical operation. Note: value previously named MAV_TYPE_VTOL_QUADROTOR. | */
MAV_TYPE_VTOL_TILTROTOR=21, /* Tiltrotor VTOL. Fuselage and wings stay (nominally) horizontal in all flight phases. It able to tilt (some) rotors to provide thrust in cruise flight. | */
MAV_TYPE_VTOL_FIXEDROTOR=22, /* VTOL with separate fixed rotors for hover and cruise flight. Fuselage and wings stay (nominally) horizontal in all flight phases. | */
MAV_TYPE_VTOL_TAILSITTER=23, /* Tailsitter VTOL. Fuselage and wings orientation changes depending on flight phase: vertical for hover, horizontal for cruise. Use more specific VTOL MAV_TYPE_VTOL_DUOROTOR or MAV_TYPE_VTOL_QUADROTOR if appropriate. | */
MAV_TYPE_VTOL_TILTWING=24, /* Tiltwing VTOL. Fuselage stays horizontal in all flight phases. The whole wing, along with any attached engine, can tilt between vertical and horizontal mode. | */
MAV_TYPE_VTOL_RESERVED5=25, /* VTOL reserved 5 | */
MAV_TYPE_GIMBAL=26, /* Gimbal | */
MAV_TYPE_ADSB=27, /* ADSB system | */
MAV_TYPE_PARAFOIL=28, /* Steerable, nonrigid airfoil | */
MAV_TYPE_DODECAROTOR=29, /* Dodecarotor | */
MAV_TYPE_CAMERA=30, /* Camera | */
MAV_TYPE_CHARGING_STATION=31, /* Charging station | */
MAV_TYPE_FLARM=32, /* FLARM collision avoidance system | */
MAV_TYPE_SERVO=33, /* Servo | */
MAV_TYPE_ODID=34, /* Open Drone ID. See https://mavlink.io/en/services/opendroneid.html. | */
MAV_TYPE_DECAROTOR=35, /* Decarotor | */
MAV_TYPE_BATTERY=36, /* Battery | */
MAV_TYPE_PARACHUTE=37, /* Parachute | */
MAV_TYPE_LOG=38, /* Log | */
MAV_TYPE_OSD=39, /* OSD | */
MAV_TYPE_IMU=40, /* IMU | */
MAV_TYPE_GPS=41, /* GPS | */
MAV_TYPE_WINCH=42, /* Winch | */
MAV_TYPE_ENUM_END=43, /* | */
} MAV_TYPE;
#endif
/** @brief These flags encode the MAV mode. */
#ifndef HAVE_ENUM_MAV_MODE_FLAG
#define HAVE_ENUM_MAV_MODE_FLAG
typedef enum MAV_MODE_FLAG
{
MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */
MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */
MAV_MODE_FLAG_AUTO_ENABLED=4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */
MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies waypoints / mission items. | */
MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */
MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */
MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */
MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state. | */
MAV_MODE_FLAG_ENUM_END=129, /* | */
} MAV_MODE_FLAG;
#endif
/** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */
#ifndef HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION
#define HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION
typedef enum MAV_MODE_FLAG_DECODE_POSITION
{
MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */
MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */
MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixth bit: 00000100 | */
MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit: 00001000 | */
MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */
MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit: 00100000 | */
MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */
MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit: 10000000 | */
MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /* | */
} MAV_MODE_FLAG_DECODE_POSITION;
#endif
/** @brief */
#ifndef HAVE_ENUM_MAV_STATE
#define HAVE_ENUM_MAV_STATE
typedef enum MAV_STATE
{
MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */
MAV_STATE_BOOT=1, /* System is booting up. | */
MAV_STATE_CALIBRATING=2, /* System is calibrating and not flight-ready. | */
MAV_STATE_STANDBY=3, /* System is grounded and on standby. It can be launched any time. | */
MAV_STATE_ACTIVE=4, /* System is active and might be already airborne. Motors are engaged. | */
MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode. It can however still navigate. | */
MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */
MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */
MAV_STATE_FLIGHT_TERMINATION=8, /* System is terminating itself. | */
MAV_STATE_ENUM_END=9, /* | */
} MAV_STATE;
#endif
/** @brief Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.).
Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components.
When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded. */
#ifndef HAVE_ENUM_MAV_COMPONENT
#define HAVE_ENUM_MAV_COMPONENT
typedef enum MAV_COMPONENT
{
MAV_COMP_ID_ALL=0, /* Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message. | */
MAV_COMP_ID_AUTOPILOT1=1, /* System flight controller component ("autopilot"). Only one autopilot is expected in a particular system. | */
MAV_COMP_ID_USER1=25, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER2=26, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER3=27, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER4=28, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER5=29, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER6=30, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER7=31, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER8=32, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER9=33, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER10=34, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER11=35, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER12=36, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER13=37, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER14=38, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER15=39, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER16=40, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER17=41, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER18=42, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER19=43, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER20=44, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER21=45, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER22=46, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER23=47, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER24=48, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER25=49, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER26=50, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER27=51, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER28=52, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER29=53, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER30=54, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER31=55, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER32=56, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER33=57, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER34=58, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER35=59, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER36=60, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER37=61, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER38=62, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER39=63, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER40=64, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER41=65, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER42=66, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER43=67, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_TELEMETRY_RADIO=68, /* Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages). | */
MAV_COMP_ID_USER45=69, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER46=70, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER47=71, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER48=72, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER49=73, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER50=74, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER51=75, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER52=76, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER53=77, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER54=78, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER55=79, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER56=80, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER57=81, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER58=82, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER59=83, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER60=84, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER61=85, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER62=86, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER63=87, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER64=88, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER65=89, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER66=90, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER67=91, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER68=92, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER69=93, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER70=94, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER71=95, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER72=96, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER73=97, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER74=98, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_USER75=99, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */
MAV_COMP_ID_CAMERA=100, /* Camera #1. | */
MAV_COMP_ID_CAMERA2=101, /* Camera #2. | */
MAV_COMP_ID_CAMERA3=102, /* Camera #3. | */
MAV_COMP_ID_CAMERA4=103, /* Camera #4. | */
MAV_COMP_ID_CAMERA5=104, /* Camera #5. | */
MAV_COMP_ID_CAMERA6=105, /* Camera #6. | */
MAV_COMP_ID_SERVO1=140, /* Servo #1. | */
MAV_COMP_ID_SERVO2=141, /* Servo #2. | */
MAV_COMP_ID_SERVO3=142, /* Servo #3. | */
MAV_COMP_ID_SERVO4=143, /* Servo #4. | */
MAV_COMP_ID_SERVO5=144, /* Servo #5. | */
MAV_COMP_ID_SERVO6=145, /* Servo #6. | */
MAV_COMP_ID_SERVO7=146, /* Servo #7. | */
MAV_COMP_ID_SERVO8=147, /* Servo #8. | */
MAV_COMP_ID_SERVO9=148, /* Servo #9. | */
MAV_COMP_ID_SERVO10=149, /* Servo #10. | */
MAV_COMP_ID_SERVO11=150, /* Servo #11. | */
MAV_COMP_ID_SERVO12=151, /* Servo #12. | */
MAV_COMP_ID_SERVO13=152, /* Servo #13. | */
MAV_COMP_ID_SERVO14=153, /* Servo #14. | */
MAV_COMP_ID_GIMBAL=154, /* Gimbal #1. | */
MAV_COMP_ID_LOG=155, /* Logging component. | */
MAV_COMP_ID_ADSB=156, /* Automatic Dependent Surveillance-Broadcast (ADS-B) component. | */
MAV_COMP_ID_OSD=157, /* On Screen Display (OSD) devices for video links. | */
MAV_COMP_ID_PERIPHERAL=158, /* Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice. | */
MAV_COMP_ID_QX1_GIMBAL=159, /* Gimbal ID for QX1. | */
MAV_COMP_ID_FLARM=160, /* FLARM collision alert component. | */
MAV_COMP_ID_PARACHUTE=161, /* Parachute component. | */
MAV_COMP_ID_WINCH=169, /* Winch component. | */
MAV_COMP_ID_GIMBAL2=171, /* Gimbal #2. | */
MAV_COMP_ID_GIMBAL3=172, /* Gimbal #3. | */
MAV_COMP_ID_GIMBAL4=173, /* Gimbal #4 | */
MAV_COMP_ID_GIMBAL5=174, /* Gimbal #5. | */
MAV_COMP_ID_GIMBAL6=175, /* Gimbal #6. | */
MAV_COMP_ID_BATTERY=180, /* Battery #1. | */
MAV_COMP_ID_BATTERY2=181, /* Battery #2. | */
MAV_COMP_ID_MAVCAN=189, /* CAN over MAVLink client. | */
MAV_COMP_ID_MISSIONPLANNER=190, /* Component that can generate/supply a mission flight plan (e.g. GCS or developer API). | */
MAV_COMP_ID_ONBOARD_COMPUTER=191, /* Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. | */
MAV_COMP_ID_ONBOARD_COMPUTER2=192, /* Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. | */
MAV_COMP_ID_ONBOARD_COMPUTER3=193, /* Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. | */
MAV_COMP_ID_ONBOARD_COMPUTER4=194, /* Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. | */
MAV_COMP_ID_PATHPLANNER=195, /* Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.). | */
MAV_COMP_ID_OBSTACLE_AVOIDANCE=196, /* Component that plans a collision free path between two points. | */
MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY=197, /* Component that provides position estimates using VIO techniques. | */
MAV_COMP_ID_PAIRING_MANAGER=198, /* Component that manages pairing of vehicle and GCS. | */
MAV_COMP_ID_IMU=200, /* Inertial Measurement Unit (IMU) #1. | */
MAV_COMP_ID_IMU_2=201, /* Inertial Measurement Unit (IMU) #2. | */
MAV_COMP_ID_IMU_3=202, /* Inertial Measurement Unit (IMU) #3. | */
MAV_COMP_ID_GPS=220, /* GPS #1. | */
MAV_COMP_ID_GPS2=221, /* GPS #2. | */
MAV_COMP_ID_ODID_TXRX_1=236, /* Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). | */
MAV_COMP_ID_ODID_TXRX_2=237, /* Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). | */
MAV_COMP_ID_ODID_TXRX_3=238, /* Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). | */
MAV_COMP_ID_UDP_BRIDGE=240, /* Component to bridge MAVLink to UDP (i.e. from a UART). | */
MAV_COMP_ID_UART_BRIDGE=241, /* Component to bridge to UART (i.e. from UDP). | */
MAV_COMP_ID_TUNNEL_NODE=242, /* Component handling TUNNEL messages (e.g. vendor specific GUI of a component). | */
MAV_COMP_ID_SYSTEM_CONTROL=250, /* Deprecated, don't use. Component for handling system messages (e.g. to ARM, takeoff, etc.). | */
MAV_COMPONENT_ENUM_END=251, /* | */
} MAV_COMPONENT;
#endif
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 3
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 3
#endif
// MESSAGE DEFINITIONS
#include "./mavlink_msg_heartbeat.h"
#include "./mavlink_msg_protocol_version.h"
// base include
#if MAVLINK_MINIMAL_XML_HASH == MAVLINK_PRIMARY_XML_HASH
# 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
#endif
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // MAVLINK_MINIMAL_H

View File

@ -0,0 +1,164 @@
/** @file
* @brief MAVLink comm protocol testsuite generated from minimal.xml
* @see https://mavlink.io/en/
*/
#pragma once
#ifndef MINIMAL_TESTSUITE_H
#define MINIMAL_TESTSUITE_H
#ifdef __cplusplus
extern "C" {
#endif
#ifndef MAVLINK_TEST_ALL
#define MAVLINK_TEST_ALL
static void mavlink_test_minimal(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_minimal(system_id, component_id, last_msg);
}
#endif
static void mavlink_test_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_HEARTBEAT >= 256) {
return;
}
#endif
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_heartbeat_t packet_in = {
963497464,17,84,151,218,3
};
mavlink_heartbeat_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.custom_mode = packet_in.custom_mode;
packet1.type = packet_in.type;
packet1.autopilot = packet_in.autopilot;
packet1.base_mode = packet_in.base_mode;
packet1.system_status = packet_in.system_status;
packet1.mavlink_version = packet_in.mavlink_version;
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
// cope with extensions
memset(MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN);
}
#endif
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_heartbeat_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_heartbeat_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_heartbeat_pack(system_id, component_id, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status );
mavlink_msg_heartbeat_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status );
mavlink_msg_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_heartbeat_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_heartbeat_send(MAVLINK_COMM_1 , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status );
mavlink_msg_heartbeat_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
MAVLINK_ASSERT(mavlink_get_message_info_by_name("HEARTBEAT") != NULL);
MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_HEARTBEAT) != NULL);
#endif
}
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);
#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
MAVLINK_ASSERT(mavlink_get_message_info_by_name("PROTOCOL_VERSION") != NULL);
MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PROTOCOL_VERSION) != NULL);
#endif
}
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
}
#endif // __cplusplus
#endif // MINIMAL_TESTSUITE_H

View File

@ -0,0 +1,14 @@
/** @file
* @brief MAVLink comm protocol built from minimal.xml
* @see http://mavlink.org
*/
#pragma once
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Mar 27 2023"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22
#endif // MAVLINK_VERSION_H

View File

@ -0,0 +1,334 @@
#pragma once
#include "string.h"
#include "mavlink_types.h"
/*
If you want MAVLink on a system that is native big-endian,
you need to define NATIVE_BIG_ENDIAN
*/
#ifdef NATIVE_BIG_ENDIAN
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN)
#else
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN)
#endif
#ifndef MAVLINK_STACK_BUFFER
#define MAVLINK_STACK_BUFFER 0
#endif
#ifndef MAVLINK_AVOID_GCC_STACK_BUG
# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__)
#endif
#ifndef MAVLINK_ASSERT
#define MAVLINK_ASSERT(x)
#endif
#ifndef MAVLINK_START_UART_SEND
#define MAVLINK_START_UART_SEND(chan, length)
#endif
#ifndef MAVLINK_END_UART_SEND
#define MAVLINK_END_UART_SEND(chan, length)
#endif
/* option to provide alternative implementation of mavlink_helpers.h */
#ifdef MAVLINK_SEPARATE_HELPERS
#define MAVLINK_HELPER
/* decls in sync with those in mavlink_helpers.h */
#ifndef MAVLINK_GET_CHANNEL_STATUS
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
#endif
MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan);
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra);
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t min_length, uint8_t length, uint8_t crc_extra);
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint32_t msgid, const char *packet,
uint8_t min_length, uint8_t length, uint8_t crc_extra);
#endif
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
mavlink_status_t* status,
uint8_t c,
mavlink_message_t* r_message,
mavlink_status_t* r_mavlink_status);
MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index,
uint8_t* r_bit_index, uint8_t* buffer);
MAVLINK_HELPER const mavlink_msg_entry_t *mavlink_get_msg_entry(uint32_t msgid);
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg);
#endif
#else
#define MAVLINK_HELPER static inline
#include "mavlink_helpers.h"
#endif // MAVLINK_SEPARATE_HELPERS
/**
* @brief Get the required buffer size for this message
*/
static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg)
{
if (msg->magic == MAVLINK_STX_MAVLINK1) {
return msg->len + MAVLINK_CORE_HEADER_MAVLINK1_LEN+1 + 2;
}
uint16_t signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0;
return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES + signature_len;
}
#if MAVLINK_NEED_BYTE_SWAP
static inline void byte_swap_2(char *dst, const char *src)
{
dst[0] = src[1];
dst[1] = src[0];
}
static inline void byte_swap_4(char *dst, const char *src)
{
dst[0] = src[3];
dst[1] = src[2];
dst[2] = src[1];
dst[3] = src[0];
}
static inline void byte_swap_8(char *dst, const char *src)
{
dst[0] = src[7];
dst[1] = src[6];
dst[2] = src[5];
dst[3] = src[4];
dst[4] = src[3];
dst[5] = src[2];
dst[6] = src[1];
dst[7] = src[0];
}
#elif !MAVLINK_ALIGNED_FIELDS
static inline void byte_copy_2(char *dst, const char *src)
{
dst[0] = src[0];
dst[1] = src[1];
}
static inline void byte_copy_4(char *dst, const char *src)
{
dst[0] = src[0];
dst[1] = src[1];
dst[2] = src[2];
dst[3] = src[3];
}
static inline void byte_copy_8(char *dst, const char *src)
{
memcpy(dst, src, 8);
}
#endif
#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b
#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b
#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b
#if MAVLINK_NEED_BYTE_SWAP
#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
#elif !MAVLINK_ALIGNED_FIELDS
#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
#else
#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b
#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b
#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b
#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b
#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b
#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b
#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b
#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b
#endif
/*
like memcpy(), but if src is NULL, do a memset to zero
*/
static inline void mav_array_memcpy(void *dest, const void *src, size_t n)
{
if (src == NULL) {
memset(dest, 0, n);
} else {
memcpy(dest, src, n);
}
}
/*
* Place a char array into a buffer
*/
static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
{
mav_array_memcpy(&buf[wire_offset], b, array_length);
}
/*
* Place a uint8_t array into a buffer
*/
static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
{
mav_array_memcpy(&buf[wire_offset], b, array_length);
}
/*
* Place a int8_t array into a buffer
*/
static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length)
{
mav_array_memcpy(&buf[wire_offset], b, array_length);
}
#if MAVLINK_NEED_BYTE_SWAP
#define _MAV_PUT_ARRAY(TYPE, V) \
static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
{ \
if (b == NULL) { \
memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
} else { \
uint16_t i; \
for (i=0; i<array_length; i++) { \
_mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \
} \
} \
}
#else
#define _MAV_PUT_ARRAY(TYPE, V) \
static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
{ \
mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
}
#endif
_MAV_PUT_ARRAY(uint16_t, u16)
_MAV_PUT_ARRAY(uint32_t, u32)
_MAV_PUT_ARRAY(uint64_t, u64)
_MAV_PUT_ARRAY(int16_t, i16)
_MAV_PUT_ARRAY(int32_t, i32)
_MAV_PUT_ARRAY(int64_t, i64)
_MAV_PUT_ARRAY(float, f)
_MAV_PUT_ARRAY(double, d)
#define _MAV_RETURN_char(msg, wire_offset) (char)_MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_int8_t(msg, wire_offset) (int8_t)_MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_uint8_t(msg, wire_offset) (uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
#if MAVLINK_NEED_BYTE_SWAP
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
{ TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
_MAV_MSG_RETURN_TYPE(uint16_t, 2)
_MAV_MSG_RETURN_TYPE(int16_t, 2)
_MAV_MSG_RETURN_TYPE(uint32_t, 4)
_MAV_MSG_RETURN_TYPE(int32_t, 4)
_MAV_MSG_RETURN_TYPE(uint64_t, 8)
_MAV_MSG_RETURN_TYPE(int64_t, 8)
_MAV_MSG_RETURN_TYPE(float, 4)
_MAV_MSG_RETURN_TYPE(double, 8)
#elif !MAVLINK_ALIGNED_FIELDS
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
{ TYPE r; byte_copy_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
_MAV_MSG_RETURN_TYPE(uint16_t, 2)
_MAV_MSG_RETURN_TYPE(int16_t, 2)
_MAV_MSG_RETURN_TYPE(uint32_t, 4)
_MAV_MSG_RETURN_TYPE(int32_t, 4)
_MAV_MSG_RETURN_TYPE(uint64_t, 8)
_MAV_MSG_RETURN_TYPE(int64_t, 8)
_MAV_MSG_RETURN_TYPE(float, 4)
_MAV_MSG_RETURN_TYPE(double, 8)
#else // nicely aligned, no swap
#define _MAV_MSG_RETURN_TYPE(TYPE) \
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
{ return *(const TYPE *)(&_MAV_PAYLOAD(msg)[ofs]);}
_MAV_MSG_RETURN_TYPE(uint16_t)
_MAV_MSG_RETURN_TYPE(int16_t)
_MAV_MSG_RETURN_TYPE(uint32_t)
_MAV_MSG_RETURN_TYPE(int32_t)
_MAV_MSG_RETURN_TYPE(uint64_t)
_MAV_MSG_RETURN_TYPE(int64_t)
_MAV_MSG_RETURN_TYPE(float)
_MAV_MSG_RETURN_TYPE(double)
#endif // MAVLINK_NEED_BYTE_SWAP
static inline uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value,
uint8_t array_length, uint8_t wire_offset)
{
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
return array_length;
}
static inline uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value,
uint8_t array_length, uint8_t wire_offset)
{
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
return array_length;
}
static inline uint16_t _MAV_RETURN_int8_t_array(const mavlink_message_t *msg, int8_t *value,
uint8_t array_length, uint8_t wire_offset)
{
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
return array_length;
}
#if MAVLINK_NEED_BYTE_SWAP
#define _MAV_RETURN_ARRAY(TYPE, V) \
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
uint8_t array_length, uint8_t wire_offset) \
{ \
uint16_t i; \
for (i=0; i<array_length; i++) { \
value[i] = _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \
} \
return array_length*sizeof(value[0]); \
}
#else
#define _MAV_RETURN_ARRAY(TYPE, V) \
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
uint8_t array_length, uint8_t wire_offset) \
{ \
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length*sizeof(TYPE)); \
return array_length*sizeof(TYPE); \
}
#endif
_MAV_RETURN_ARRAY(uint16_t, u16)
_MAV_RETURN_ARRAY(uint32_t, u32)
_MAV_RETURN_ARRAY(uint64_t, u64)
_MAV_RETURN_ARRAY(int16_t, i16)
_MAV_RETURN_ARRAY(int32_t, i32)
_MAV_RETURN_ARRAY(int64_t, i64)
_MAV_RETURN_ARRAY(float, f)
_MAV_RETURN_ARRAY(double, d)

View File

@ -0,0 +1,250 @@
#include <fcntl.h>
#include <stdio.h>
#include <stdbool.h>
#include <unistd.h>
#include <linux/joystick.h>
#include <sys/socket.h>
#include <errno.h>
#include <sys/time.h>
#include <netinet/in.h>
#include <arpa/inet.h>
#include "common/mavlink.h"
#define BUFFER_LENGTH 2041
int errsv;
uint8_t axes_count = 5;
///////////////////////////////////////////////////////////////////////////////////////
int read_event(int fd, struct js_event *event)
{
ssize_t bytes;
bytes = read(fd, event, sizeof(*event));
if (bytes == sizeof(*event))
return 0;
errsv = errno;
return -1;
}
size_t get_axes_count(int fd)
{
__u8 axes;
if (ioctl(fd, JSIOCGAXES, &axes) == -1)
return 0;
return axes;
}
size_t get_button_count(int fd)
{
__u8 buttons;
if (ioctl(fd, JSIOCGBUTTONS, &buttons) == -1)
return 0;
return buttons;
}
struct axis_state {
short x, y;
};
size_t get_axis_state(struct js_event *event, struct axis_state axes[3])
{
size_t axis = event->number / 2;
if (axis < axes_count)
{
if (event->number % 2 == 0)
axes[axis].x = event->value;
else
axes[axis].y = event->value;
}
return axis;
}
///////////////////////////////////////////////////////////////////////////////////////
long long millis() {
struct timeval te;
gettimeofday(&te, NULL); // get current time
long long milliseconds = te.tv_sec*1000LL + te.tv_usec/1000; // calculate milliseconds
return milliseconds;
}
uint16_t axes_to_ch(int16_t val) {
return ((32768 + val) / 65.535) + 1000;
}
///////////////////////////////////////////////////////////////////////////////////////
int main(int argc, char *argv[])
{
const char *device;
int js;
struct js_event event;
struct axis_state axes[9] = {
{ 0, 0 }, //ch1/2 default
{ -32768, 0 }, //ch3/4 default
{ -32768, -32768 }, //ch5/6 default
{ -32768, -32768 }, //ch7/8 default
{ -32768, -32768 }, //ch9/10 default
{ -32768, -32768 }, //ch11/12 default
{ -32768, -32768 }, //ch13/14 default
{ -32768, -32768 }, //ch15/16 default
{ -32768, -32768 }, //ch17/18 default
};
size_t axis;
//udp sock
uint8_t buf[BUFFER_LENGTH];
mavlink_message_t msg;
uint16_t len;
int bytes_sent;
int out_sock = socket(AF_INET, SOCK_DGRAM, 0);
struct sockaddr_in sin_out = {
.sin_family = AF_INET,
};
int buttons[14] = {1000,1000,1000,1000,1000,1000,1000,1000,1000,1000,1000,1000,1000,1000};
//time checker
long long time_check = millis();
uint16_t send_time = 50;
struct timespec tw = {0,10};
struct timespec tr;
//args
int opt;
bool verbose = false;
//defaults
device = "/dev/input/js0";
inet_aton("127.0.0.1", &sin_out.sin_addr);
sin_out.sin_port = htons(14650);
//rssi func
int8_t chan_rxpkts = 0; //default disabled
int16_t rxpkts_prev = 0, rxpkts = 0, rxpkts_per_second = 0;
long long rxpkts_time = millis();
while ((opt = getopt(argc, argv, "vd:a:p:t:x:r:h")) != -1) {
switch (opt) {
case 'v':
verbose = true;
break;
case 'd':
device = optarg;
break;
case 'a':
inet_aton(optarg, &sin_out.sin_addr);
break;
case 'p':
sin_out.sin_port = htons(atoi(optarg));
break;
case 't':
send_time = atoi(optarg);
break;
case 'x':
axes_count = atoi(optarg);
break;
case 'r':
chan_rxpkts = atoi(optarg);
break;
case 'h':
printf("rcjoystick by whoim@mail.ru\ncapture usb-hid joystic state and share to mavlink reciever as RC_CHANNELS_OVERRIDE packets\nUsage:\n [-v] verbose;\n [-d device] default '/dev/input/js0';\n [-a addr] ip address send to, default 127.0.0.1;\n [-p port] udp port send to, default 14650;\n [-t time] update RC_CHANNEL_OVERRIDE time in ms, default 50;\n [-x axes_count] 2..9 axes, default 5, other channels mapping to js buttons from button 0;\n");
return 0;
}
}
while (true) { //loop
js = open(device, O_RDONLY | O_NONBLOCK);
if (js == -1) {
perror("Could not open joystick");
//close(js);
perror ("open()");
sleep (1); //try again later
continue; //go to start while true
//return 0;
}
printf("Device: %s, %d axes, %d buttons\n", device, get_axes_count(js), get_button_count(js));
printf("Update time: %dms\n", send_time);
printf("UDP: %s:%d\n", inet_ntoa(sin_out.sin_addr), ntohs(sin_out.sin_port));
printf("Used axes: %d, other channels as buttons\n", axes_count);
if(chan_rxpkts > 0) printf("Store rxpkts to channel %d\n", chan_rxpkts);
printf("Started\n");
do //while not errno read js
{
errsv = 11; //reset
if( read_event(js, &event) == 0 ) {
switch (event.type)
{
case JS_EVENT_BUTTON:
if (verbose) printf("Button %u %s\n", event.number, event.value ? "pressed" : "released");
buttons[event.number] = event.value ? 2000 : 1000;
break;
case JS_EVENT_AXIS:
axis = get_axis_state(&event, axes);
if (axis < axes_count)
if (verbose) printf("Axis %zu at (%6d, %6d)\n", axis, axes[axis].x, axes[axis].y);
break;
default:
// Ignore init events.
break;
}
}
//check rxpkts
if(chan_rxpkts > 4) {
if( (long long)rxpkts_time + 1000 < millis() ){
FILE* rxpkts_ptr = fopen("/sys/class/net/wlan0/statistics/rx_packets", "r");
if (rxpkts_ptr == NULL) {
printf("error open net statistics");
//return 0;
}
fscanf(rxpkts_ptr, "%hd", &rxpkts);
fclose(rxpkts_ptr);
rxpkts_per_second = rxpkts - rxpkts_prev;
rxpkts_time = millis();
rxpkts_prev = rxpkts;
if (verbose) printf("current rx per sec is %d \n", rxpkts_per_second);
}
}
//send to udp
if( (long long)time_check + send_time < millis() ){
uint8_t btnidx = 0;
mavlink_msg_rc_channels_override_pack(255, 190, &msg, 0, 0,
axes_to_ch(axes[0].x), //ch1
axes_to_ch(axes[0].y), //ch2
axes_to_ch(axes[1].x), //ch3
axes_to_ch(axes[1].y), //ch4
(chan_rxpkts == 5) ? rxpkts_per_second : (axes_count > 2) ? axes_to_ch(axes[2].x) : buttons[btnidx], //ch5
(chan_rxpkts == 6) ? rxpkts_per_second : (axes_count > 2) ? axes_to_ch(axes[2].y) : buttons[btnidx++], //ch6
(chan_rxpkts == 7) ? rxpkts_per_second : (axes_count > 3) ? axes_to_ch(axes[3].x) : buttons[btnidx++], //ch7
(chan_rxpkts == 8) ? rxpkts_per_second : (axes_count > 3) ? axes_to_ch(axes[3].y) : buttons[btnidx++], //ch8
(chan_rxpkts == 9) ? rxpkts_per_second : (axes_count > 4) ? axes_to_ch(axes[4].x) : buttons[btnidx++], //ch9
(chan_rxpkts == 10) ? rxpkts_per_second : (axes_count > 4) ? axes_to_ch(axes[4].y) : buttons[btnidx++], //ch10
(chan_rxpkts == 11) ? rxpkts_per_second : (axes_count > 5) ? axes_to_ch(axes[5].x) : buttons[btnidx++], //ch11
(chan_rxpkts == 12) ? rxpkts_per_second : (axes_count > 5) ? axes_to_ch(axes[5].y) : buttons[btnidx++], //ch12
(chan_rxpkts == 13) ? rxpkts_per_second : (axes_count > 6) ? axes_to_ch(axes[6].x) : buttons[btnidx++], //ch13
(chan_rxpkts == 14) ? rxpkts_per_second : (axes_count > 6) ? axes_to_ch(axes[6].y) : buttons[btnidx++], //ch14
(chan_rxpkts == 15) ? rxpkts_per_second : (axes_count > 7) ? axes_to_ch(axes[7].x) : buttons[btnidx++], //ch15
(chan_rxpkts == 16) ? rxpkts_per_second : (axes_count > 7) ? axes_to_ch(axes[7].y) : buttons[btnidx++], //ch16
(chan_rxpkts == 17) ? rxpkts_per_second : (axes_count > 8) ? axes_to_ch(axes[8].x) : buttons[btnidx++], //ch17
(chan_rxpkts == 18) ? rxpkts_per_second : (axes_count > 8) ? axes_to_ch(axes[8].y) : buttons[btnidx++] //ch18
);
len = mavlink_msg_to_send_buffer(buf, &msg);
bytes_sent = sendto(out_sock, buf, len, 0, (struct sockaddr *)&sin_out, sizeof(sin_out));
if (verbose) printf("Sent %d bytes\n", bytes_sent);
time_check = millis();
}
if (verbose) fflush(stdout);
nanosleep(&tw, &tr); //for low CPU ut
} while (errsv == 11 || errsv == 38); //while not err
} //while true
}

View File

@ -0,0 +1,34 @@
/** @file
* @brief MAVLink comm protocol built from standard.xml
* @see http://mavlink.org
*/
#pragma once
#ifndef MAVLINK_H
#define MAVLINK_H
#define MAVLINK_PRIMARY_XML_HASH 1712659564068400467
#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 "standard.h"
#endif // MAVLINK_H

View File

@ -0,0 +1,66 @@
/** @file
* @brief MAVLink comm protocol generated from standard.xml
* @see http://mavlink.org
*/
#pragma once
#ifndef MAVLINK_STANDARD_H
#define MAVLINK_STANDARD_H
#ifndef MAVLINK_H
#error Wrong include order: MAVLINK_STANDARD.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
#define MAVLINK_STANDARD_XML_HASH 1712659564068400467
#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 {{0, 50, 9, 9, 0, 0, 0}, {300, 217, 22, 22, 0, 0, 0}}
#endif
#include "../protocol.h"
#define MAVLINK_ENABLED_STANDARD
// ENUM DEFINITIONS
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
// MESSAGE DEFINITIONS
// base include
#include "../minimal/minimal.h"
#if MAVLINK_STANDARD_XML_HASH == MAVLINK_PRIMARY_XML_HASH
# 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
#endif
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // MAVLINK_STANDARD_H

View File

@ -0,0 +1,37 @@
/** @file
* @brief MAVLink comm protocol testsuite generated from standard.xml
* @see https://mavlink.io/en/
*/
#pragma once
#ifndef STANDARD_TESTSUITE_H
#define STANDARD_TESTSUITE_H
#ifdef __cplusplus
extern "C" {
#endif
#ifndef MAVLINK_TEST_ALL
#define MAVLINK_TEST_ALL
static void mavlink_test_minimal(uint8_t, uint8_t, mavlink_message_t *last_msg);
static void mavlink_test_standard(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_minimal(system_id, component_id, last_msg);
mavlink_test_standard(system_id, component_id, last_msg);
}
#endif
#include "../minimal/testsuite.h"
static void mavlink_test_standard(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
}
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // STANDARD_TESTSUITE_H

View File

@ -0,0 +1,14 @@
/** @file
* @brief MAVLink comm protocol built from standard.xml
* @see http://mavlink.org
*/
#pragma once
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Mar 27 2023"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22
#endif // MAVLINK_VERSION_H