Updated mavlink added eeprom class.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1239 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
james.goppert 2010-12-23 23:02:51 +00:00
parent b8ffddb061
commit 125b971173
30 changed files with 2455 additions and 313 deletions

View File

@ -17,6 +17,7 @@
#include <stdint.h>
#include "include/menu.h" /// simple menu subsystem
#include "c++.h" // c++ additions
////////////////////////////////////////////////////////////////////////////////
/// @name Warning control

View File

@ -0,0 +1,373 @@
/*
* AP_Vector.h
* Copyright (C) James Goppert 2010 <james.goppert@gmail.com>
*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef AP_Vector_H
#define AP_Vector_H
#ifdef ASSERT
const static char vectorSource[] ="AP_Vector.hpp";
#endif
// vector
template <class dataType,class sumType=dataType>
class AP_Vector
{
private:
size_t size;
size_t extraAllocationSize; // extra space to add after each allocation
size_t sizeAllocated; // total allocated size
dataType* data;
public:
// default constructor
AP_Vector(const size_t & size=0, const size_t & extraAllocationSize=0) : size(0), extraAllocationSize(extraAllocationSize), sizeAllocated(0), data(NULL) {
setSize(size);
}
// 3 vector constructor
AP_Vector(const dataType & a, const dataType & b, const dataType & c) : size(3), extraAllocationSize(extraAllocationSize), sizeAllocated(0), data(NULL) {
setSize(size);
(*this)(0)=a;
(*this)(1)=b;
(*this)(2)=c;
}
// construct from array
AP_Vector(const dataType* array, const size_t & size, const size_t & extraAllocationSize=0) : size(0), extraAllocationSize(extraAllocationSize), sizeAllocated(0), data(NULL) {
setSize(size);
for (size_t i=0; i<getSize(); i++)
(*this)(i)=array[i];
}
// copy constructor
AP_Vector(const AP_Vector &v) : size(0), extraAllocationSize(0), sizeAllocated(0), data(NULL) {
setSize(v.getSize());
for (size_t i=0; i<getSize(); i++)
(*this)(i)=v(i);
}
// convert to float vector
AP_Vector<float> toFloat() const {
AP_Vector<float> v(getSize());
for (size_t i=0; i<getSize(); i++)
v(i)=(*this)(i);
return v;
}
// destructor
virtual ~AP_Vector() {
empty();
}
void empty() {
if (data) delete [] data;
data = NULL;
sizeAllocated=0;
size=0;
}
// set the size
void setSize(const size_t & n) {
if (n==0) {
if (data) delete [] data;
data = NULL;
sizeAllocated=0;
}
if (n>sizeAllocated) {
dataType * newData = new dataType[n+extraAllocationSize];
memcpy(newData,data,sizeof(dataType)/sizeof(char)*getSize());
memset(newData+size,0,sizeof(dataType)/sizeof(char)*(n-getSize()));
delete[] data;
data = newData;
sizeAllocated=n+extraAllocationSize;
}
size=n;
}
// return size
const size_t & getSize() const {
return size;
}
// insert
void insert(const size_t index, const dataType value) {
//Serial.println("insert called");
#ifdef ASSERT
assert(index<size+1,vectorSource,__LINE__);
#endif
//Serial.print("Old Size: ");
//Serial.println(getSize());
setSize(getSize()+1);
//Serial.print("New Size: ");
//Serial.println(getSize());
//Serial.print("Size of dataType");
//Serial.println(sizeof(dataType));
if (index != getSize()-1) {
memmove(data+index+1,data+index,sizeof(dataType)/sizeof(char)*(getSize()-1-index));
//Serial.println("memmove called and completed");
}
(*this)(index)=value;
//Serial.println("insert done");
}
// remove
void remove(const size_t & index) {
#ifdef ASSERT
assert(index<size,vectorSource,__LINE__);
#endif
memmove(data+index,data+index+1,getSize()-index-1);
setSize(getSize()-1);
}
// push_back
void push_back(const dataType & value) {
//Serial.println("push_back called");
insert(getSize(),value);
//Serial.println("push_back done");
}
// pop_front
dataType & pop_front() {
dataType tmp = (*this)(0);
remove(0);
return tmp;
}
// push_back a vector
void push_back(const AP_Vector & vector) {
for (size_t i=0; i<vector.getSize(); i++)
push_back(vector(i));
}
// const array access operator
const dataType & operator()(const size_t & index) const {
#ifdef ASSERT
assert(index<getSize(),vectorSource,__LINE__);
#endif
return data[index];
}
// array access operator
dataType & operator()(const size_t & index) {
#ifdef ASSERT
assert(index<getSize(),vectorSource,__LINE__);
#endif
return data[index];
}
// assignment operator
AP_Vector & operator=(const AP_Vector & v) {
setSize(v.getSize());
for (size_t i=0; i<getSize(); i++)
(*this)(i)=v(i);
return *this;
}
// equal
const bool operator==(const AP_Vector& v) const {
#ifdef ASSERT
assert(getSize()==v.getSize(),vectorSource,__LINE__);
#endif
for (size_t i=0; i<getSize(); i++) {
if ((*this)(i)!=v(i)) return false;
}
return true;
}
// not equal
const bool operator!=(const AP_Vector& v) const {
return !((*this)==v);
}
// addition
const AP_Vector operator+(const AP_Vector& v) const {
#ifdef ASSERT
assert(v.getSize() == getSize(),vectorSource,__LINE__);
#endif
AP_Vector result(getSize());
for (size_t i=0; i<getSize(); i++)
result(i)=(*this)(i)+v(i);
return result;
}
// addition
const AP_Vector operator+(const dataType& s) const {
AP_Vector result(getSize());
for (size_t i=0; i<getSize(); i++)
result(i)=(*this)(i)+s;
return result;
}
// subtraction
const AP_Vector operator-(const AP_Vector& v) const {
#ifdef ASSERT
assert(v.getSize() == getSize(),vectorSource,__LINE__);
#endif
AP_Vector result(getSize());
for (size_t i=0; i<getSize(); i++)
result(i)=(*this)(i)-v(i);
return result;
}
// negation
const AP_Vector operator-() const {
AP_Vector result(getSize());
for (size_t i=0; i<getSize(); i++)
result(i)=-(*this)(i);
return result;
}
// +=
AP_Vector& operator+=(const AP_Vector& v) {
#ifdef ASSERT
assert(v.getSize() == getSize(),vectorSource,__LINE__);
#endif
AP_Vector result(getSize());
for (size_t i=0; i<getSize(); i++)
(*this)(i)+=v(i);
return *this;
}
// -=
AP_Vector& operator-=( const AP_Vector& v) {
#ifdef ASSERT
assert(v.getSize() == getSize(),vectorSource,__LINE__);
#endif
AP_Vector result(getSize());
for (size_t i=0; i<getSize(); i++)
(*this)(i)-=v(i);
return *this;
}
// elementwise mult.
const AP_Vector operator*(const AP_Vector & v) const {
AP_Vector result(getSize());
for (size_t i=0; i<getSize(); i++)
result(i)=(*this)(i)*v(i);
return result;
}
// mult. by a scalar
const AP_Vector operator*(const dataType & s) const {
AP_Vector result(getSize());
for (size_t i=0; i<getSize(); i++)
result(i)=(*this)(i)*s;
return result;
}
// div. by a scalar
const AP_Vector operator/(const dataType & s) const {
AP_Vector result(getSize());
for (size_t i=0; i<getSize(); i++)
result(i)=(*this)(i)/s;
return result;
}
// elementwise div.
const AP_Vector operator/(const AP_Vector & v) const {
AP_Vector result(getSize());
for (size_t i=0; i<getSize(); i++)
result(i)=(*this)(i)/v(i);
return result;
}
// div. by a scalar
AP_Vector & operator/=(const dataType & s) {
for (size_t i=0; i<getSize(); i++)
(*this)(i)/=s;
return *this;
}
// mult. by a scalar
AP_Vector & operator*=(const dataType & s) {
for (size_t i=0; i<getSize(); i++)
(*this)(i)*=s;
return *this;
}
// cross/vector product
const AP_Vector cross(const AP_Vector& v) const {
AP_Vector result(3), u=*this;
#ifdef ASSERT
assert(u.getSize()==3 && v.getSize()==3,vectorSource,__LINE__);
#endif
result(0) = u(1)*v(2)-u(2)*v(1);
result(1) = -u(0)*v(2)+u(2)*v(0);
result(2) = u(0)*v(1)-u(1)*v(0);
return result;
}
// dot/scalar product
const dataType dot(const AP_Vector& v) const {
#ifdef ASSERT
assert(getSize()==v.getSize(),vectorSource,__LINE__);
#endif
dataType result;
for (size_t i=0; i<getSize(); i++) result += (*this)(i)*v(i);
return result;
}
// norm
const dataType norm() const {
return sqrt(dot(*this));
}
// unit vector
const AP_Vector unit() const {
return (*this)*(1/norm());
}
// sum
const sumType sum(const size_t & start=0,const int & end=-1) const {
size_t end2;
if (end==-1) end2=getSize()-1;
else end2=end;
sumType sum = 0;
for (size_t i=start; i<=end2; i++) sum += (*this)(i);
return sum;
}
void sumFletcher(uint8_t & CK_A, uint8_t & CK_B, const size_t & start=0,const int & end=-1) const {
size_t end2;
if (end==-1) end2=getSize()-1;
else end2=end;
for (size_t i = start; i<=end2; i++) {
CK_A += (*this)(i);
CK_B += CK_A;
}
}
// range
const AP_Vector range(const size_t & start, const size_t & stop) const {
AP_Vector v(stop-start+1);
for (size_t i=start; i<=stop; i++) v(i-start) = (*this)(i);
return v;
}
// to Array
const dataType* toArray() const {
dataType array[getSize()];
for (size_t i=0; i<getSize(); i++) array[i] = (*this)(i);
return array;
}
// printing
void print(Stream & serial=Serial, const char * msg="", size_t format=0) const {
serial.print(msg);
for (size_t i=0; i<getSize(); i++) {
serial.print((*this)(i),format);
serial.print(" ");
}
serial.println();
}
// self test
static bool selfTest(Stream & serial=Serial) {
serial.println("AP_Vector self test.");
AP_Vector u(3),v(3),w(3);
u(0) = 1;
u(1) = 2;
u(2) = 3;
v(0) = -4;
v(1) = -5;
v(2) = -6;
u.print(serial,"u: ");
v.print(serial,"v: ");
(u+v).print(serial,"u + v: ");
(u-v).print(serial,"u - v: ");
Serial.print("u dot v: ");
Serial.println(u.dot(v));
Serial.print("size of u: ");
Serial.println(u.getSize());
Serial.print("size of v: ");
Serial.println(v.getSize());
w=u.cross(v);
w.print(serial,"u cross v: ");
Serial.print("size of u cross v: ");
Serial.println(w.getSize());
return true;
}
};
#endif
// vim:ts=4:sw=4:expandtab

View File

@ -8,6 +8,8 @@
//
#include <stdlib.h>
#include "c++.h"
#include "WProgram.h"
void * operator new(size_t size)
{
@ -16,8 +18,17 @@ void * operator new(size_t size)
void operator delete(void *p)
{
if (p)
free(p);
if (p) free(p);
}
void * operator new[](size_t size)
{
return malloc(size);
}
void operator delete[](void * ptr)
{
if (ptr) free(ptr);
}
__extension__ typedef int __guard __attribute__((mode (__DI__)));
@ -33,3 +44,29 @@ void __cxa_guard_release (__guard *g)
};
void __cxa_guard_abort (__guard *) {};
// free memory
extern unsigned int __bss_end;
extern void *__brkval;
void displayMemory()
{
static int minMemFree=0;
if (minMemFree<=0 || freeMemory()<minMemFree) {
minMemFree = freeMemory();
Serial.print("bytes free: ");
Serial.println(minMemFree);
}
}
int freeMemory()
{
int free_memory;
if ((int)__brkval == 0)
free_memory = ((int)&free_memory) - ((int)&__bss_end);
else
free_memory = ((int)&free_memory) - ((int)__brkval);
return free_memory;
}

View File

@ -0,0 +1,7 @@
#ifndef CPP_H
#define CPP_H
void displayMemory();
int freeMemory();
#endif

View File

@ -1,41 +1,82 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
#ifndef AP_EEProm_H
#define AP_EEProm_H
/// @file AP_EEPROM.h
/// @brief AP_EEPROM manager
#include <AP_Vector.h>
#include <avr/eeprom.h>
#include <avr/pgmspace.h>
#ifndef AP_EEPROM_h
#define AP_EEPROM_h
//#include <stdint.h>
#include "WProgram.h"
/// @class AP_EEPROM
/// @brief Object for reading and writing to the EEPROM
class AP_EEPROM{
public:
/// Constructor
AP_EEPROM(){}
int read_byte(int address);
int read_int(int address);
long read_long(int address);
float read_float(int address);
void write_byte(int address, int8_t value);
void write_int(int address, int16_t value);
void write_long(int address, int32_t value);
void write_float(int address, float value);
private:
union type_union {
int8_t bytes[4];
long lvalue;
int ivalue;
float fvalue;
} _type_union;
class AP_EEPromEntry
{
public:
virtual void setEntry(float val) = 0;
virtual float getEntry() = 0;
uint16_t getId() { return _id; }
uint16_t getAddress() { return _address; }
protected:
uint16_t _id;
uint16_t _address;
};
#endif
class AP_EEPromRegistry : public AP_Vector<AP_EEPromEntry *>
{
public:
/**
* Default constructor
*/
AP_EEPromRegistry(uint16_t maxSize) :
_lastAddress(0), _lastId(0), _maxSize(maxSize)
{
}
/**
* Add an entry to the registry
*/
void add(AP_EEPromEntry * entry, uint16_t & id, uint16_t & address, size_t size)
{
if (_lastAddress + size > _maxSize) return;
address = _lastAddress;
_lastAddress += size;
id = _lastId++;
push_back(entry);
}
private:
uint16_t _lastAddress;
uint16_t _lastId;
uint16_t _maxSize;
};
AP_EEPromRegistry eepromRegistry(1024);
template <class type>
class AP_EEPromVar : public AP_EEPromEntry
{
public:
AP_EEPromVar()
{
eepromRegistry.add(this,_id,_address,sizeof(_data));
}
void set(type val) { _data = val; }
type get() { return _data; }
void save()
{
eeprom_write_block((const void*)&_data,(void*)(_address),sizeof(_data));
}
void load()
{
eeprom_read_block((void*)&_data,(const void*)(_address),sizeof(_data));
}
virtual void setEntry(float val)
{
_data = (type)val;
}
virtual float getEntry()
{
return (float)_data;
}
private:
type _data;
};
#endif

View File

@ -1,39 +1,33 @@
#include <AP_EEPROM.h> // ArduPilot Mega RC Library
/*
* Libraries
*/
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_EEProm.h>
byte byte_value = 99;
int int_value = 30000;
long long_value = 123456789;
float float_value = .01234;
AP_EEPromVar<int> var;
FastSerialPort0(Serial);
AP_EEPROM ee;
void setup()
{
Serial.begin(38400);
delay(100);
Serial.println("\nAP_EEPROM test");
Serial.println("AP_EEPROM test");
ee.write_byte(0, byte_value);
ee.write_int(1, int_value);
ee.write_long(3, long_value);
ee.write_float(7, float_value);
Serial.println(ee.read_byte(0), DEC);
Serial.println(ee.read_int(1), DEC);
Serial.println(ee.read_long(3), DEC);
float e = ee.read_float(7);
long y = e * 100;
//Serial.println(e, 5);930 bytes
Serial.begin(115200);
Serial.println("starting");
displayMemory();
}
void loop()
{
var.set(123);
Serial.printf_P(PSTR("initially set 123 and save: %d\n"), var.get());
var.save();
var.set(456);
Serial.printf_P(PSTR("next set to 456: %d\n"), var.get());
var.load();
Serial.printf_P(PSTR("now reload initial value: %d\n"), var.get());
uint16_t id = var.getId();
Serial.printf_P(PSTR("now find id for variable: %d\n"), id);
Serial.printf_P(PSTR("now find variable value by id: %f\n"), eepromRegistry(id)->getEntry());
eepromRegistry(id)->setEntry(456);
Serial.printf_P(PSTR("now set variable value by id to 456: %d\n"), var.get());
delay(5000);
}
// 2162 bytes
// 2216

View File

@ -0,0 +1,82 @@
#ifndef AP_EEProm_H
#define AP_EEProm_H
#include <AP_Vector.h>
#include <avr/eeprom.h>
#include <avr/pgmspace.h>
class AP_EEPromEntry
{
public:
virtual void setEntry(float val) = 0;
virtual float getEntry() = 0;
uint16_t getId() { return _id; }
uint16_t getAddress() { return _address; }
protected:
uint16_t _id;
uint16_t _address;
};
class AP_EEPromRegistry : public AP_Vector<AP_EEPromEntry *>
{
public:
/**
* Default constructor
*/
AP_EEPromRegistry(uint16_t maxSize) :
_lastAddress(0), _lastId(0), _maxSize(maxSize)
{
}
/**
* Add an entry to the registry
*/
void add(AP_EEPromEntry * entry, uint16_t & id, uint16_t & address, size_t size)
{
if (_lastAddress + size > _maxSize) return;
address = _lastAddress;
_lastAddress += size;
id = _lastId++;
push_back(entry);
}
private:
uint16_t _lastAddress;
uint16_t _lastId;
uint16_t _maxSize;
};
AP_EEPromRegistry eepromRegistry(1024);
template <class type>
class AP_EEPromVar : public AP_EEPromEntry
{
public:
AP_EEPromVar()
{
eepromRegistry.add(this,_id,_address,sizeof(_data));
}
void set(type val) { _data = val; }
type get() { return _data; }
void save()
{
eeprom_write_block((const void*)&_data,(void*)(_address),sizeof(_data));
}
void load()
{
eeprom_read_block((void*)&_data,(const void*)(_address),sizeof(_data));
}
virtual void setEntry(float val)
{
_data = (type)val;
}
virtual float getEntry()
{
return (float)_data;
}
private:
type _data;
};
#endif

View File

@ -0,0 +1,33 @@
/*
* Libraries
*/
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_EEProm.h>
AP_EEPromVar<int> var;
FastSerialPort0(Serial);
void setup()
{
Serial.begin(115200);
Serial.println("starting");
displayMemory();
}
void loop()
{
var.set(123);
Serial.printf_P(PSTR("initially set 123 and save: %d\n"), var.get());
var.save();
var.set(456);
Serial.printf_P(PSTR("next set to 456: %d\n"), var.get());
var.load();
Serial.printf_P(PSTR("now reload initial value: %d\n"), var.get());
uint16_t id = var.getId();
Serial.printf_P(PSTR("now find id for variable: %d\n"), id);
Serial.printf_P(PSTR("now find variable value by id: %f\n"), eepromRegistry(id)->getEntry());
eepromRegistry(id)->setEntry(456);
Serial.printf_P(PSTR("now set variable value by id to 456: %d\n"), var.get());
delay(5000);
}

View File

View File

@ -5,9 +5,10 @@
typedef struct __mavlink_raw_pressure_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch)
int32_t press_abs; ///< Absolute pressure (hectopascal)
int32_t press_diff1; ///< Differential pressure 1 (hectopascal)
int32_t press_diff2; ///< Differential pressure 2 (hectopascal)
int16_t press_abs; ///< Absolute pressure (hectopascal)
int16_t press_diff1; ///< Differential pressure 1 (hectopascal)
int16_t press_diff2; ///< Differential pressure 2 (hectopascal)
int16_t temperature; ///< Raw Temperature measurement
} mavlink_raw_pressure_t;
@ -20,17 +21,19 @@ typedef struct __mavlink_raw_pressure_t
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff1 Differential pressure 1 (hectopascal)
* @param press_diff2 Differential pressure 2 (hectopascal)
* @param temperature Raw Temperature measurement
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, int32_t press_abs, int32_t press_diff1, int32_t press_diff2)
static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since UNIX epoch)
i += put_int32_t_by_index(press_abs, i, msg->payload); //Absolute pressure (hectopascal)
i += put_int32_t_by_index(press_diff1, i, msg->payload); //Differential pressure 1 (hectopascal)
i += put_int32_t_by_index(press_diff2, i, msg->payload); //Differential pressure 2 (hectopascal)
i += put_int16_t_by_index(press_abs, i, msg->payload); //Absolute pressure (hectopascal)
i += put_int16_t_by_index(press_diff1, i, msg->payload); //Differential pressure 1 (hectopascal)
i += put_int16_t_by_index(press_diff2, i, msg->payload); //Differential pressure 2 (hectopascal)
i += put_int16_t_by_index(temperature, i, msg->payload); //Raw Temperature measurement
return mavlink_finalize_message(msg, system_id, component_id, i);
}
@ -50,12 +53,12 @@ static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uin
static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure)
{
return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2);
return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t usec, int32_t press_abs, int32_t press_diff1, int32_t press_diff2)
static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
{
mavlink_message_t msg;
mavlink_msg_raw_pressure_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, press_abs, press_diff1, press_diff2);
@ -89,14 +92,12 @@ static inline uint64_t mavlink_msg_raw_pressure_get_usec(const mavlink_message_t
*
* @return Absolute pressure (hectopascal)
*/
static inline int32_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t))[0];
r.b[2] = (msg->payload+sizeof(uint64_t))[1];
r.b[1] = (msg->payload+sizeof(uint64_t))[2];
r.b[0] = (msg->payload+sizeof(uint64_t))[3];
return (int32_t)r.i;
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t))[1];
return (int16_t)r.s;
}
/**
@ -104,14 +105,12 @@ static inline int32_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_messa
*
* @return Differential pressure 1 (hectopascal)
*/
static inline int32_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg)
static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t))[3];
return (int32_t)r.i;
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
@ -119,14 +118,25 @@ static inline int32_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_mes
*
* @return Differential pressure 2 (hectopascal)
*/
static inline int32_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t)+sizeof(int32_t))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t)+sizeof(int32_t))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t)+sizeof(int32_t))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t)+sizeof(int32_t))[3];
return (int32_t)r.i;
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field temperature from raw_pressure message
*
* @return Raw Temperature measurement
*/
static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure)
@ -135,4 +145,5 @@ static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg,
raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg);
raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg);
raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg);
raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg);
}

View File

@ -40,6 +40,8 @@ enum MAV_ACTION {
MAV_ACTION_LAND = 26,
MAV_ACTION_LOITER = 27,
MAV_ACTION_SET_ORIGIN = 28,
MAV_ACITON_RELAY_ON = 29,
MAV_ACTION_RELAY_OFF = 30,
MAV_ACTION_NB ///< Number of MAV actions
};
@ -165,6 +167,8 @@ typedef struct __mavlink_message {
typedef enum {
MAVLINK_COMM_0,
MAVLINK_COMM_1,
MAVLINK_COMM_2,
MAVLINK_COMM_3,
MAVLINK_COMM_NB,
MAVLINK_COMM_NB_HIGH = 16
} mavlink_channel_t;

View File

@ -1,10 +1,9 @@
// MESSAGE AIR_DATA PACKING
#define MAVLINK_MSG_ID_AIR_DATA 191
#define MAVLINK_MSG_ID_AIR_DATA 171
typedef struct __mavlink_air_data_t
{
uint8_t target; ///< The system reporting the air data
float dynamicPressure; ///< Dynamic pressure (Pa)
float staticPressure; ///< Static pressure (Pa)
uint16_t temperature; ///< Board temperature
@ -16,18 +15,16 @@ typedef struct __mavlink_air_data_t
/**
* @brief Send a air_data message
*
* @param target The system reporting the air data
* @param dynamicPressure Dynamic pressure (Pa)
* @param staticPressure Static pressure (Pa)
* @param temperature Board temperature
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_air_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float dynamicPressure, float staticPressure, uint16_t temperature)
static inline uint16_t mavlink_msg_air_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float dynamicPressure, float staticPressure, uint16_t temperature)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_AIR_DATA;
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the air data
i += put_float_by_index(dynamicPressure, i, msg->payload); //Dynamic pressure (Pa)
i += put_float_by_index(staticPressure, i, msg->payload); //Static pressure (Pa)
i += put_uint16_t_by_index(temperature, i, msg->payload); //Board temperature
@ -50,12 +47,12 @@ static inline uint16_t mavlink_msg_air_data_pack_chan(uint8_t system_id, uint8_t
static inline uint16_t mavlink_msg_air_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_air_data_t* air_data)
{
return mavlink_msg_air_data_pack(system_id, component_id, msg, air_data->target, air_data->dynamicPressure, air_data->staticPressure, air_data->temperature);
return mavlink_msg_air_data_pack(system_id, component_id, msg, air_data->dynamicPressure, air_data->staticPressure, air_data->temperature);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_air_data_send(mavlink_channel_t chan, uint8_t target, float dynamicPressure, float staticPressure, uint16_t temperature)
static inline void mavlink_msg_air_data_send(mavlink_channel_t chan, float dynamicPressure, float staticPressure, uint16_t temperature)
{
mavlink_message_t msg;
mavlink_msg_air_data_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, dynamicPressure, staticPressure, temperature);
@ -65,16 +62,6 @@ static inline void mavlink_msg_air_data_send(mavlink_channel_t chan, uint8_t tar
#endif
// MESSAGE AIR_DATA UNPACKING
/**
* @brief Get field target from air_data message
*
* @return The system reporting the air data
*/
static inline uint8_t mavlink_msg_air_data_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field dynamicPressure from air_data message
*
@ -83,10 +70,10 @@ static inline uint8_t mavlink_msg_air_data_get_target(const mavlink_message_t* m
static inline float mavlink_msg_air_data_get_dynamicPressure(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t))[3];
r.b[3] = (msg->payload)[0];
r.b[2] = (msg->payload)[1];
r.b[1] = (msg->payload)[2];
r.b[0] = (msg->payload)[3];
return (float)r.f;
}
@ -98,10 +85,10 @@ static inline float mavlink_msg_air_data_get_dynamicPressure(const mavlink_messa
static inline float mavlink_msg_air_data_get_staticPressure(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3];
r.b[3] = (msg->payload+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float))[3];
return (float)r.f;
}
@ -113,14 +100,13 @@ static inline float mavlink_msg_air_data_get_staticPressure(const mavlink_messag
static inline uint16_t mavlink_msg_air_data_get_temperature(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[0];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[1];
return (uint16_t)r.s;
}
static inline void mavlink_msg_air_data_decode(const mavlink_message_t* msg, mavlink_air_data_t* air_data)
{
air_data->target = mavlink_msg_air_data_get_target(msg);
air_data->dynamicPressure = mavlink_msg_air_data_get_dynamicPressure(msg);
air_data->staticPressure = mavlink_msg_air_data_get_staticPressure(msg);
air_data->temperature = mavlink_msg_air_data_get_temperature(msg);

View File

@ -1,10 +1,9 @@
// MESSAGE CPU_LOAD PACKING
#define MAVLINK_MSG_ID_CPU_LOAD 190
#define MAVLINK_MSG_ID_CPU_LOAD 170
typedef struct __mavlink_cpu_load_t
{
uint8_t target; ///< The system reporting the CPU load
uint8_t sensLoad; ///< Sensor DSC Load
uint8_t ctrlLoad; ///< Control DSC Load
uint16_t batVolt; ///< Battery Voltage in millivolts
@ -16,18 +15,16 @@ typedef struct __mavlink_cpu_load_t
/**
* @brief Send a cpu_load message
*
* @param target The system reporting the CPU load
* @param sensLoad Sensor DSC Load
* @param ctrlLoad Control DSC Load
* @param batVolt Battery Voltage in millivolts
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cpu_load_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt)
static inline uint16_t mavlink_msg_cpu_load_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CPU_LOAD;
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the CPU load
i += put_uint8_t_by_index(sensLoad, i, msg->payload); //Sensor DSC Load
i += put_uint8_t_by_index(ctrlLoad, i, msg->payload); //Control DSC Load
i += put_uint16_t_by_index(batVolt, i, msg->payload); //Battery Voltage in millivolts
@ -50,12 +47,12 @@ static inline uint16_t mavlink_msg_cpu_load_pack_chan(uint8_t system_id, uint8_t
static inline uint16_t mavlink_msg_cpu_load_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cpu_load_t* cpu_load)
{
return mavlink_msg_cpu_load_pack(system_id, component_id, msg, cpu_load->target, cpu_load->sensLoad, cpu_load->ctrlLoad, cpu_load->batVolt);
return mavlink_msg_cpu_load_pack(system_id, component_id, msg, cpu_load->sensLoad, cpu_load->ctrlLoad, cpu_load->batVolt);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_cpu_load_send(mavlink_channel_t chan, uint8_t target, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt)
static inline void mavlink_msg_cpu_load_send(mavlink_channel_t chan, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt)
{
mavlink_message_t msg;
mavlink_msg_cpu_load_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, sensLoad, ctrlLoad, batVolt);
@ -65,16 +62,6 @@ static inline void mavlink_msg_cpu_load_send(mavlink_channel_t chan, uint8_t tar
#endif
// MESSAGE CPU_LOAD UNPACKING
/**
* @brief Get field target from cpu_load message
*
* @return The system reporting the CPU load
*/
static inline uint8_t mavlink_msg_cpu_load_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field sensLoad from cpu_load message
*
@ -82,7 +69,7 @@ static inline uint8_t mavlink_msg_cpu_load_get_target(const mavlink_message_t* m
*/
static inline uint8_t mavlink_msg_cpu_load_get_sensLoad(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
return (uint8_t)(msg->payload)[0];
}
/**
@ -92,7 +79,7 @@ static inline uint8_t mavlink_msg_cpu_load_get_sensLoad(const mavlink_message_t*
*/
static inline uint8_t mavlink_msg_cpu_load_get_ctrlLoad(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
@ -103,14 +90,13 @@ static inline uint8_t mavlink_msg_cpu_load_get_ctrlLoad(const mavlink_message_t*
static inline uint16_t mavlink_msg_cpu_load_get_batVolt(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
return (uint16_t)r.s;
}
static inline void mavlink_msg_cpu_load_decode(const mavlink_message_t* msg, mavlink_cpu_load_t* cpu_load)
{
cpu_load->target = mavlink_msg_cpu_load_get_target(msg);
cpu_load->sensLoad = mavlink_msg_cpu_load_get_sensLoad(msg);
cpu_load->ctrlLoad = mavlink_msg_cpu_load_get_ctrlLoad(msg);
cpu_load->batVolt = mavlink_msg_cpu_load_get_batVolt(msg);

View File

@ -0,0 +1,76 @@
// MESSAGE CTRL_SRFC_PT PACKING
#define MAVLINK_MSG_ID_CTRL_SRFC_PT 181
typedef struct __mavlink_ctrl_srfc_pt_t
{
uint8_t target; ///< The system setting the commands
uint16_t bitfieldPt; ///< Bitfield containing the PT configuration
} mavlink_ctrl_srfc_pt_t;
/**
* @brief Send a ctrl_srfc_pt message
*
* @param target The system setting the commands
* @param bitfieldPt Bitfield containing the PT configuration
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ctrl_srfc_pt_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint16_t bitfieldPt)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CTRL_SRFC_PT;
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the commands
i += put_uint16_t_by_index(bitfieldPt, i, msg->payload); //Bitfield containing the PT configuration
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_ctrl_srfc_pt_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ctrl_srfc_pt_t* ctrl_srfc_pt)
{
return mavlink_msg_ctrl_srfc_pt_pack(system_id, component_id, msg, ctrl_srfc_pt->target, ctrl_srfc_pt->bitfieldPt);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ctrl_srfc_pt_send(mavlink_channel_t chan, uint8_t target, uint16_t bitfieldPt)
{
mavlink_message_t msg;
mavlink_msg_ctrl_srfc_pt_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, bitfieldPt);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE CTRL_SRFC_PT UNPACKING
/**
* @brief Get field target from ctrl_srfc_pt message
*
* @return The system setting the commands
*/
static inline uint8_t mavlink_msg_ctrl_srfc_pt_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field bitfieldPt from ctrl_srfc_pt message
*
* @return Bitfield containing the PT configuration
*/
static inline uint16_t mavlink_msg_ctrl_srfc_pt_get_bitfieldPt(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t))[1];
return (uint16_t)r.s;
}
static inline void mavlink_msg_ctrl_srfc_pt_decode(const mavlink_message_t* msg, mavlink_ctrl_srfc_pt_t* ctrl_srfc_pt)
{
ctrl_srfc_pt->target = mavlink_msg_ctrl_srfc_pt_get_target(msg);
ctrl_srfc_pt->bitfieldPt = mavlink_msg_ctrl_srfc_pt_get_bitfieldPt(msg);
}

View File

@ -0,0 +1,159 @@
// MESSAGE DATA_LOG PACKING
#define MAVLINK_MSG_ID_DATA_LOG 177
typedef struct __mavlink_data_log_t
{
float fl_1; ///< Log value 1
float fl_2; ///< Log value 2
float fl_3; ///< Log value 3
float fl_4; ///< Log value 4
float fl_5; ///< Log value 5
float fl_6; ///< Log value 6
} mavlink_data_log_t;
/**
* @brief Send a data_log message
*
* @param fl_1 Log value 1
* @param fl_2 Log value 2
* @param fl_3 Log value 3
* @param fl_4 Log value 4
* @param fl_5 Log value 5
* @param fl_6 Log value 6
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data_log_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float fl_1, float fl_2, float fl_3, float fl_4, float fl_5, float fl_6)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DATA_LOG;
i += put_float_by_index(fl_1, i, msg->payload); //Log value 1
i += put_float_by_index(fl_2, i, msg->payload); //Log value 2
i += put_float_by_index(fl_3, i, msg->payload); //Log value 3
i += put_float_by_index(fl_4, i, msg->payload); //Log value 4
i += put_float_by_index(fl_5, i, msg->payload); //Log value 5
i += put_float_by_index(fl_6, i, msg->payload); //Log value 6
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_data_log_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_log_t* data_log)
{
return mavlink_msg_data_log_pack(system_id, component_id, msg, data_log->fl_1, data_log->fl_2, data_log->fl_3, data_log->fl_4, data_log->fl_5, data_log->fl_6);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_data_log_send(mavlink_channel_t chan, float fl_1, float fl_2, float fl_3, float fl_4, float fl_5, float fl_6)
{
mavlink_message_t msg;
mavlink_msg_data_log_pack(mavlink_system.sysid, mavlink_system.compid, &msg, fl_1, fl_2, fl_3, fl_4, fl_5, fl_6);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE DATA_LOG UNPACKING
/**
* @brief Get field fl_1 from data_log message
*
* @return Log value 1
*/
static inline float mavlink_msg_data_log_get_fl_1(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload)[0];
r.b[2] = (msg->payload)[1];
r.b[1] = (msg->payload)[2];
r.b[0] = (msg->payload)[3];
return (float)r.f;
}
/**
* @brief Get field fl_2 from data_log message
*
* @return Log value 2
*/
static inline float mavlink_msg_data_log_get_fl_2(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field fl_3 from data_log message
*
* @return Log value 3
*/
static inline float mavlink_msg_data_log_get_fl_3(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field fl_4 from data_log message
*
* @return Log value 4
*/
static inline float mavlink_msg_data_log_get_fl_4(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field fl_5 from data_log message
*
* @return Log value 5
*/
static inline float mavlink_msg_data_log_get_fl_5(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field fl_6 from data_log message
*
* @return Log value 6
*/
static inline float mavlink_msg_data_log_get_fl_6(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
static inline void mavlink_msg_data_log_decode(const mavlink_message_t* msg, mavlink_data_log_t* data_log)
{
data_log->fl_1 = mavlink_msg_data_log_get_fl_1(msg);
data_log->fl_2 = mavlink_msg_data_log_get_fl_2(msg);
data_log->fl_3 = mavlink_msg_data_log_get_fl_3(msg);
data_log->fl_4 = mavlink_msg_data_log_get_fl_4(msg);
data_log->fl_5 = mavlink_msg_data_log_get_fl_5(msg);
data_log->fl_6 = mavlink_msg_data_log_get_fl_6(msg);
}

View File

@ -1,10 +1,9 @@
// MESSAGE DIAGNOSTIC PACKING
#define MAVLINK_MSG_ID_DIAGNOSTIC 193
#define MAVLINK_MSG_ID_DIAGNOSTIC 173
typedef struct __mavlink_diagnostic_t
{
uint8_t target; ///< The system reporting the diagnostic
float diagFl1; ///< Diagnostic float 1
float diagFl2; ///< Diagnostic float 2
float diagFl3; ///< Diagnostic float 3
@ -19,7 +18,6 @@ typedef struct __mavlink_diagnostic_t
/**
* @brief Send a diagnostic message
*
* @param target The system reporting the diagnostic
* @param diagFl1 Diagnostic float 1
* @param diagFl2 Diagnostic float 2
* @param diagFl3 Diagnostic float 3
@ -28,12 +26,11 @@ typedef struct __mavlink_diagnostic_t
* @param diagSh3 Diagnostic short 3
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_diagnostic_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3)
static inline uint16_t mavlink_msg_diagnostic_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC;
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the diagnostic
i += put_float_by_index(diagFl1, i, msg->payload); //Diagnostic float 1
i += put_float_by_index(diagFl2, i, msg->payload); //Diagnostic float 2
i += put_float_by_index(diagFl3, i, msg->payload); //Diagnostic float 3
@ -62,12 +59,12 @@ static inline uint16_t mavlink_msg_diagnostic_pack_chan(uint8_t system_id, uint8
static inline uint16_t mavlink_msg_diagnostic_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_diagnostic_t* diagnostic)
{
return mavlink_msg_diagnostic_pack(system_id, component_id, msg, diagnostic->target, diagnostic->diagFl1, diagnostic->diagFl2, diagnostic->diagFl3, diagnostic->diagSh1, diagnostic->diagSh2, diagnostic->diagSh3);
return mavlink_msg_diagnostic_pack(system_id, component_id, msg, diagnostic->diagFl1, diagnostic->diagFl2, diagnostic->diagFl3, diagnostic->diagSh1, diagnostic->diagSh2, diagnostic->diagSh3);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_diagnostic_send(mavlink_channel_t chan, uint8_t target, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3)
static inline void mavlink_msg_diagnostic_send(mavlink_channel_t chan, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3)
{
mavlink_message_t msg;
mavlink_msg_diagnostic_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, diagFl1, diagFl2, diagFl3, diagSh1, diagSh2, diagSh3);
@ -77,16 +74,6 @@ static inline void mavlink_msg_diagnostic_send(mavlink_channel_t chan, uint8_t t
#endif
// MESSAGE DIAGNOSTIC UNPACKING
/**
* @brief Get field target from diagnostic message
*
* @return The system reporting the diagnostic
*/
static inline uint8_t mavlink_msg_diagnostic_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field diagFl1 from diagnostic message
*
@ -95,10 +82,10 @@ static inline uint8_t mavlink_msg_diagnostic_get_target(const mavlink_message_t*
static inline float mavlink_msg_diagnostic_get_diagFl1(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t))[3];
r.b[3] = (msg->payload)[0];
r.b[2] = (msg->payload)[1];
r.b[1] = (msg->payload)[2];
r.b[0] = (msg->payload)[3];
return (float)r.f;
}
@ -110,10 +97,10 @@ static inline float mavlink_msg_diagnostic_get_diagFl1(const mavlink_message_t*
static inline float mavlink_msg_diagnostic_get_diagFl2(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3];
r.b[3] = (msg->payload+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float))[3];
return (float)r.f;
}
@ -125,10 +112,10 @@ static inline float mavlink_msg_diagnostic_get_diagFl2(const mavlink_message_t*
static inline float mavlink_msg_diagnostic_get_diagFl3(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
@ -140,8 +127,8 @@ static inline float mavlink_msg_diagnostic_get_diagFl3(const mavlink_message_t*
static inline int16_t mavlink_msg_diagnostic_get_diagSh1(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
return (int16_t)r.s;
}
@ -153,8 +140,8 @@ static inline int16_t mavlink_msg_diagnostic_get_diagSh1(const mavlink_message_t
static inline int16_t mavlink_msg_diagnostic_get_diagSh2(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
@ -166,14 +153,13 @@ static inline int16_t mavlink_msg_diagnostic_get_diagSh2(const mavlink_message_t
static inline int16_t mavlink_msg_diagnostic_get_diagSh3(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
static inline void mavlink_msg_diagnostic_decode(const mavlink_message_t* msg, mavlink_diagnostic_t* diagnostic)
{
diagnostic->target = mavlink_msg_diagnostic_get_target(msg);
diagnostic->diagFl1 = mavlink_msg_diagnostic_get_diagFl1(msg);
diagnostic->diagFl2 = mavlink_msg_diagnostic_get_diagFl2(msg);
diagnostic->diagFl3 = mavlink_msg_diagnostic_get_diagFl3(msg);

View File

@ -0,0 +1,216 @@
// MESSAGE FILTERED_DATA PACKING
#define MAVLINK_MSG_ID_FILTERED_DATA 178
typedef struct __mavlink_filtered_data_t
{
float aX; ///< Accelerometer X value (m/s^2)
float aY; ///< Accelerometer Y value (m/s^2)
float aZ; ///< Accelerometer Z value (m/s^2)
float gX; ///< Gyro X value (rad/s)
float gY; ///< Gyro Y value (rad/s)
float gZ; ///< Gyro Z value (rad/s)
float mX; ///< Magnetometer X (normalized to 1)
float mY; ///< Magnetometer Y (normalized to 1)
float mZ; ///< Magnetometer Z (normalized to 1)
} mavlink_filtered_data_t;
/**
* @brief Send a filtered_data message
*
* @param aX Accelerometer X value (m/s^2)
* @param aY Accelerometer Y value (m/s^2)
* @param aZ Accelerometer Z value (m/s^2)
* @param gX Gyro X value (rad/s)
* @param gY Gyro Y value (rad/s)
* @param gZ Gyro Z value (rad/s)
* @param mX Magnetometer X (normalized to 1)
* @param mY Magnetometer Y (normalized to 1)
* @param mZ Magnetometer Z (normalized to 1)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_filtered_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float aX, float aY, float aZ, float gX, float gY, float gZ, float mX, float mY, float mZ)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_FILTERED_DATA;
i += put_float_by_index(aX, i, msg->payload); //Accelerometer X value (m/s^2)
i += put_float_by_index(aY, i, msg->payload); //Accelerometer Y value (m/s^2)
i += put_float_by_index(aZ, i, msg->payload); //Accelerometer Z value (m/s^2)
i += put_float_by_index(gX, i, msg->payload); //Gyro X value (rad/s)
i += put_float_by_index(gY, i, msg->payload); //Gyro Y value (rad/s)
i += put_float_by_index(gZ, i, msg->payload); //Gyro Z value (rad/s)
i += put_float_by_index(mX, i, msg->payload); //Magnetometer X (normalized to 1)
i += put_float_by_index(mY, i, msg->payload); //Magnetometer Y (normalized to 1)
i += put_float_by_index(mZ, i, msg->payload); //Magnetometer Z (normalized to 1)
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_filtered_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_filtered_data_t* filtered_data)
{
return mavlink_msg_filtered_data_pack(system_id, component_id, msg, filtered_data->aX, filtered_data->aY, filtered_data->aZ, filtered_data->gX, filtered_data->gY, filtered_data->gZ, filtered_data->mX, filtered_data->mY, filtered_data->mZ);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_filtered_data_send(mavlink_channel_t chan, float aX, float aY, float aZ, float gX, float gY, float gZ, float mX, float mY, float mZ)
{
mavlink_message_t msg;
mavlink_msg_filtered_data_pack(mavlink_system.sysid, mavlink_system.compid, &msg, aX, aY, aZ, gX, gY, gZ, mX, mY, mZ);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE FILTERED_DATA UNPACKING
/**
* @brief Get field aX from filtered_data message
*
* @return Accelerometer X value (m/s^2)
*/
static inline float mavlink_msg_filtered_data_get_aX(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload)[0];
r.b[2] = (msg->payload)[1];
r.b[1] = (msg->payload)[2];
r.b[0] = (msg->payload)[3];
return (float)r.f;
}
/**
* @brief Get field aY from filtered_data message
*
* @return Accelerometer Y value (m/s^2)
*/
static inline float mavlink_msg_filtered_data_get_aY(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field aZ from filtered_data message
*
* @return Accelerometer Z value (m/s^2)
*/
static inline float mavlink_msg_filtered_data_get_aZ(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field gX from filtered_data message
*
* @return Gyro X value (rad/s)
*/
static inline float mavlink_msg_filtered_data_get_gX(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field gY from filtered_data message
*
* @return Gyro Y value (rad/s)
*/
static inline float mavlink_msg_filtered_data_get_gY(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field gZ from filtered_data message
*
* @return Gyro Z value (rad/s)
*/
static inline float mavlink_msg_filtered_data_get_gZ(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field mX from filtered_data message
*
* @return Magnetometer X (normalized to 1)
*/
static inline float mavlink_msg_filtered_data_get_mX(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field mY from filtered_data message
*
* @return Magnetometer Y (normalized to 1)
*/
static inline float mavlink_msg_filtered_data_get_mY(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field mZ from filtered_data message
*
* @return Magnetometer Z (normalized to 1)
*/
static inline float mavlink_msg_filtered_data_get_mZ(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
static inline void mavlink_msg_filtered_data_decode(const mavlink_message_t* msg, mavlink_filtered_data_t* filtered_data)
{
filtered_data->aX = mavlink_msg_filtered_data_get_aX(msg);
filtered_data->aY = mavlink_msg_filtered_data_get_aY(msg);
filtered_data->aZ = mavlink_msg_filtered_data_get_aZ(msg);
filtered_data->gX = mavlink_msg_filtered_data_get_gX(msg);
filtered_data->gY = mavlink_msg_filtered_data_get_gY(msg);
filtered_data->gZ = mavlink_msg_filtered_data_get_gZ(msg);
filtered_data->mX = mavlink_msg_filtered_data_get_mX(msg);
filtered_data->mY = mavlink_msg_filtered_data_get_mY(msg);
filtered_data->mZ = mavlink_msg_filtered_data_get_mZ(msg);
}

View File

@ -0,0 +1,143 @@
// MESSAGE GPS_DATE_TIME PACKING
#define MAVLINK_MSG_ID_GPS_DATE_TIME 179
typedef struct __mavlink_gps_date_time_t
{
uint8_t year; ///< Year reported by Gps
uint8_t month; ///< Month reported by Gps
uint8_t day; ///< Day reported by Gps
uint8_t hour; ///< Hour reported by Gps
uint8_t min; ///< Min reported by Gps
uint8_t sec; ///< Sec reported by Gps
uint8_t visSat; ///< Visible sattelites reported by Gps
} mavlink_gps_date_time_t;
/**
* @brief Send a gps_date_time message
*
* @param year Year reported by Gps
* @param month Month reported by Gps
* @param day Day reported by Gps
* @param hour Hour reported by Gps
* @param min Min reported by Gps
* @param sec Sec reported by Gps
* @param visSat Visible sattelites reported by Gps
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_date_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_DATE_TIME;
i += put_uint8_t_by_index(year, i, msg->payload); //Year reported by Gps
i += put_uint8_t_by_index(month, i, msg->payload); //Month reported by Gps
i += put_uint8_t_by_index(day, i, msg->payload); //Day reported by Gps
i += put_uint8_t_by_index(hour, i, msg->payload); //Hour reported by Gps
i += put_uint8_t_by_index(min, i, msg->payload); //Min reported by Gps
i += put_uint8_t_by_index(sec, i, msg->payload); //Sec reported by Gps
i += put_uint8_t_by_index(visSat, i, msg->payload); //Visible sattelites reported by Gps
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_gps_date_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_date_time_t* gps_date_time)
{
return mavlink_msg_gps_date_time_pack(system_id, component_id, msg, gps_date_time->year, gps_date_time->month, gps_date_time->day, gps_date_time->hour, gps_date_time->min, gps_date_time->sec, gps_date_time->visSat);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_date_time_send(mavlink_channel_t chan, uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat)
{
mavlink_message_t msg;
mavlink_msg_gps_date_time_pack(mavlink_system.sysid, mavlink_system.compid, &msg, year, month, day, hour, min, sec, visSat);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE GPS_DATE_TIME UNPACKING
/**
* @brief Get field year from gps_date_time message
*
* @return Year reported by Gps
*/
static inline uint8_t mavlink_msg_gps_date_time_get_year(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field month from gps_date_time message
*
* @return Month reported by Gps
*/
static inline uint8_t mavlink_msg_gps_date_time_get_month(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field day from gps_date_time message
*
* @return Day reported by Gps
*/
static inline uint8_t mavlink_msg_gps_date_time_get_day(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field hour from gps_date_time message
*
* @return Hour reported by Gps
*/
static inline uint8_t mavlink_msg_gps_date_time_get_hour(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field min from gps_date_time message
*
* @return Min reported by Gps
*/
static inline uint8_t mavlink_msg_gps_date_time_get_min(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field sec from gps_date_time message
*
* @return Sec reported by Gps
*/
static inline uint8_t mavlink_msg_gps_date_time_get_sec(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field visSat from gps_date_time message
*
* @return Visible sattelites reported by Gps
*/
static inline uint8_t mavlink_msg_gps_date_time_get_visSat(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
static inline void mavlink_msg_gps_date_time_decode(const mavlink_message_t* msg, mavlink_gps_date_time_t* gps_date_time)
{
gps_date_time->year = mavlink_msg_gps_date_time_get_year(msg);
gps_date_time->month = mavlink_msg_gps_date_time_get_month(msg);
gps_date_time->day = mavlink_msg_gps_date_time_get_day(msg);
gps_date_time->hour = mavlink_msg_gps_date_time_get_hour(msg);
gps_date_time->min = mavlink_msg_gps_date_time_get_min(msg);
gps_date_time->sec = mavlink_msg_gps_date_time_get_sec(msg);
gps_date_time->visSat = mavlink_msg_gps_date_time_get_visSat(msg);
}

View File

@ -0,0 +1,116 @@
// MESSAGE MID_LVL_CMDS PACKING
#define MAVLINK_MSG_ID_MID_LVL_CMDS 180
typedef struct __mavlink_mid_lvl_cmds_t
{
uint8_t target; ///< The system setting the commands
float hCommand; ///< Commanded Airspeed
float uCommand; ///< Log value 2
float rCommand; ///< Log value 3
} mavlink_mid_lvl_cmds_t;
/**
* @brief Send a mid_lvl_cmds message
*
* @param target The system setting the commands
* @param hCommand Commanded Airspeed
* @param uCommand Log value 2
* @param rCommand Log value 3
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mid_lvl_cmds_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float hCommand, float uCommand, float rCommand)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_MID_LVL_CMDS;
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the commands
i += put_float_by_index(hCommand, i, msg->payload); //Commanded Airspeed
i += put_float_by_index(uCommand, i, msg->payload); //Log value 2
i += put_float_by_index(rCommand, i, msg->payload); //Log value 3
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_mid_lvl_cmds_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mid_lvl_cmds_t* mid_lvl_cmds)
{
return mavlink_msg_mid_lvl_cmds_pack(system_id, component_id, msg, mid_lvl_cmds->target, mid_lvl_cmds->hCommand, mid_lvl_cmds->uCommand, mid_lvl_cmds->rCommand);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_mid_lvl_cmds_send(mavlink_channel_t chan, uint8_t target, float hCommand, float uCommand, float rCommand)
{
mavlink_message_t msg;
mavlink_msg_mid_lvl_cmds_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, hCommand, uCommand, rCommand);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE MID_LVL_CMDS UNPACKING
/**
* @brief Get field target from mid_lvl_cmds message
*
* @return The system setting the commands
*/
static inline uint8_t mavlink_msg_mid_lvl_cmds_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field hCommand from mid_lvl_cmds message
*
* @return Commanded Airspeed
*/
static inline float mavlink_msg_mid_lvl_cmds_get_hCommand(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t))[3];
return (float)r.f;
}
/**
* @brief Get field uCommand from mid_lvl_cmds message
*
* @return Log value 2
*/
static inline float mavlink_msg_mid_lvl_cmds_get_uCommand(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field rCommand from mid_lvl_cmds message
*
* @return Log value 3
*/
static inline float mavlink_msg_mid_lvl_cmds_get_rCommand(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
static inline void mavlink_msg_mid_lvl_cmds_decode(const mavlink_message_t* msg, mavlink_mid_lvl_cmds_t* mid_lvl_cmds)
{
mid_lvl_cmds->target = mavlink_msg_mid_lvl_cmds_get_target(msg);
mid_lvl_cmds->hCommand = mavlink_msg_mid_lvl_cmds_get_hCommand(msg);
mid_lvl_cmds->uCommand = mavlink_msg_mid_lvl_cmds_get_uCommand(msg);
mid_lvl_cmds->rCommand = mavlink_msg_mid_lvl_cmds_get_rCommand(msg);
}

View File

@ -0,0 +1,130 @@
// MESSAGE PID PACKING
#define MAVLINK_MSG_ID_PID 182
typedef struct __mavlink_pid_t
{
uint8_t target; ///< The system setting the PID values
float pVal; ///< Proportional gain
float iVal; ///< Integral gain
float dVal; ///< Derivative gain
uint8_t idx; ///< PID loop index
} mavlink_pid_t;
/**
* @brief Send a pid message
*
* @param target The system setting the PID values
* @param pVal Proportional gain
* @param iVal Integral gain
* @param dVal Derivative gain
* @param idx PID loop index
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pid_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float pVal, float iVal, float dVal, uint8_t idx)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PID;
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the PID values
i += put_float_by_index(pVal, i, msg->payload); //Proportional gain
i += put_float_by_index(iVal, i, msg->payload); //Integral gain
i += put_float_by_index(dVal, i, msg->payload); //Derivative gain
i += put_uint8_t_by_index(idx, i, msg->payload); //PID loop index
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_pid_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pid_t* pid)
{
return mavlink_msg_pid_pack(system_id, component_id, msg, pid->target, pid->pVal, pid->iVal, pid->dVal, pid->idx);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_pid_send(mavlink_channel_t chan, uint8_t target, float pVal, float iVal, float dVal, uint8_t idx)
{
mavlink_message_t msg;
mavlink_msg_pid_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, pVal, iVal, dVal, idx);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE PID UNPACKING
/**
* @brief Get field target from pid message
*
* @return The system setting the PID values
*/
static inline uint8_t mavlink_msg_pid_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field pVal from pid message
*
* @return Proportional gain
*/
static inline float mavlink_msg_pid_get_pVal(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t))[3];
return (float)r.f;
}
/**
* @brief Get field iVal from pid message
*
* @return Integral gain
*/
static inline float mavlink_msg_pid_get_iVal(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field dVal from pid message
*
* @return Derivative gain
*/
static inline float mavlink_msg_pid_get_dVal(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field idx from pid message
*
* @return PID loop index
*/
static inline uint8_t mavlink_msg_pid_get_idx(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
}
static inline void mavlink_msg_pid_decode(const mavlink_message_t* msg, mavlink_pid_t* pid)
{
pid->target = mavlink_msg_pid_get_target(msg);
pid->pVal = mavlink_msg_pid_get_pVal(msg);
pid->iVal = mavlink_msg_pid_get_iVal(msg);
pid->dVal = mavlink_msg_pid_get_dVal(msg);
pid->idx = mavlink_msg_pid_get_idx(msg);
}

View File

@ -1,10 +1,9 @@
// MESSAGE PILOT_CONSOLE PACKING
#define MAVLINK_MSG_ID_PILOT_CONSOLE 194
#define MAVLINK_MSG_ID_PILOT_CONSOLE 174
typedef struct __mavlink_pilot_console_t
{
uint8_t target; ///< The system reporting the diagnostic
uint16_t dt; ///< Pilot's console throttle command
uint16_t dla; ///< Pilot's console left aileron command
uint16_t dra; ///< Pilot's console right aileron command
@ -18,7 +17,6 @@ typedef struct __mavlink_pilot_console_t
/**
* @brief Send a pilot_console message
*
* @param target The system reporting the diagnostic
* @param dt Pilot's console throttle command
* @param dla Pilot's console left aileron command
* @param dra Pilot's console right aileron command
@ -26,12 +24,11 @@ typedef struct __mavlink_pilot_console_t
* @param de Pilot's console elevator command
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pilot_console_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint16_t dt, uint16_t dla, uint16_t dra, uint16_t dr, uint16_t de)
static inline uint16_t mavlink_msg_pilot_console_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t dt, uint16_t dla, uint16_t dra, uint16_t dr, uint16_t de)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PILOT_CONSOLE;
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the diagnostic
i += put_uint16_t_by_index(dt, i, msg->payload); //Pilot's console throttle command
i += put_uint16_t_by_index(dla, i, msg->payload); //Pilot's console left aileron command
i += put_uint16_t_by_index(dra, i, msg->payload); //Pilot's console right aileron command
@ -58,12 +55,12 @@ static inline uint16_t mavlink_msg_pilot_console_pack_chan(uint8_t system_id, ui
static inline uint16_t mavlink_msg_pilot_console_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pilot_console_t* pilot_console)
{
return mavlink_msg_pilot_console_pack(system_id, component_id, msg, pilot_console->target, pilot_console->dt, pilot_console->dla, pilot_console->dra, pilot_console->dr, pilot_console->de);
return mavlink_msg_pilot_console_pack(system_id, component_id, msg, pilot_console->dt, pilot_console->dla, pilot_console->dra, pilot_console->dr, pilot_console->de);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_pilot_console_send(mavlink_channel_t chan, uint8_t target, uint16_t dt, uint16_t dla, uint16_t dra, uint16_t dr, uint16_t de)
static inline void mavlink_msg_pilot_console_send(mavlink_channel_t chan, uint16_t dt, uint16_t dla, uint16_t dra, uint16_t dr, uint16_t de)
{
mavlink_message_t msg;
mavlink_msg_pilot_console_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, dt, dla, dra, dr, de);
@ -73,16 +70,6 @@ static inline void mavlink_msg_pilot_console_send(mavlink_channel_t chan, uint8_
#endif
// MESSAGE PILOT_CONSOLE UNPACKING
/**
* @brief Get field target from pilot_console message
*
* @return The system reporting the diagnostic
*/
static inline uint8_t mavlink_msg_pilot_console_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field dt from pilot_console message
*
@ -91,8 +78,8 @@ static inline uint8_t mavlink_msg_pilot_console_get_target(const mavlink_message
static inline uint16_t mavlink_msg_pilot_console_get_dt(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t))[1];
r.b[1] = (msg->payload)[0];
r.b[0] = (msg->payload)[1];
return (uint16_t)r.s;
}
@ -104,8 +91,8 @@ static inline uint16_t mavlink_msg_pilot_console_get_dt(const mavlink_message_t*
static inline uint16_t mavlink_msg_pilot_console_get_dla(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[1];
r.b[1] = (msg->payload+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
@ -117,8 +104,8 @@ static inline uint16_t mavlink_msg_pilot_console_get_dla(const mavlink_message_t
static inline uint16_t mavlink_msg_pilot_console_get_dra(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
@ -130,8 +117,8 @@ static inline uint16_t mavlink_msg_pilot_console_get_dra(const mavlink_message_t
static inline uint16_t mavlink_msg_pilot_console_get_dr(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
@ -143,14 +130,13 @@ static inline uint16_t mavlink_msg_pilot_console_get_dr(const mavlink_message_t*
static inline uint16_t mavlink_msg_pilot_console_get_de(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
static inline void mavlink_msg_pilot_console_decode(const mavlink_message_t* msg, mavlink_pilot_console_t* pilot_console)
{
pilot_console->target = mavlink_msg_pilot_console_get_target(msg);
pilot_console->dt = mavlink_msg_pilot_console_get_dt(msg);
pilot_console->dla = mavlink_msg_pilot_console_get_dla(msg);
pilot_console->dra = mavlink_msg_pilot_console_get_dra(msg);

View File

@ -1,10 +1,9 @@
// MESSAGE PWM_COMMANDS PACKING
#define MAVLINK_MSG_ID_PWM_COMMANDS 195
#define MAVLINK_MSG_ID_PWM_COMMANDS 175
typedef struct __mavlink_pwm_commands_t
{
uint8_t target; ///< The system reporting the diagnostic
uint16_t dt_c; ///< AutoPilot's throttle command
uint16_t dla_c; ///< AutoPilot's left aileron command
uint16_t dra_c; ///< AutoPilot's right aileron command
@ -23,7 +22,6 @@ typedef struct __mavlink_pwm_commands_t
/**
* @brief Send a pwm_commands message
*
* @param target The system reporting the diagnostic
* @param dt_c AutoPilot's throttle command
* @param dla_c AutoPilot's left aileron command
* @param dra_c AutoPilot's right aileron command
@ -36,12 +34,11 @@ typedef struct __mavlink_pwm_commands_t
* @param aux2 AutoPilot's aux2 command
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pwm_commands_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint16_t dt_c, uint16_t dla_c, uint16_t dra_c, uint16_t dr_c, uint16_t dle_c, uint16_t dre_c, uint16_t dlf_c, uint16_t drf_c, uint16_t aux1, uint16_t aux2)
static inline uint16_t mavlink_msg_pwm_commands_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t dt_c, uint16_t dla_c, uint16_t dra_c, uint16_t dr_c, uint16_t dle_c, uint16_t dre_c, uint16_t dlf_c, uint16_t drf_c, uint16_t aux1, uint16_t aux2)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PWM_COMMANDS;
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the diagnostic
i += put_uint16_t_by_index(dt_c, i, msg->payload); //AutoPilot's throttle command
i += put_uint16_t_by_index(dla_c, i, msg->payload); //AutoPilot's left aileron command
i += put_uint16_t_by_index(dra_c, i, msg->payload); //AutoPilot's right aileron command
@ -78,12 +75,12 @@ static inline uint16_t mavlink_msg_pwm_commands_pack_chan(uint8_t system_id, uin
static inline uint16_t mavlink_msg_pwm_commands_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pwm_commands_t* pwm_commands)
{
return mavlink_msg_pwm_commands_pack(system_id, component_id, msg, pwm_commands->target, pwm_commands->dt_c, pwm_commands->dla_c, pwm_commands->dra_c, pwm_commands->dr_c, pwm_commands->dle_c, pwm_commands->dre_c, pwm_commands->dlf_c, pwm_commands->drf_c, pwm_commands->aux1, pwm_commands->aux2);
return mavlink_msg_pwm_commands_pack(system_id, component_id, msg, pwm_commands->dt_c, pwm_commands->dla_c, pwm_commands->dra_c, pwm_commands->dr_c, pwm_commands->dle_c, pwm_commands->dre_c, pwm_commands->dlf_c, pwm_commands->drf_c, pwm_commands->aux1, pwm_commands->aux2);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_pwm_commands_send(mavlink_channel_t chan, uint8_t target, uint16_t dt_c, uint16_t dla_c, uint16_t dra_c, uint16_t dr_c, uint16_t dle_c, uint16_t dre_c, uint16_t dlf_c, uint16_t drf_c, uint16_t aux1, uint16_t aux2)
static inline void mavlink_msg_pwm_commands_send(mavlink_channel_t chan, uint16_t dt_c, uint16_t dla_c, uint16_t dra_c, uint16_t dr_c, uint16_t dle_c, uint16_t dre_c, uint16_t dlf_c, uint16_t drf_c, uint16_t aux1, uint16_t aux2)
{
mavlink_message_t msg;
mavlink_msg_pwm_commands_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, dt_c, dla_c, dra_c, dr_c, dle_c, dre_c, dlf_c, drf_c, aux1, aux2);
@ -93,16 +90,6 @@ static inline void mavlink_msg_pwm_commands_send(mavlink_channel_t chan, uint8_t
#endif
// MESSAGE PWM_COMMANDS UNPACKING
/**
* @brief Get field target from pwm_commands message
*
* @return The system reporting the diagnostic
*/
static inline uint8_t mavlink_msg_pwm_commands_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field dt_c from pwm_commands message
*
@ -111,8 +98,8 @@ static inline uint8_t mavlink_msg_pwm_commands_get_target(const mavlink_message_
static inline uint16_t mavlink_msg_pwm_commands_get_dt_c(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t))[1];
r.b[1] = (msg->payload)[0];
r.b[0] = (msg->payload)[1];
return (uint16_t)r.s;
}
@ -124,8 +111,8 @@ static inline uint16_t mavlink_msg_pwm_commands_get_dt_c(const mavlink_message_t
static inline uint16_t mavlink_msg_pwm_commands_get_dla_c(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[1];
r.b[1] = (msg->payload+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
@ -137,8 +124,8 @@ static inline uint16_t mavlink_msg_pwm_commands_get_dla_c(const mavlink_message_
static inline uint16_t mavlink_msg_pwm_commands_get_dra_c(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
@ -150,8 +137,8 @@ static inline uint16_t mavlink_msg_pwm_commands_get_dra_c(const mavlink_message_
static inline uint16_t mavlink_msg_pwm_commands_get_dr_c(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
@ -163,8 +150,8 @@ static inline uint16_t mavlink_msg_pwm_commands_get_dr_c(const mavlink_message_t
static inline uint16_t mavlink_msg_pwm_commands_get_dle_c(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
@ -176,8 +163,8 @@ static inline uint16_t mavlink_msg_pwm_commands_get_dle_c(const mavlink_message_
static inline uint16_t mavlink_msg_pwm_commands_get_dre_c(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
@ -189,8 +176,8 @@ static inline uint16_t mavlink_msg_pwm_commands_get_dre_c(const mavlink_message_
static inline uint16_t mavlink_msg_pwm_commands_get_dlf_c(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
@ -202,8 +189,8 @@ static inline uint16_t mavlink_msg_pwm_commands_get_dlf_c(const mavlink_message_
static inline uint16_t mavlink_msg_pwm_commands_get_drf_c(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
@ -215,8 +202,8 @@ static inline uint16_t mavlink_msg_pwm_commands_get_drf_c(const mavlink_message_
static inline uint16_t mavlink_msg_pwm_commands_get_aux1(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
@ -228,14 +215,13 @@ static inline uint16_t mavlink_msg_pwm_commands_get_aux1(const mavlink_message_t
static inline uint16_t mavlink_msg_pwm_commands_get_aux2(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
static inline void mavlink_msg_pwm_commands_decode(const mavlink_message_t* msg, mavlink_pwm_commands_t* pwm_commands)
{
pwm_commands->target = mavlink_msg_pwm_commands_get_target(msg);
pwm_commands->dt_c = mavlink_msg_pwm_commands_get_dt_c(msg);
pwm_commands->dla_c = mavlink_msg_pwm_commands_get_dla_c(msg);
pwm_commands->dra_c = mavlink_msg_pwm_commands_get_dra_c(msg);

View File

@ -1,10 +1,9 @@
// MESSAGE SENSOR_BIAS PACKING
#define MAVLINK_MSG_ID_SENSOR_BIAS 192
#define MAVLINK_MSG_ID_SENSOR_BIAS 172
typedef struct __mavlink_sensor_bias_t
{
uint8_t target; ///< The system reporting the biases
float axBias; ///< Accelerometer X bias (m/s)
float ayBias; ///< Accelerometer Y bias (m/s)
float azBias; ///< Accelerometer Z bias (m/s)
@ -19,7 +18,6 @@ typedef struct __mavlink_sensor_bias_t
/**
* @brief Send a sensor_bias message
*
* @param target The system reporting the biases
* @param axBias Accelerometer X bias (m/s)
* @param ayBias Accelerometer Y bias (m/s)
* @param azBias Accelerometer Z bias (m/s)
@ -28,12 +26,11 @@ typedef struct __mavlink_sensor_bias_t
* @param gzBias Gyro Z bias (rad/s)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensor_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
static inline uint16_t mavlink_msg_sensor_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS;
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the biases
i += put_float_by_index(axBias, i, msg->payload); //Accelerometer X bias (m/s)
i += put_float_by_index(ayBias, i, msg->payload); //Accelerometer Y bias (m/s)
i += put_float_by_index(azBias, i, msg->payload); //Accelerometer Z bias (m/s)
@ -62,12 +59,12 @@ static inline uint16_t mavlink_msg_sensor_bias_pack_chan(uint8_t system_id, uint
static inline uint16_t mavlink_msg_sensor_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_bias_t* sensor_bias)
{
return mavlink_msg_sensor_bias_pack(system_id, component_id, msg, sensor_bias->target, sensor_bias->axBias, sensor_bias->ayBias, sensor_bias->azBias, sensor_bias->gxBias, sensor_bias->gyBias, sensor_bias->gzBias);
return mavlink_msg_sensor_bias_pack(system_id, component_id, msg, sensor_bias->axBias, sensor_bias->ayBias, sensor_bias->azBias, sensor_bias->gxBias, sensor_bias->gyBias, sensor_bias->gzBias);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_sensor_bias_send(mavlink_channel_t chan, uint8_t target, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
static inline void mavlink_msg_sensor_bias_send(mavlink_channel_t chan, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
{
mavlink_message_t msg;
mavlink_msg_sensor_bias_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, axBias, ayBias, azBias, gxBias, gyBias, gzBias);
@ -77,16 +74,6 @@ static inline void mavlink_msg_sensor_bias_send(mavlink_channel_t chan, uint8_t
#endif
// MESSAGE SENSOR_BIAS UNPACKING
/**
* @brief Get field target from sensor_bias message
*
* @return The system reporting the biases
*/
static inline uint8_t mavlink_msg_sensor_bias_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field axBias from sensor_bias message
*
@ -95,10 +82,10 @@ static inline uint8_t mavlink_msg_sensor_bias_get_target(const mavlink_message_t
static inline float mavlink_msg_sensor_bias_get_axBias(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t))[3];
r.b[3] = (msg->payload)[0];
r.b[2] = (msg->payload)[1];
r.b[1] = (msg->payload)[2];
r.b[0] = (msg->payload)[3];
return (float)r.f;
}
@ -110,10 +97,10 @@ static inline float mavlink_msg_sensor_bias_get_axBias(const mavlink_message_t*
static inline float mavlink_msg_sensor_bias_get_ayBias(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3];
r.b[3] = (msg->payload+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float))[3];
return (float)r.f;
}
@ -125,10 +112,10 @@ static inline float mavlink_msg_sensor_bias_get_ayBias(const mavlink_message_t*
static inline float mavlink_msg_sensor_bias_get_azBias(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
@ -140,10 +127,10 @@ static inline float mavlink_msg_sensor_bias_get_azBias(const mavlink_message_t*
static inline float mavlink_msg_sensor_bias_get_gxBias(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
@ -155,10 +142,10 @@ static inline float mavlink_msg_sensor_bias_get_gxBias(const mavlink_message_t*
static inline float mavlink_msg_sensor_bias_get_gyBias(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
@ -170,16 +157,15 @@ static inline float mavlink_msg_sensor_bias_get_gyBias(const mavlink_message_t*
static inline float mavlink_msg_sensor_bias_get_gzBias(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
static inline void mavlink_msg_sensor_bias_decode(const mavlink_message_t* msg, mavlink_sensor_bias_t* sensor_bias)
{
sensor_bias->target = mavlink_msg_sensor_bias_get_target(msg);
sensor_bias->axBias = mavlink_msg_sensor_bias_get_axBias(msg);
sensor_bias->ayBias = mavlink_msg_sensor_bias_get_ayBias(msg);
sensor_bias->azBias = mavlink_msg_sensor_bias_get_azBias(msg);

View File

@ -0,0 +1,90 @@
// MESSAGE SLUGS_ACTION PACKING
#define MAVLINK_MSG_ID_SLUGS_ACTION 183
typedef struct __mavlink_slugs_action_t
{
uint8_t target; ///< The system reporting the action
uint8_t actionId; ///< Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
uint16_t actionVal; ///< Value associated with the action
} mavlink_slugs_action_t;
/**
* @brief Send a slugs_action message
*
* @param target The system reporting the action
* @param actionId Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
* @param actionVal Value associated with the action
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_slugs_action_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint8_t actionId, uint16_t actionVal)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SLUGS_ACTION;
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the action
i += put_uint8_t_by_index(actionId, i, msg->payload); //Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
i += put_uint16_t_by_index(actionVal, i, msg->payload); //Value associated with the action
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_slugs_action_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_slugs_action_t* slugs_action)
{
return mavlink_msg_slugs_action_pack(system_id, component_id, msg, slugs_action->target, slugs_action->actionId, slugs_action->actionVal);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_slugs_action_send(mavlink_channel_t chan, uint8_t target, uint8_t actionId, uint16_t actionVal)
{
mavlink_message_t msg;
mavlink_msg_slugs_action_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, actionId, actionVal);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE SLUGS_ACTION UNPACKING
/**
* @brief Get field target from slugs_action message
*
* @return The system reporting the action
*/
static inline uint8_t mavlink_msg_slugs_action_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field actionId from slugs_action message
*
* @return Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
*/
static inline uint8_t mavlink_msg_slugs_action_get_actionId(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field actionVal from slugs_action message
*
* @return Value associated with the action
*/
static inline uint16_t mavlink_msg_slugs_action_get_actionVal(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
return (uint16_t)r.s;
}
static inline void mavlink_msg_slugs_action_decode(const mavlink_message_t* msg, mavlink_slugs_action_t* slugs_action)
{
slugs_action->target = mavlink_msg_slugs_action_get_target(msg);
slugs_action->actionId = mavlink_msg_slugs_action_get_actionId(msg);
slugs_action->actionVal = mavlink_msg_slugs_action_get_actionVal(msg);
}

View File

@ -0,0 +1,206 @@
// MESSAGE SLUGS_NAVIGATION PACKING
#define MAVLINK_MSG_ID_SLUGS_NAVIGATION 176
typedef struct __mavlink_slugs_navigation_t
{
float u_m; ///< Measured Airspeed prior to the Nav Filter
float phi_c; ///< Commanded Roll
float theta_c; ///< Commanded Pitch
float psiDot_c; ///< Commanded Turn rate
float ay_body; ///< Y component of the body acceleration
float totalDist; ///< Total Distance to Run on this leg of Navigation
float dist2Go; ///< Remaining distance to Run on this leg of Navigation
uint8_t fromWP; ///< Origin WP
uint8_t toWP; ///< Destination WP
} mavlink_slugs_navigation_t;
/**
* @brief Send a slugs_navigation message
*
* @param u_m Measured Airspeed prior to the Nav Filter
* @param phi_c Commanded Roll
* @param theta_c Commanded Pitch
* @param psiDot_c Commanded Turn rate
* @param ay_body Y component of the body acceleration
* @param totalDist Total Distance to Run on this leg of Navigation
* @param dist2Go Remaining distance to Run on this leg of Navigation
* @param fromWP Origin WP
* @param toWP Destination WP
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_slugs_navigation_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float u_m, float phi_c, float theta_c, float psiDot_c, float ay_body, float totalDist, float dist2Go, uint8_t fromWP, uint8_t toWP)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SLUGS_NAVIGATION;
i += put_float_by_index(u_m, i, msg->payload); //Measured Airspeed prior to the Nav Filter
i += put_float_by_index(phi_c, i, msg->payload); //Commanded Roll
i += put_float_by_index(theta_c, i, msg->payload); //Commanded Pitch
i += put_float_by_index(psiDot_c, i, msg->payload); //Commanded Turn rate
i += put_float_by_index(ay_body, i, msg->payload); //Y component of the body acceleration
i += put_float_by_index(totalDist, i, msg->payload); //Total Distance to Run on this leg of Navigation
i += put_float_by_index(dist2Go, i, msg->payload); //Remaining distance to Run on this leg of Navigation
i += put_uint8_t_by_index(fromWP, i, msg->payload); //Origin WP
i += put_uint8_t_by_index(toWP, i, msg->payload); //Destination WP
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_slugs_navigation_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_slugs_navigation_t* slugs_navigation)
{
return mavlink_msg_slugs_navigation_pack(system_id, component_id, msg, slugs_navigation->u_m, slugs_navigation->phi_c, slugs_navigation->theta_c, slugs_navigation->psiDot_c, slugs_navigation->ay_body, slugs_navigation->totalDist, slugs_navigation->dist2Go, slugs_navigation->fromWP, slugs_navigation->toWP);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_slugs_navigation_send(mavlink_channel_t chan, float u_m, float phi_c, float theta_c, float psiDot_c, float ay_body, float totalDist, float dist2Go, uint8_t fromWP, uint8_t toWP)
{
mavlink_message_t msg;
mavlink_msg_slugs_navigation_pack(mavlink_system.sysid, mavlink_system.compid, &msg, u_m, phi_c, theta_c, psiDot_c, ay_body, totalDist, dist2Go, fromWP, toWP);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE SLUGS_NAVIGATION UNPACKING
/**
* @brief Get field u_m from slugs_navigation message
*
* @return Measured Airspeed prior to the Nav Filter
*/
static inline float mavlink_msg_slugs_navigation_get_u_m(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload)[0];
r.b[2] = (msg->payload)[1];
r.b[1] = (msg->payload)[2];
r.b[0] = (msg->payload)[3];
return (float)r.f;
}
/**
* @brief Get field phi_c from slugs_navigation message
*
* @return Commanded Roll
*/
static inline float mavlink_msg_slugs_navigation_get_phi_c(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field theta_c from slugs_navigation message
*
* @return Commanded Pitch
*/
static inline float mavlink_msg_slugs_navigation_get_theta_c(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field psiDot_c from slugs_navigation message
*
* @return Commanded Turn rate
*/
static inline float mavlink_msg_slugs_navigation_get_psiDot_c(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field ay_body from slugs_navigation message
*
* @return Y component of the body acceleration
*/
static inline float mavlink_msg_slugs_navigation_get_ay_body(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field totalDist from slugs_navigation message
*
* @return Total Distance to Run on this leg of Navigation
*/
static inline float mavlink_msg_slugs_navigation_get_totalDist(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field dist2Go from slugs_navigation message
*
* @return Remaining distance to Run on this leg of Navigation
*/
static inline float mavlink_msg_slugs_navigation_get_dist2Go(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field fromWP from slugs_navigation message
*
* @return Origin WP
*/
static inline uint8_t mavlink_msg_slugs_navigation_get_fromWP(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
}
/**
* @brief Get field toWP from slugs_navigation message
*
* @return Destination WP
*/
static inline uint8_t mavlink_msg_slugs_navigation_get_toWP(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0];
}
static inline void mavlink_msg_slugs_navigation_decode(const mavlink_message_t* msg, mavlink_slugs_navigation_t* slugs_navigation)
{
slugs_navigation->u_m = mavlink_msg_slugs_navigation_get_u_m(msg);
slugs_navigation->phi_c = mavlink_msg_slugs_navigation_get_phi_c(msg);
slugs_navigation->theta_c = mavlink_msg_slugs_navigation_get_theta_c(msg);
slugs_navigation->psiDot_c = mavlink_msg_slugs_navigation_get_psiDot_c(msg);
slugs_navigation->ay_body = mavlink_msg_slugs_navigation_get_ay_body(msg);
slugs_navigation->totalDist = mavlink_msg_slugs_navigation_get_totalDist(msg);
slugs_navigation->dist2Go = mavlink_msg_slugs_navigation_get_dist2Go(msg);
slugs_navigation->fromWP = mavlink_msg_slugs_navigation_get_fromWP(msg);
slugs_navigation->toWP = mavlink_msg_slugs_navigation_get_toWP(msg);
}

View File

@ -28,6 +28,14 @@ extern "C" {
#include "./mavlink_msg_diagnostic.h"
#include "./mavlink_msg_pilot_console.h"
#include "./mavlink_msg_pwm_commands.h"
#include "./mavlink_msg_slugs_navigation.h"
#include "./mavlink_msg_data_log.h"
#include "./mavlink_msg_filtered_data.h"
#include "./mavlink_msg_gps_date_time.h"
#include "./mavlink_msg_mid_lvl_cmds.h"
#include "./mavlink_msg_ctrl_srfc_pt.h"
#include "./mavlink_msg_pid.h"
#include "./mavlink_msg_slugs_action.h"
#ifdef __cplusplus
}
#endif

View File

@ -9,7 +9,7 @@
</message>
<message name="BOOT" id="1">
<description>The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions.</description>
<description>The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions.</description>
<field name="version" type="uint32_t">The onboard software version</field>
</message>
@ -27,14 +27,14 @@
</message>
<message name="ACTION" id="10">
<description>An action message allows to execute a certain onboard action. These include liftoff, land, storing parameters too EEPROM, shutddown, etc. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description>
<description>An action message allows to execute a certain onboard action. These include liftoff, land, storing parameters too EEPROM, shutddown, etc. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description>
<field name="target" type="uint8_t">The system executing the action</field>
<field name="target_component" type="uint8_t">The component executing the action</field>
<field name="action" type="uint8_t">The action id</field>
</message>
<message name="ACTION_ACK" id="62">
<description>This message acknowledges an action. IMPORTANT: The acknowledgement can be also negative, e.g. the MAV rejects a reset message because it is in-flight. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description>
<description>This message acknowledges an action. IMPORTANT: The acknowledgement can be also negative, e.g. the MAV rejects a reset message because it is in-flight. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description>
<field name="action" type="uint8_t">The action id</field>
<field name="result" type="uint8_t">0: Action DENIED, 1: Action executed</field>
</message>
@ -98,9 +98,10 @@
<message name="RAW_PRESSURE" id="29">
<description>The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, unscaled ADC values.</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch)</field>
<field name="press_abs" type="int32_t">Absolute pressure (hectopascal)</field>
<field name="press_diff1" type="int32_t">Differential pressure 1 (hectopascal)</field>
<field name="press_diff2" type="int32_t">Differential pressure 2 (hectopascal)</field>
<field name="press_abs" type="int16_t">Absolute pressure (hectopascal)</field>
<field name="press_diff1" type="int16_t">Differential pressure 1 (hectopascal)</field>
<field name="press_diff2" type="int16_t">Differential pressure 2 (hectopascal)</field>
<field name="temperature" type="int16_t">Raw Temperature measurement </field>
</message>
<message name="ATTITUDE" id="30">
@ -339,7 +340,7 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se
<field name="z" type="float">z position</field>
<field name="yaw" type="float">yaw orientation in radians, 0 = NORTH</field>
</message>
<message name="STATE_CORRECTION" id="64">
<description>Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle.</description>
<field name="xErr" type="float">x position error</field>

View File

@ -0,0 +1,227 @@
<?xml version="1.0"?>
<mavlink>
<messages>
<message name="HEARTBEAT" id="0">
<description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description>
<field name="type" type="uint8_t">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
<field name="autopilot" type="uint8_t">Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM</field>
</message>
<message name="BOOT" id="1">
<description>The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions.</description>
<field name="version" type="uint32_t">The onboard software version</field>
</message>
<message name="SYSTEM_TIME" id="2">
<description>The system time is the time of the master clock, typically the computer clock of the main onboard computer.</description>
<field name="time_usec" type="uint64_t">Timestamp of the master clock in microseconds since UNIX epoch.</field>
</message>
<message name="PING" id="3">
<description>A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections.</description>
<field name="seq" type="uint32_t">PING sequence</field>
<field name="target_system" type="uint8_t">0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system</field>
<field name="target_component" type="uint8_t">0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system</field>
<field name="time" type="uint64_t">Unix timestamp in microseconds</field>
</message>
<message name="ACTION" id="10">
<description>An action message allows to execute a certain onboard action. These include liftoff, land, storing parameters too EEPROM, shutddown, etc. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description>
<field name="target" type="uint8_t">The system executing the action</field>
<field name="target_component" type="uint8_t">The component executing the action</field>
<field name="action" type="uint8_t">The action id</field>
</message>
<message name="ACTION_ACK" id="62">
<description>This message acknowledges an action. IMPORTANT: The acknowledgement can be also negative, e.g. the MAV rejects a reset message because it is in-flight. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description>
<field name="action" type="uint8_t">The action id</field>
<field name="result" type="uint8_t">0: Action DENIED, 1: Action executed</field>
</message>
<message name="SET_MODE" id="11">
<description>Set the system mode, as defined by enum MAV_MODE in mavlink/include/mavlink_types.h. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.</description>
<field name="target" type="uint8_t">The system setting the mode</field>
<field name="mode" type="uint8_t">The new mode</field>
</message>
<message name="SET_NAV_MODE" id="12">
<description>Set the system navigation mode, as defined by enum MAV_NAV_MODE in mavlink/include/mavlink_types.h. The navigation mode applies to the whole aircraft and thus all components.</description>
<field name="target" type="uint8_t">The system setting the mode</field>
<field name="nav_mode" type="uint8_t">The new navigation mode</field>
</message>
<message name="RAW_IMU" id="28">
<description>The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging.</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch)</field>
<field name="xacc" type="int16_t">X acceleration (mg raw)</field>
<field name="yacc" type="int16_t">Y acceleration (mg raw)</field>
<field name="zacc" type="int16_t">Z acceleration (mg raw)</field>
<field name="xgyro" type="int16_t">Angular speed around X axis (adc units)</field>
<field name="ygyro" type="int16_t">Angular speed around Y axis (adc units)</field>
<field name="zgyro" type="int16_t">Angular speed around Z axis (adc units)</field>
<field name="xmag" type="int16_t">X Magnetic field (milli tesla)</field>
<field name="ymag" type="int16_t">Y Magnetic field (milli tesla)</field>
<field name="zmag" type="int16_t">Z Magnetic field (milli tesla)</field>
</message>
<message name="RAW_PRESSURE" id="29">
<description>The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, unscaled ADC values.</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch)</field>
<field name="press_abs" type="int16_t">Absolute pressure (hectopascal)</field>
<field name="press_diff1" type="int16_t">Differential pressure 1 (hectopascal)</field>
<field name="press_diff2" type="int16_t">Differential pressure 2 (hectopascal)</field>
<field name="temperature" type="int16_t">Raw Temperature measurement </field>
</message>
<message name="ATTITUDE" id="30">
<description>The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).</description>
<field name="usec" type="uint64_t">Timestamp (microseconds)</field>
<field name="roll" type="float">Roll angle (rad)</field>
<field name="pitch" type="float">Pitch angle (rad)</field>
<field name="yaw" type="float">Yaw angle (rad)</field>
<field name="rollspeed" type="float">Roll angular speed (rad/s)</field>
<field name="pitchspeed" type="float">Pitch angular speed (rad/s)</field>
<field name="yawspeed" type="float">Yaw angular speed (rad/s)</field>
</message>
<message name="LOCAL_POSITION" id="31">
<description>The filtered local position (e.g. fused computer vision and accelerometers).</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since unix epoch)</field>
<field name="x" type="float">X Position</field>
<field name="y" type="float">Y Position</field>
<field name="z" type="float">Z Position</field>
<field name="vx" type="float">X Speed</field>
<field name="vy" type="float">Y Speed</field>
<field name="vz" type="float">Z Speed</field>
</message>
<message name="GPS_RAW" id="32">
<description>The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate.</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since unix epoch)</field>
<field name="fix_type" type="uint8_t">0-1: no fix, 2: 2D fix, 3: 3D fix</field>
<field name="lat" type="float">X Position</field>
<field name="lon" type="float">Y Position</field>
<field name="alt" type="float">Z Position in meters</field>
<field name="eph" type="float">Uncertainty in meters of latitude</field>
<field name="epv" type="float">Uncertainty in meters of longitude</field>
<field name="v" type="float">Overall speed</field>
<field name="hdg" type="float">Heading, in FIXME</field>
</message>
<message name="GPS_STATUS" id="27">
<description>The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites.</description>
<field name="satellites_visible" type="uint8_t">Number of satellites visible</field>
<field name="satellite_prn" type="array[20]">Global satellite ID</field>
<field name="satellite_used" type="array[20]">0: Satellite not used, 1: used for localization</field>
<field name="satellite_elevation" type="array[20]">Elevation (0: right on top of receiver, 90: on the horizon) of satellite</field>
<field name="satellite_azimuth" type="array[20]">Direction of satellite, 0: 0 deg, 255: 360 deg.</field>
<field name="satellite_snr" type="array[20]">Signal to noise ratio of satellite</field>
</message>
<message name="SYS_STATUS" id="34">
<description>The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.</description>
<field name="mode" type="uint8_t">System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h</field>
<field name="nav_mode" type="uint8_t">Navigation mode, see MAV_NAV_MODE ENUM</field>
<field name="status" type="uint8_t">System status flag, see MAV_STATUS ENUM</field>
<field name="vbat" type="uint16_t">Battery voltage, in millivolts (1 = 1 millivolt)</field>
<field name="motor_block" type="uint8_t">Motor block status flag, 0: Motors can be switched on (and could be either off or on), 1: Mechanical motor block switch is on, motors cannot be switched on (and are definitely off)</field>
<field name="packet_drop" type="uint16_t">Dropped packets (packets that were corrupted on reception on the MAV)</field>
</message>
<message name="WAYPOINT" id="39">
<description>Message encoding a waypoint. This message is emitted to announce
the presence of a waypoint. It cannot be used to set a waypoint, use WAYPOINT_SET for this purpose. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon. The global and body frame are related as: positive Z-down, positive X(front looking north, positive Y(body:right) looking east. Therefore y encodes in global mode the latitude, whereas x encodes the longitude and z the GPS altitude (WGS84).</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="seq" type="uint16_t">Sequence</field>
<field name="type" type="uint8_t">0: global (GPS), 1: local, 2: global orbit, 3: local orbit</field>
<field name="orbit" type="float">Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint</field>
<field name="orbit_direction" type="uint8_t">Direction of the orbit circling: 0: clockwise, 1: counter-clockwise</field>
<field name="param1" type="float">For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters</field>
<field name="param2" type="float">For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds</field>
<field name="current" type="uint8_t">false:0, true:1</field>
<field name="x" type="float">local: x position, global: longitude</field>
<field name="y" type="float">y position: global: latitude</field>
<field name="z" type="float">z position: global: altitude</field>
<field name="yaw" type="float">yaw orientation in radians, 0 = NORTH</field>
<field name="autocontinue" type="uint8_t">autocontinue to next wp</field>
</message>
<message name="WAYPOINT_REQUEST" id="40">
<description>Request the information of the waypoint with the sequence number seq. The response of the system to this message should be a WAYPOINT message.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="seq" type="uint16_t">Sequence</field>
</message>
<message name="WAYPOINT_SET_CURRENT" id="41">
<description>Set the waypoint with sequence number seq as current waypoint. This means that the MAV will continue to this waypoint on the shortest path (not following the waypoints in-between).</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="seq" type="uint16_t">Sequence</field>
</message>
<message name="WAYPOINT_CURRENT" id="42">
<description>Message that announces the sequence number of the current active waypoint. The MAV will fly towards this waypoint.</description>
<field name="seq" type="uint16_t">Sequence</field>
</message>
<message name="WAYPOINT_COUNT" id="44">
<description>This message is emitted as response to WAYPOINT_REQUEST_LIST by the MAV. The GCS can then request the individual waypoints based on the knowledge of the total number of waypoints.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="count" type="uint16_t">Number of Waypoints in the Sequence</field>
</message>
<message name="WAYPOINT_CLEAR_ALL" id="45">
<description>Delete all waypoints at once.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
</message>
<message name="WAYPOINT_REACHED" id="46">
<description>A certain waypoint has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint.</description>
<field name="seq" type="uint16_t">Sequence</field>
</message>
<message name="WAYPOINT_ACK" id="47">
<description>Ack message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero).</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="type" type="uint8_t">0: OK, 1: Error</field>
</message>
<message name="WAYPOINT_SET_GLOBAL_REFERENCE" id="48">
<description>As local waypoints exist, the global waypoint reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="global_x" type="float">global x position</field>
<field name="global_y" type="float">global y position</field>
<field name="global_z" type="float">global z position</field>
<field name="global_yaw" type="float">global yaw orientation in radians, 0 = NORTH</field>
<field name="local_x" type="float">local x position that matches the global x position</field>
<field name="local_y" type="float">local y position that matches the global y position</field>
<field name="local_z" type="float">local z position that matches the global z position</field>
<field name="local_yaw" type="float">local yaw that matches the global yaw orientation</field>
</message>
<!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files -->
<message name="STATUSTEXT" id= "254">
<description>Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz).</description>
<field name="severity" type="uint8_t">Severity of status, 0 = info message, 255 = critical fault</field>
<field name="text" type="array[50]">Status text message, without null termination character</field>
</message>
<message name="DEBUG" id="255">
<description>Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N.</description>
<field name="ind" type="uint8_t">index of debug variable</field>
<field name="value" type="float">DEBUG value</field>
</message>
</messages>
</mavlink>

View File

@ -1,25 +1,57 @@
<?xml version="1.0"?>
<mavlink>
<include>common.xml</include>
<!-- <enums>
<enum name="SLUGS_ACTION" >
<description> Slugs Actions </description>
<entry name = "SLUGS_ACTION_NONE">
<entry name = "SLUGS_ACTION_SUCCESS">
<entry name = "SLUGS_ACTION_FAIL">
<entry name = "SLUGS_ACTION_EEPROM">
<entry name = "SLUGS_ACTION_MODE_CHANGE">
<entry name = "SLUGS_ACTION_MODE_REPORT">
<entry name = "SLUGS_ACTION_PT_CHANGE">
<entry name = "SLUGS_ACTION_PT_REPORT">
<entry name = "SLUGS_ACTION_PID_CHANGE">
<entry name = "SLUGS_ACTION_PID_REPORT">
<entry name = "SLUGS_ACTION_WP_CHANGE">
<entry name = "SLUGS_ACTION_WP_REPORT">
<entry name = "SLUGS_ACTION_MLC_CHANGE">
<entry name = "SLUGS_ACTION_MLC_REPORT">
</enum>
<enum name="WP_PROTOCOL_STATE" >
<description> Waypoint Protocol States </description>
<entry name = "WP_PROT_IDLE">
<entry name = "WP_PROT_LIST_REQUESTED">
<entry name = "WP_PROT_NUM_SENT">
<entry name = "WP_PROT_TX_WP">
<entry name = "WP_PROT_RX_WP">
<entry name = "WP_PROT_SENDING_WP_IDLE">
<entry name = "WP_PROT_GETTING_WP_IDLE">
</enum>
</enums> -->
<messages>
<message name="CPU_LOAD" id="190">
<message name="CPU_LOAD" id="170">
Sensor and DSC control loads.
<field name="target" type="uint8_t">The system reporting the CPU load</field>
<field name="sensLoad" type="uint8_t">Sensor DSC Load</field>
<field name="ctrlLoad" type="uint8_t">Control DSC Load</field>
<field name="batVolt" type="uint16_t">Battery Voltage in millivolts</field>
</message>
<message name="AIR_DATA" id="191">
<message name="AIR_DATA" id="171">
Air data for altitude and airspeed computation.
<field name="target" type="uint8_t">The system reporting the air data</field>
<field name="dynamicPressure" type="float">Dynamic pressure (Pa)</field>
<field name="staticPressure" type="float">Static pressure (Pa)</field>
<field name="temperature" type="uint16_t">Board temperature</field>
</message>
<message name="SENSOR_BIAS" id="192">
<message name="SENSOR_BIAS" id="172">
Accelerometer and gyro biases.
<field name="target" type="uint8_t">The system reporting the biases</field>
<field name="axBias" type="float">Accelerometer X bias (m/s)</field>
<field name="ayBias" type="float">Accelerometer Y bias (m/s)</field>
<field name="azBias" type="float">Accelerometer Z bias (m/s)</field>
@ -28,30 +60,27 @@
<field name="gzBias" type="float">Gyro Z bias (rad/s)</field>
</message>
<message name="DIAGNOSTIC" id="193">
<message name="DIAGNOSTIC" id="173">
Configurable diagnostic messages.
<field name="target" type="uint8_t">The system reporting the diagnostic</field>
<field name="diagFl1" type="float">Diagnostic float 1</field>
<field name="diagFl2" type="float">Diagnostic float 2</field>
<field name="diagFl3" type="float">Diagnostic float 3</field>
<field name="diagSh1" type="int16_t">Diagnostic short 1</field>
<field name="diagSh2" type="int16_t">Diagnostic short 2</field>
<field name="diagSh3" type="int16_t">Diagnostic short 3</field>
</message>
</message>
<message name="PILOT_CONSOLE" id="194">
<message name="PILOT_CONSOLE" id="174">
Pilot console PWM messges.
<field name="target" type="uint8_t">The system reporting the diagnostic</field>
<field name="dt" type="uint16_t">Pilot's console throttle command </field>
<field name="dla" type="uint16_t">Pilot's console left aileron command </field>
<field name="dra" type="uint16_t">Pilot's console right aileron command </field>
<field name="dr" type="uint16_t">Pilot's console rudder command </field>
<field name="de" type="uint16_t">Pilot's console elevator command </field>
</message>
</message>
<message name="PWM_COMMANDS" id="195">
<message name="PWM_COMMANDS" id="175">
PWM Commands from the AP to the control surfaces.
<field name="target" type="uint8_t">The system reporting the diagnostic</field>
<field name="dt_c" type="uint16_t">AutoPilot's throttle command </field>
<field name="dla_c" type="uint16_t">AutoPilot's left aileron command </field>
<field name="dra_c" type="uint16_t">AutoPilot's right aileron command </field>
@ -63,5 +92,95 @@
<field name="aux1" type="uint16_t">AutoPilot's aux1 command </field>
<field name="aux2" type="uint16_t">AutoPilot's aux2 command </field>
</message>
<message name="SLUGS_NAVIGATION" id="176">
Data used in the navigation algorithm.
<field name="u_m" type="float">Measured Airspeed prior to the Nav Filter</field>
<field name="phi_c" type="float">Commanded Roll</field>
<field name="theta_c" type="float">Commanded Pitch</field>
<field name="psiDot_c" type="float">Commanded Turn rate</field>
<field name="ay_body" type="float">Y component of the body acceleration</field>
<field name="totalDist" type="float">Total Distance to Run on this leg of Navigation</field>
<field name="dist2Go" type="float">Remaining distance to Run on this leg of Navigation</field>
<field name="fromWP" type="uint8_t">Origin WP</field>
<field name="toWP" type="uint8_t">Destination WP</field>
</message>
<message name="DATA_LOG" id="177">
Configurable data log probes to be used inside Simulink
<field name="fl_1" type="float">Log value 1 </field>
<field name="fl_2" type="float">Log value 2 </field>
<field name="fl_3" type="float">Log value 3 </field>
<field name="fl_4" type="float">Log value 4 </field>
<field name="fl_5" type="float">Log value 5 </field>
<field name="fl_6" type="float">Log value 6 </field>
</message>
<message name="FILTERED_DATA" id="178">
Measured value from the IMU in units after sensor calibration and temperature compensation. Note that this IS NOT the output of the attitude filter, for that see messages 30 and 33.
<field name="aX" type="float">Accelerometer X value (m/s^2) </field>
<field name="aY" type="float">Accelerometer Y value (m/s^2)</field>
<field name="aZ" type="float">Accelerometer Z value (m/s^2)</field>
<field name="gX" type="float">Gyro X value (rad/s) </field>
<field name="gY" type="float">Gyro Y value (rad/s)</field>
<field name="gZ" type="float">Gyro Z value (rad/s)</field>
<field name="mX" type="float">Magnetometer X (normalized to 1) </field>
<field name="mY" type="float">Magnetometer Y (normalized to 1) </field>
<field name="mZ" type="float">Magnetometer Z (normalized to 1) </field>
</message>
<message name="GPS_DATE_TIME" id="179">
Pilot console PWM messges.
<field name="year" type="uint8_t">Year reported by Gps </field>
<field name="month" type="uint8_t">Month reported by Gps </field>
<field name="day" type="uint8_t">Day reported by Gps </field>
<field name="hour" type="uint8_t">Hour reported by Gps </field>
<field name="min" type="uint8_t">Min reported by Gps </field>
<field name="sec" type="uint8_t">Sec reported by Gps </field>
<field name="visSat" type="uint8_t">Visible sattelites reported by Gps </field>
</message>
<message name="MID_LVL_CMDS" id="180">
Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX.
<field name="target" type="uint8_t">The system setting the commands</field>
<field name="hCommand" type="float">Commanded Airspeed</field>
<field name="uCommand" type="float">Log value 2 </field>
<field name="rCommand" type="float">Log value 3 </field>
</message>
<message name="CTRL_SRFC_PT" id="181">
This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows:
Position Bit Code
=================================
15-8 Reserved
7 dt_pass 128
6 dla_pass 64
5 dra_pass 32
4 dr_pass 16
3 dle_pass 8
2 dre_pass 4
1 dlf_pass 2
0 drf_pass 1
Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface.
<field name="target" type="uint8_t">The system setting the commands</field>
<field name="bitfieldPt" type="uint16_t">Bitfield containing the PT configuration</field>
</message>
<message name="PID" id="182">
Configure a PID loop.
<field name="target" type="uint8_t">The system setting the PID values</field>
<field name="pVal" type="float">Proportional gain</field>
<field name="iVal" type="float">Integral gain</field>
<field name="dVal" type="float">Derivative gain</field>
<field name="idx" type="uint8_t">PID loop index</field>
</message>
<message name="SLUGS_ACTION" id="183">
Action messages focused on the SLUGS AP.
<field name="target" type="uint8_t">The system reporting the action</field>
<field name="actionId" type="uint8_t">Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names</field>
<field name="actionVal" type="uint16_t">Value associated with the action</field>
</message>
</messages>
</mavlink>

View File

@ -0,0 +1,152 @@
<?xml version="1.0"?>
<mavlink>
<include>common_slugs.xml</include>
<messages>
<message name="CPU_LOAD" id="170">
Sensor and DSC control loads.
<field name="sensLoad" type="uint8_t">Sensor DSC Load</field>
<field name="ctrlLoad" type="uint8_t">Control DSC Load</field>
<field name="batVolt" type="uint16_t">Battery Voltage in millivolts</field>
</message>
<message name="AIR_DATA" id="171">
Air data for altitude and airspeed computation.
<field name="dynamicPressure" type="float">Dynamic pressure (Pa)</field>
<field name="staticPressure" type="float">Static pressure (Pa)</field>
<field name="temperature" type="uint16_t">Board temperature</field>
</message>
<message name="SENSOR_BIAS" id="172">
Accelerometer and gyro biases.
<field name="axBias" type="float">Accelerometer X bias (m/s)</field>
<field name="ayBias" type="float">Accelerometer Y bias (m/s)</field>
<field name="azBias" type="float">Accelerometer Z bias (m/s)</field>
<field name="gxBias" type="float">Gyro X bias (rad/s)</field>
<field name="gyBias" type="float">Gyro Y bias (rad/s)</field>
<field name="gzBias" type="float">Gyro Z bias (rad/s)</field>
</message>
<message name="DIAGNOSTIC" id="173">
Configurable diagnostic messages.
<field name="diagFl1" type="float">Diagnostic float 1</field>
<field name="diagFl2" type="float">Diagnostic float 2</field>
<field name="diagFl3" type="float">Diagnostic float 3</field>
<field name="diagSh1" type="int16_t">Diagnostic short 1</field>
<field name="diagSh2" type="int16_t">Diagnostic short 2</field>
<field name="diagSh3" type="int16_t">Diagnostic short 3</field>
</message>
<message name="PILOT_CONSOLE" id="174">
Pilot console PWM messges.
<field name="dt" type="uint16_t">Pilot's console throttle command </field>
<field name="dla" type="uint16_t">Pilot's console left aileron command </field>
<field name="dra" type="uint16_t">Pilot's console right aileron command </field>
<field name="dr" type="uint16_t">Pilot's console rudder command </field>
<field name="de" type="uint16_t">Pilot's console elevator command </field>
</message>
<message name="PWM_COMMANDS" id="175">
PWM Commands from the AP to the control surfaces.
<field name="dt_c" type="uint16_t">AutoPilot's throttle command </field>
<field name="dla_c" type="uint16_t">AutoPilot's left aileron command </field>
<field name="dra_c" type="uint16_t">AutoPilot's right aileron command </field>
<field name="dr_c" type="uint16_t">AutoPilot's rudder command </field>
<field name="dle_c" type="uint16_t">AutoPilot's left elevator command </field>
<field name="dre_c" type="uint16_t">AutoPilot's right elevator command </field>
<field name="dlf_c" type="uint16_t">AutoPilot's left flap command </field>
<field name="drf_c" type="uint16_t">AutoPilot's right flap command </field>
<field name="aux1" type="uint16_t">AutoPilot's aux1 command </field>
<field name="aux2" type="uint16_t">AutoPilot's aux2 command </field>
</message>
<message name="SLUGS_NAVIGATION" id="176">
Data used in the navigation algorithm.
<field name="u_m" type="float">Measured Airspeed prior to the Nav Filter</field>
<field name="phi_c" type="float">Commanded Roll</field>
<field name="theta_c" type="float">Commanded Pitch</field>
<field name="psiDot_c" type="float">Commanded Turn rate</field>
<field name="ay_body" type="float">Y component of the body acceleration</field>
<field name="totalDist" type="float">Total Distance to Run on this leg of Navigation</field>
<field name="dist2Go" type="float">Remaining distance to Run on this leg of Navigation</field>
<field name="fromWP" type="uint8_t">Origin WP</field>
<field name="toWP" type="uint8_t">Destination WP</field>
</message>
<message name="DATA_LOG" id="177">
Configurable data log probes to be used inside Simulink
<field name="fl_1" type="float">Log value 1 </field>
<field name="fl_2" type="float">Log value 2 </field>
<field name="fl_3" type="float">Log value 3 </field>
<field name="fl_4" type="float">Log value 4 </field>
<field name="fl_5" type="float">Log value 5 </field>
<field name="fl_6" type="float">Log value 6 </field>
</message>
<message name="FILTERED_DATA" id="178">
Measured value from the IMU in units after sensor calibration and temperature compensation. Note that this IS NOT the output of the attitude filter, for that see messages 30 and 33.
<field name="aX" type="float">Accelerometer X value (m/s^2) </field>
<field name="aY" type="float">Accelerometer Y value (m/s^2)</field>
<field name="aZ" type="float">Accelerometer Z value (m/s^2)</field>
<field name="gX" type="float">Gyro X value (rad/s) </field>
<field name="gY" type="float">Gyro Y value (rad/s)</field>
<field name="gZ" type="float">Gyro Z value (rad/s)</field>
<field name="mX" type="float">Magnetometer X (normalized to 1) </field>
<field name="mY" type="float">Magnetometer Y (normalized to 1) </field>
<field name="mZ" type="float">Magnetometer Z (normalized to 1) </field>
</message>
<message name="GPS_DATE_TIME" id="179">
Pilot console PWM messges.
<field name="year" type="uint8_t">Year reported by Gps </field>
<field name="month" type="uint8_t">Month reported by Gps </field>
<field name="day" type="uint8_t">Day reported by Gps </field>
<field name="hour" type="uint8_t">Hour reported by Gps </field>
<field name="min" type="uint8_t">Min reported by Gps </field>
<field name="sec" type="uint8_t">Sec reported by Gps </field>
<field name="visSat" type="uint8_t">Visible sattelites reported by Gps </field>
</message>
<message name="MID_LVL_CMDS" id="180">
Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX.
<field name="target" type="uint8_t">The system setting the commands</field>
<field name="hCommand" type="float">Commanded Airspeed</field>
<field name="uCommand" type="float">Log value 2 </field>
<field name="rCommand" type="float">Log value 3 </field>
</message>
<message name="CTRL_SRFC_PT" id="181">
This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows:
Position Bit Code
=================================
15-8 Reserved
7 dt_pass 128
6 dla_pass 64
5 dra_pass 32
4 dr_pass 16
3 dle_pass 8
2 dre_pass 4
1 dlf_pass 2
0 drf_pass 1
Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface.
<field name="target" type="uint8_t">The system setting the commands</field>
<field name="bitfieldPt" type="uint16_t">Bitfield containing the PT configuration</field>
</message>
<message name="PID" id="182">
Configure a PID loop.
<field name="target" type="uint8_t">The system setting the PID values</field>
<field name="pVal" type="float">Proportional gain</field>
<field name="iVal" type="float">Integral gain</field>
<field name="dVal" type="float">Derivative gain</field>
<field name="idx" type="uint8_t">PID loop index</field>
</message>
<message name="SLUGS_ACTION" id="183">
Action messages focused on the SLUGS AP.
<field name="target" type="uint8_t">The system reporting the action</field>
<field name="actionId" type="uint8_t">Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names</field>
<field name="actionVal" type="uint16_t">Value associated with the action</field>
</message>
</messages>
</mavlink>