Commit f3cd7d6c authored by LM's avatar LM

Merge branch 'dev_senseSoarMavlinkv10' of https://github.com/oberion/qgroundcontrol into v10release

parents 94f9e534 d4616625
......@@ -34,6 +34,10 @@ user_config.pri
*.ncb
*.vcproj
*.vcxproj*
*.sdf
*.ipch
*.pdb
*.sln
*.sln
*.vcproj
......
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html>
<head>
......@@ -415,9 +415,9 @@ function createAircraft(id, type, color)
planeModel.setLocation(planeLoc);
planeLink = ge.createLink('');
planeOrient = ge.createOrientation('');
planeModel.setOrientation(planeOrient);
planeModel.setOrientation(planeOrient);
planeLink.setHref('http://qgroundcontrol.org/_media/users/models/ascent-park-glider.dae');
planeLink.setHref('http://www.asl.ethz.ch/people/rudink/senseSoarDummy.dae');
planeModel.setLink(planeLink);
planeModel.setAltitudeMode (ge.ALTITUDE_ABSOLUTE);
......@@ -584,10 +584,10 @@ function setAircraftPositionAttitude(id, lat, lon, alt, roll, pitch, yaw)
//currFollowHeading = ((yaw/M_PI)+1.0)*360.0;
// FIXME Currently invalid conversion from right-handed z-down to z-up frame
planeOrient.setRoll(((roll/M_PI))*180.0+180.0);
planeOrient.setTilt(((pitch/M_PI))*180.0+180.0);
planeOrient.setHeading(((yaw/M_PI))*180.0-90.0);
planeOrient.setRoll(+((pitch / M_PI)) * 180.0);
planeOrient.setTilt(-((roll / M_PI)) * 180.0);
planeOrient.setHeading(((yaw / M_PI)) * 180.0 - 90.0);
planeModel.setOrientation(planeOrient);
currFollowHeading = ((yaw/M_PI))*180.0;
......
......@@ -19,6 +19,8 @@
# Qt configuration
CONFIG += qt \
thread
QT += network \
opengl \
svg \
......@@ -29,17 +31,25 @@ QT += network \
TEMPLATE = app
TARGET = qgroundcontrol
BASEDIR = $$IN_PWD
TARGETDIR = $$OUT_PWD
BUILDDIR = $$TARGETDIR/build
BASEDIR = $${IN_PWD}
TARGETDIR = $${OUT_PWD}
BUILDDIR = $${TARGETDIR}/build
LANGUAGE = C++
#OBJECTS_DIR = $$BUILDDIR/obj
#MOC_DIR = $$BUILDDIR/moc
#UI_HEADERS_DIR = $$BUILDDIR/ui
#RCC_DIR = $$BUILDDIR/rcc
OBJECTS_DIR = $${BUILDDIR}/obj
MOC_DIR = $${BUILDDIR}/moc
UI_DIR = $${BUILDDIR}/ui
RCC_DIR = $${BUILDDIR}/rcc
MAVLINK_CONF = ""
DEFINES += MAVLINK_NO_DATA
QMAKE_INCDIR_QT = $$(QTDIR)/include
QMAKE_LIBDIR_QT = $$(QTDIR)/lib
QMAKE_UIC = "$$(QTDIR)/bin/uic.exe"
QMAKE_MOC = "$$(QTDIR)/bin/moc.exe"
QMAKE_RCC = "$$(QTDIR)/bin/rcc.exe"
QMAKE_QMAKE = "$$(QTDIR)/bin/qmake.exe"
#################################################################
# EXTERNAL LIBRARY CONFIGURATION
......@@ -119,6 +129,16 @@ contains(MAVLINK_CONF, ardupilotmega) {
INCLUDEPATH += $$BASEDIR/thirdParty/mavlink/include/ardupilotmega
DEFINES += QGC_USE_ARDUPILOTMEGA_MESSAGES
}
contains(MAVLINK_CONF, senseSoar) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
INCLUDEPATH -= $$BASEDIR/thirdParty/mavlink/include/common
# SENSESOAR SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/SenseSoar
INCLUDEPATH += $$BASEDIR/thirdParty/mavlink/include/SenseSoar
DEFINES += QGC_USE_SENSESOAR_MESSAGES
}
# Include general settings for QGroundControl
......@@ -272,6 +292,7 @@ HEADERS += src/MG.h \
src/uas/SlugsMAV.h \
src/uas/PxQuadMAV.h \
src/uas/ArduPilotMegaMAV.h \
src/uas/senseSoarMAV.h \
src/ui/watchdog/WatchdogControl.h \
src/ui/watchdog/WatchdogProcessView.h \
src/ui/watchdog/WatchdogView.h \
......@@ -402,6 +423,7 @@ SOURCES += src/main.cc \
src/uas/SlugsMAV.cc \
src/uas/PxQuadMAV.cc \
src/uas/ArduPilotMegaMAV.cc \
src/uas/senseSoarMAV.cpp \
src/ui/watchdog/WatchdogControl.cc \
src/ui/watchdog/WatchdogProcessView.cc \
src/ui/watchdog/WatchdogView.cc \
......@@ -516,19 +538,21 @@ win32:exists(src/lib/opalrt/OpalApi.h):exists(C:/OPAL-RT/RT-LAB7.2.4/Common/bin)
TRANSLATIONS += es-MX.ts \
en-US.ts
## xbee support
## libxbee only supported by linux and windows systems
##win32-msvc2008|win32-msvc2010|linux{
# HEADERS += src/comm/XbeeLinkInterface.h \
# src/comm/XbeeLink.h \
# src/ui/XbeeConfigurationWindow.h \
# src/comm/CallConv.h
# SOURCES += src/comm/XbeeLink.cpp \
# src/ui/XbeeConfigurationWindow.cpp
# DEFINES += XBEELINK
# INCLUDEPATH += thirdParty/libxbee
## TO DO: build library when it does not exists already
# LIBS += -LthirdParty/libxbee/lib \
# -llibxbee
#
#}
# xbee support
# libxbee only supported by linux and windows systems
win32-msvc2008|win32-msvc2010|linux{
HEADERS += src/comm/XbeeLinkInterface.h \
src/comm/XbeeLink.h \
src/comm/HexSpinBox.h \
src/ui/XbeeConfigurationWindow.h \
src/comm/CallConv.h
SOURCES += src/comm/XbeeLink.cpp \
src/comm/HexSpinBox.cpp \
src/ui/XbeeConfigurationWindow.cpp
DEFINES += XBEELINK
INCLUDEPATH += thirdParty/libxbee
# TO DO: build library when it does not exists already
LIBS += -LthirdParty/libxbee/lib \
-llibxbee
}
......@@ -143,6 +143,7 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv)
// to make sure that all components are initialized when the
// first messages arrive
UDPLink* udpLink = new UDPLink(QHostAddress::Any, 14550);
MainWindow::instance()->addLink(udpLink);
// Listen on Multicast-Address 239.255.77.77, Port 14550
//QHostAddress * multicast_udp = new QHostAddress("239.255.77.77");
//UDPLink* udpLink = new UDPLink(*multicast_udp, 14550);
......
......@@ -237,7 +237,7 @@ signals:
protected:
static int getNextLinkId() {
static int nextId = 0;
static int nextId = 1;
return nextId++;
}
......
......@@ -211,7 +211,7 @@ using namespace TNX;
SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl, bool parity,
int dataBits, int stopBits) :
port(NULL),
port(NULL), m_stopp(false),
ports(new QVector<QString>())
{
// Setup settings
......@@ -340,7 +340,7 @@ QVector<QString>* SerialLink::getCurrentPorts()
QextPortInfo portInfo = ports.at(i);
QString portString = QString(portInfo.portName.toLocal8Bit().constData()) + " - " + QString(ports.at(i).friendName.toLocal8Bit().constData()).split("(").first();
// Prepend newly found port to the list
ports.append(portString);
this->ports->append(portString);
}
//printf("port name: %s\n", ports.at(i).portName.toLocal8Bit().constData());
......@@ -349,7 +349,7 @@ QVector<QString>* SerialLink::getCurrentPorts()
//printf("enumerator name: %s\n", ports.at(i).enumName.toLocal8Bit().constData());
//printf("===================================\n\n");
#endif
return ports;
return this->ports;
}
void SerialLink::loadSettings()
......@@ -394,6 +394,14 @@ void SerialLink::run()
// Qt way to make clear what a while(1) loop does
forever
{
{
QMutexLocker locker(&this->m_stoppMutex);
if(this->m_stopp)
{
this->m_stopp = false;
break;
}
}
// Check if new bytes have arrived, if yes, emit the notification signal
checkForBytes();
/* Serial data isn't arriving that fast normally, this saves the thread
......@@ -401,6 +409,13 @@ void SerialLink::run()
*/
MG::SLEEP::msleep(SerialLink::poll_interval);
}
if (port) {
port->flushInBuffer();
port->flushOutBuffer();
port->close();
delete port;
port = NULL;
}
}
......@@ -512,25 +527,34 @@ qint64 SerialLink::bytesAvailable()
**/
bool SerialLink::disconnect()
{
if (port) {
if(this->isRunning())
{
{
QMutexLocker locker(&this->m_stoppMutex);
this->m_stopp = true;
}
this->wait();
// if (port) {
//#if !defined _WIN32 || !defined _WIN64
/* Block the thread until it returns from run() */
//#endif
port->flushInBuffer();
port->flushOutBuffer();
port->close();
delete port;
port = NULL;
if(this->isRunning()) this->terminate(); //stop running the thread, restart it upon connect
// port->flushInBuffer();
// port->flushOutBuffer();
// port->close();
// delete port;
// port = NULL;
// if(this->isRunning()) this->terminate(); //stop running the thread, restart it upon connect
bool closed = true;
//port->isOpen();
emit disconnected();
emit connected(false);
return closed;
} else {
}
else {
// No port, so we're disconnected
return true;
}
......@@ -545,6 +569,10 @@ bool SerialLink::disconnect()
bool SerialLink::connect()
{
if (this->isRunning()) this->disconnect();
{
QMutexLocker locker(&this->m_stoppMutex);
this->m_stopp = false;
}
this->start(LowPriority);
return true;
}
......
......@@ -168,6 +168,10 @@ protected:
QMutex dataMutex;
QVector<QString>* ports;
private:
volatile bool m_stopp;
QMutex m_stoppMutex;
void setName(QString name);
bool hardwareConnect();
......
......@@ -40,19 +40,22 @@ This file is part of the QGROUNDCONTROL project
//#include <netinet/in.h>
UDPLink::UDPLink(QHostAddress host, quint16 port)
: socket(NULL)
{
this->host = host;
this->port = port;
this->connectState = false;
// Set unique ID and add link to the list of links
this->id = getNextLinkId();
this->name = tr("UDP Link (port:%1)").arg(14550);
LinkManager::instance()->add(this);
this->name = tr("UDP Link (port:%1)").arg(this->port);
emit nameChanged(this->name);
// LinkManager::instance()->add(this);
}
UDPLink::~UDPLink()
{
disconnect();
this->deleteLater();
}
/**
......@@ -61,23 +64,39 @@ UDPLink::~UDPLink()
**/
void UDPLink::run()
{
// forever
// {
// QGC::SLEEP::msleep(5000);
// }
exec();
exec();
}
void UDPLink::setAddress(QString address)
void UDPLink::setAddress(QHostAddress host)
{
Q_UNUSED(address);
bool reconnect(false);
if(this->isConnected())
{
disconnect();
reconnect = true;
}
this->host = host;
if(reconnect)
{
connect();
}
}
void UDPLink::setPort(int port)
{
bool reconnect(false);
if(this->isConnected())
{
disconnect();
reconnect = true;
}
this->port = port;
disconnect();
connect();
this->name = tr("UDP Link (port:%1)").arg(this->port);
emit nameChanged(this->name);
if(reconnect)
{
connect();
}
}
/**
......@@ -104,9 +123,11 @@ void UDPLink::addHost(const QString& host)
}
}
hosts.append(address);
this->setAddress(address);
//qDebug() << "Address:" << address.toString();
// Set port according to user input
ports.append(host.split(":").last().toInt());
this->setPort(host.split(":").last().toInt());
}
}
else
......@@ -245,8 +266,14 @@ qint64 UDPLink::bytesAvailable()
**/
bool UDPLink::disconnect()
{
delete socket;
socket = NULL;
this->quit();
this->wait();
if(socket)
{
delete socket;
socket = NULL;
}
connectState = false;
......@@ -262,7 +289,19 @@ bool UDPLink::disconnect()
**/
bool UDPLink::connect()
{
socket = new QUdpSocket(this);
if(this->isRunning())
{
this->quit();
this->wait();
}
this->hardwareConnect();
start(HighPriority);
return true;
}
bool UDPLink::hardwareConnect(void)
{
socket = new QUdpSocket();
//Check if we are using a multicast-address
// bool multicast = false;
......@@ -309,11 +348,10 @@ bool UDPLink::connect()
emit connected();
connectionStartTime = QGC::groundTimeUsecs()/1000;
}
start(HighPriority);
return connectState;
return connectState;
}
/**
* @brief Check if connection is active.
*
......
......@@ -87,7 +87,7 @@ public:
int getId();
public slots:
void setAddress(QString address);
void setAddress(QHostAddress host);
void setPort(int port);
/** @brief Add a new host to broadcast messages to */
void addHost(const QString& host);
......@@ -128,8 +128,11 @@ protected:
void setName(QString name);
private:
bool hardwareConnect(void);
signals:
// Signals are defined by LinkInterface
//Signals are defined by LinkInterface
};
......
......@@ -7,7 +7,8 @@
#include "XbeeLink.h"
XbeeLink::XbeeLink(QString portName, int baudRate) :
m_xbeeCon(NULL), m_portName(NULL), m_portNameLength(0), m_baudRate(baudRate), m_connected(false), m_id(-1)
m_xbeeCon(NULL), m_portName(NULL), m_portNameLength(0), m_baudRate(baudRate), m_connected(false), m_id(-1),
m_addrHigh(0), m_addrLow(0)
{
/* setup the xbee */
......@@ -160,6 +161,7 @@ qint64 XbeeLink::getBitsReceived()
bool XbeeLink::hardwareConnect()
{
emit tryConnectBegin(true);
if(this->isConnected())
{
this->disconnect();
......@@ -172,9 +174,11 @@ bool XbeeLink::hardwareConnect()
{
/* oh no... it failed */
qDebug() <<"xbee_setup() failed...\n";
emit tryConnectEnd(true);
return false;
}
this->m_xbeeCon = xbee_newcon('A',xbee2_data,0x13A200,0x403D0935);
emit tryConnectEnd(true);
this->m_connected = true;
emit connected();
emit connected(true);
......@@ -194,7 +198,7 @@ bool XbeeLink::disconnect()
if(this->m_xbeeCon)
{
xbee_endcon(this->m_xbeeCon);
xbee_end();
this->m_xbeeCon = NULL;
}
this->m_connected = false;
......@@ -256,6 +260,18 @@ void XbeeLink::run()
}
}
bool XbeeLink::setRemoteAddressHigh(quint32 high)
{
this->m_addrHigh = high;
return true;
}
bool XbeeLink::setRemoteAddressLow(quint32 low)
{
this->m_addrLow = low;
return true;
}
/*
void CALLTYPE XbeeLink::portCallback(xbee_con *xbeeCon, xbee_pkt *XbeePkt)
{
......
......@@ -26,6 +26,8 @@ public: // virtual functions from XbeeLinkInterface
public slots: // virtual functions from XbeeLinkInterface
bool setPortName(QString portName);
bool setBaudRate(int rate);
bool setRemoteAddressHigh(quint32 high);
bool setRemoteAddressLow(quint32 low);
public: // virtual functions from LinkInterface
int getId();
......@@ -60,6 +62,8 @@ protected:
int m_baudRate;
bool m_connected;
QString m_name;
quint32 m_addrHigh;
quint32 m_addrLow;
private:
bool hardwareConnect();
......
......@@ -16,6 +16,12 @@ public:
public slots:
virtual bool setPortName(QString portName) = 0;
virtual bool setBaudRate(int rate) = 0;
virtual bool setRemoteAddressHigh(quint32 high) = 0;
virtual bool setRemoteAddressLow(quint32 low) = 0;
signals:
void tryConnectBegin(bool toTrue);
void tryConnectEnd(bool toTrue);
};
#endif // XBEELINKINTERFACE_H_
......@@ -72,6 +72,16 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
uas = mav;
}
break;
#ifdef QGC_USE_SENSESOAR_MESSAGES
case MAV_AUTOPILOT_SENSESOAR:
{
senseSoarMAV* mav = new senseSoarMAV(mavlink,sysid);
mav->setSystemType((int)heartbeat->type);
connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
uas = mav;
break;
}
#endif
default:
{
UAS* mav = new UAS(mavlink, sysid);
......
......@@ -12,6 +12,7 @@
#include "UAS.h"
#include "SlugsMAV.h"
#include "PxQuadMAV.h"
#include "senseSoarMAV.h"
#include "ArduPilotMegaMAV.h"
class QGCMAVLinkUASFactory : public QObject
......
......@@ -521,16 +521,16 @@ public slots:
signals:
/** @brief The main/battery voltage has changed/was updated */
void voltageChanged(int uasId, double voltage);
//void voltageChanged(int uasId, double voltage); // Defined in UASInterface already
/** @brief An actuator value has changed */
void actuatorChanged(UASInterface*, int actId, double value);
//void actuatorChanged(UASInterface*, int actId, double value); // Defined in UASInterface already
/** @brief An actuator value has changed */
void actuatorChanged(UASInterface* uas, QString actuatorName, double min, double max, double value);
void motorChanged(UASInterface* uas, QString motorName, double min, double max, double value);
/** @brief The system load (MCU/CPU usage) changed */
void loadChanged(UASInterface* uas, double load);
/** @brief Propagate a heartbeat received from the system */
void heartbeat(UASInterface* uas);
//void heartbeat(UASInterface* uas); // Defined in UASInterface already
void imageStarted(quint64 timestamp);
/** @brief A new camera image has arrived */
void imageReady(UASInterface* uas);
......
#include "senseSoarMAV.h"
#include <qmath.h>
senseSoarMAV::senseSoarMAV(MAVLinkProtocol* mavlink, int id)
: UAS(mavlink, id), senseSoarState(0)
{
}
senseSoarMAV::~senseSoarMAV(void)
{
}
void senseSoarMAV::receiveMessage(LinkInterface *link, mavlink_message_t message)
{
#ifdef MAVLINK_ENABLED_SENSESOAR
if (message.sysid == uasId) // make sure the message is for the right UAV
{
if (!link) return;
switch (message.msgid)
{
case MAVLINK_MSG_ID_CMD_AIRSPEED_ACK: // TO DO: check for acknowledgement after sended commands
{
mavlink_cmd_airspeed_ack_t airSpeedMsg;
mavlink_msg_cmd_airspeed_ack_decode(&message,&airSpeedMsg);
break;
}
/*case MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG: only sent to UAV
{
break;
}*/
case MAVLINK_MSG_ID_FILT_ROT_VEL: // rotational velocities
{
mavlink_filt_rot_vel_t rotVelMsg;
mavlink_msg_filt_rot_vel_decode(&message,&rotVelMsg);
quint64 time = getUnixTime();
for(unsigned char i=0;i<3;i++)
{
this->m_rotVel[i]=rotVelMsg.rotVel[i];
}
emit valueChanged(uasId, "rollspeed", "rad/s", this->m_rotVel[0], time);
emit valueChanged(uasId, "pitchspeed", "rad/s", this->m_rotVel[1], time);
emit valueChanged(uasId, "yawspeed", "rad/s", this->m_rotVel[2], time);
emit attitudeSpeedChanged(uasId, this->m_rotVel[0], this->m_rotVel[1], this->m_rotVel[2], time);
break;
}
case MAVLINK_MSG_ID_LLC_OUT: // low level controller output
{
mavlink_llc_out_t llcMsg;
mavlink_msg_llc_out_decode(&message,&llcMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "Servo. 1", "rad", llcMsg.servoOut[0], time);
emit valueChanged(uasId, "Servo. 2", "rad", llcMsg.servoOut[1], time);
emit valueChanged(uasId, "Servo. 3", "rad", llcMsg.servoOut[2], time);
emit valueChanged(uasId, "Servo. 4", "rad", llcMsg.servoOut[3], time);
emit valueChanged(uasId, "Motor. 1", "raw", llcMsg.MotorOut[0] , time);
emit valueChanged(uasId, "Motor. 2", "raw", llcMsg.MotorOut[1], time);
break;
}
case MAVLINK_MSG_ID_OBS_AIR_TEMP:
{
mavlink_obs_air_temp_t airTMsg;
mavlink_msg_obs_air_temp_decode(&message,&airTMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "Air Temp", "", airTMsg.airT, time);
break;
}
case MAVLINK_MSG_ID_OBS_AIR_VELOCITY:
{
mavlink_obs_air_velocity_t airVMsg;
mavlink_msg_obs_air_velocity_decode(&message,&airVMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "AirVel. mag", "m/s", airVMsg.magnitude, time);
emit valueChanged(uasId, "AirVel. AoA", "rad", airVMsg.aoa, time);
emit valueChanged(uasId, "AirVel. Slip", "rad", airVMsg.slip, time);
break;
}
case MAVLINK_MSG_ID_OBS_ATTITUDE:
{
mavlink_obs_attitude_t quatMsg;
mavlink_msg_obs_attitude_decode(&message,&quatMsg);
quint64 time = getUnixTime();
this->quat2euler(quatMsg.quat,this->roll,this->pitch,this->yaw);
emit valueChanged(uasId, "roll", "rad", roll, time);
emit valueChanged(uasId, "pitch", "rad", pitch, time);
emit valueChanged(uasId, "yaw", "rad", yaw, time);
emit valueChanged(uasId, "roll deg", "deg", (roll/M_PI)*180.0, time);
emit valueChanged(uasId, "pitch deg", "deg", (pitch/M_PI)*180.0, time);
emit valueChanged(uasId, "heading deg", "deg", (yaw/M_PI)*180.0, time);
emit attitudeChanged(this, roll, pitch, yaw, time);
break;
}
case MAVLINK_MSG_ID_OBS_BIAS:
{
mavlink_obs_bias_t biasMsg;
mavlink_msg_obs_bias_decode(&message, &biasMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "acc. biasX", "m/s^2", biasMsg.accBias[0], time);
emit valueChanged(uasId, "acc. biasY", "m/s^2", biasMsg.accBias[1], time);
emit valueChanged(uasId, "acc. biasZ", "m/s^2", biasMsg.accBias[2], time);
emit valueChanged(uasId, "gyro. biasX", "rad/s", biasMsg.gyroBias[0], time);
emit valueChanged(uasId, "gyro. biasY", "rad/s", biasMsg.gyroBias[1], time);
emit valueChanged(uasId, "gyro. biasZ", "rad/s", biasMsg.gyroBias[2], time);
break;
}
case MAVLINK_MSG_ID_OBS_POSITION:
{
mavlink_obs_position_t posMsg;
mavlink_msg_obs_position_decode(&message, &posMsg);
quint64 time = getUnixTime();
this->longitude = posMsg.lon/(double)1E7;
this->latitude = posMsg.lat/(double)1E7;
this->altitude = posMsg.alt/1000.0;
emit valueChanged(uasId, "latitude", "deg", this->latitude, time);
emit valueChanged(uasId, "longitude", "deg", this->longitude, time);
emit valueChanged(uasId, "altitude", "m", this->altitude, time);
emit globalPositionChanged(this, this->latitude, this->longitude, this->altitude, time);
break;
}
case MAVLINK_MSG_ID_OBS_QFF:
{
mavlink_obs_qff_t qffMsg;
mavlink_msg_obs_qff_decode(&message,&qffMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "QFF", "Pa", qffMsg.qff, time);
break;
}
case MAVLINK_MSG_ID_OBS_VELOCITY:
{
mavlink_obs_velocity_t velMsg;
mavlink_msg_obs_velocity_decode(&message, &velMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "x speed", "m/s", velMsg.vel[0], time);
emit valueChanged(uasId, "y speed", "m/s", velMsg.vel[1], time);
emit valueChanged(uasId, "z speed", "m/s", velMsg.vel[2], time);
emit speedChanged(this, velMsg.vel[0], velMsg.vel[1], velMsg.vel[2], time);
break;
}
case MAVLINK_MSG_ID_OBS_WIND:
{
mavlink_obs_wind_t windMsg;
mavlink_msg_obs_wind_decode(&message, &windMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "Wind speed x", "m/s", windMsg.wind[0], time);
emit valueChanged(uasId, "Wind speed y", "m/s", windMsg.wind[1], time);
emit valueChanged(uasId, "Wind speed z", "m/s", windMsg.wind[2], time);
break;
}
case MAVLINK_MSG_ID_PM_ELEC:
{
mavlink_pm_elec_t pmMsg;
mavlink_msg_pm_elec_decode(&message, &pmMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "Battery status", "%", pmMsg.BatStat, time);
emit valueChanged(uasId, "Power consuming", "W", pmMsg.PwCons, time);
emit valueChanged(uasId, "Power generating sys1", "W", pmMsg.PwGen[0], time);
emit valueChanged(uasId, "Power generating sys2", "W", pmMsg.PwGen[1], time);
emit valueChanged(uasId, "Power generating sys3", "W", pmMsg.PwGen[2], time);
break;
}
case MAVLINK_MSG_ID_SYS_STAT:
{
#define STATE_WAKING_UP 0x0 // TO DO: not important here, only for the visualisation needed
#define STATE_ON_GROUND 0x1
#define STATE_MANUAL_FLIGHT 0x2
#define STATE_AUTONOMOUS_FLIGHT 0x3
#define STATE_AUTONOMOUS_LAUNCH 0x4
mavlink_sys_stat_t statMsg;
mavlink_msg_sys_stat_decode(&message,&statMsg);
quint64 time = getUnixTime();
// check actuator states
emit valueChanged(uasId, "Motor1 status", "on/off", (statMsg.act & 0x01), time);
emit valueChanged(uasId, "Motor2 status", "on/off", (statMsg.act & 0x02)>>1, time);
emit valueChanged(uasId, "Servo1 status", "on/off", (statMsg.act & 0x04)>>2, time);
emit valueChanged(uasId, "Servo2 status", "on/off", (statMsg.act & 0x08)>>3, time);
emit valueChanged(uasId, "Servo3 status", "on/off", (statMsg.act & 0x10)>>4, time);
emit valueChanged(uasId, "Servo4 status", "on/off", (statMsg.act & 0x20)>>5, time);
// check the current state of the sensesoar
this->senseSoarState = statMsg.mod;
emit valueChanged(uasId,"senseSoar status","-",this->senseSoarState,time);
// check the gps fixes
emit valueChanged(uasId,"Lat Long fix","true/false", (statMsg.gps & 0x01), time);
emit valueChanged(uasId,"Altitude fix","true/false", (statMsg.gps & 0x02), time);
emit valueChanged(uasId,"GPS horizontal accuracy","m",((statMsg.gps & 0x1C)>>2), time);
emit valueChanged(uasId,"GPS vertiacl accuracy","m",((statMsg.gps & 0xE0)>>5),time);
// Xbee RSSI
emit valueChanged(uasId, "Xbee strength", "%", statMsg.commRssi, time);
//emit valueChanged(uasId, "Xbee strength", "%", statMsg.gps, time); // TO DO: define gps bits
break;
}
default:
{
// Let UAS handle the default message set
UAS::receiveMessage(link, message);
break;
}
}
}
#else
// Let UAS handle the default message set
UAS::receiveMessage(link, message);
Q_UNUSED(link);
Q_UNUSED(message);
#endif // MAVLINK_ENABLED_SENSESOAR
}
void senseSoarMAV::quat2euler(const double *quat, double &roll, double &pitch, double &yaw)
{
roll = std::atan2(2*(quat[0]*quat[1] + quat[2]*quat[3]),quat[0]*quat[0] - quat[1]*quat[1] - quat[2]*quat[2] + quat[3]*quat[3]);
pitch = std::asin(qMax(-1.0,qMin(1.0,2*(quat[0]*quat[2] - quat[1]*quat[3]))));
yaw = std::atan2(2*(quat[1]*quat[2] + quat[0]*quat[3]),quat[0]*quat[0] + quat[1]*quat[1] - quat[2]*quat[2] - quat[3]*quat[3]);
return;
}
\ No newline at end of file
#ifndef _SENSESOARMAV_H_
#define _SENSESOARMAV_H_
#include "UAS.h"
#include "mavlink.h"
#include <QTimer>
class senseSoarMAV : public UAS
{
Q_OBJECT
Q_INTERFACES(UASInterface)
public:
senseSoarMAV(MAVLinkProtocol* mavlink, int id);
~senseSoarMAV(void);
public slots:
/** @brief Receive a MAVLink message from this MAV */
void receiveMessage(LinkInterface* link, mavlink_message_t message);
protected:
float m_rotVel[3]; // Rotational velocity in the body frame
uint8_t senseSoarState;
private:
void quat2euler(const double *quat, double &roll, double &pitch, double &yaw);
};
#endif // _SENSESOARMAV_H_
\ No newline at end of file
......@@ -81,7 +81,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
// Connect the current UAS
action = new QAction(QIcon(":/images/devices/network-wireless.svg"), "", this);
LinkManager::instance()->add(link);
action->setData(LinkManager::instance()->getLinks().indexOf(link));
action->setData(link->getId());
action->setEnabled(true);
action->setVisible(true);
setLinkName(link->getName());
......@@ -159,6 +159,8 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
ui.linkScrollArea->setWidget(conf);
ui.linkGroupBox->setTitle(tr("Xbee Link"));
ui.linkType->setCurrentIndex(4);
connect(xbee,SIGNAL(tryConnectBegin(bool)),ui.actionConnect,SLOT(setDisabled(bool)));
connect(xbee,SIGNAL(tryConnectEnd(bool)),ui.actionConnect,SLOT(setEnabled(bool)));
}
#endif // XBEELINK
if (serial == 0 && udp == 0 && sim == 0
......@@ -232,21 +234,14 @@ void CommConfigurationWindow::setLinkType(int linktype)
break;
}
#endif // XBEELINK
case 0:
{
SerialLink *serial = new SerialLink();
tmpLink = serial;
MainWindow::instance()->addLink(tmpLink);
break;
}
/* case 1:
case 1:
{
UDPLink *udp = new UDPLink();
tmpLink = udp;
MainWindow::instance()->addLink(tmpLink);
break;
}
*/
#ifdef OPAL_RT
case 3:
{
......@@ -258,15 +253,24 @@ void CommConfigurationWindow::setLinkType(int linktype)
#endif // OPAL_RT
default:
{
MainWindow::instance()->addLink();
}
case 0:
{
SerialLink *serial = new SerialLink();
tmpLink = serial;
MainWindow::instance()->addLink(tmpLink);
break;
}
}
// trigger new window
const int32_t& linkIndex(LinkManager::instance()->getLinks().indexOf(tmpLink));
const int32_t& linkID(LinkManager::instance()->getLinks()[linkIndex]->getId());
QList<QAction*> actions = MainWindow::instance()->listLinkMenuActions();
foreach (QAction* act, actions)
{
if (act->data().toInt() == LinkManager::instance()->getLinks().indexOf(tmpLink))
if (act->data().toInt() == linkID)
{
act->trigger();
break;
......
......@@ -219,9 +219,14 @@ void DebugConsole::linkSelected(int linkId)
*/
void DebugConsole::updateLinkName(QString name)
{
// Set name if signal came from a link
// Set name if signal came from a link
LinkInterface* link = qobject_cast<LinkInterface*>(sender());
if (link != NULL) m_ui->linkComboBox->setItemText(link->getId(), name);
//if (link != NULL) m_ui->linkComboBox->setItemText(link->getId(), name);
if((link != NULL) && (links.contains(link)))
{
const qint16 &linkIndex(links.indexOf(link));
m_ui->linkComboBox->setItemText(linkIndex,name);
}
}
void DebugConsole::setAutoHold(bool hold)
......
......@@ -1050,10 +1050,11 @@ void MainWindow::addLink()
// Go fishing for this link's configuration window
QList<QAction*> actions = ui.menuNetwork->actions();
foreach (QAction* act, actions)
{
if (act->data().toInt() == LinkManager::instance()->getLinks().indexOf(link))
{
const int32_t& linkIndex(LinkManager::instance()->getLinks().indexOf(link));
const int32_t& linkID(LinkManager::instance()->getLinks()[linkIndex]->getId());
foreach (QAction* act, actions) {
if (act->data().toInt() == linkID) { // LinkManager::instance()->getLinks().indexOf(link)
act->trigger();
break;
}
......@@ -1072,20 +1073,20 @@ void MainWindow::addLink(LinkInterface *link)
// Go fishing for this link's configuration window
QList<QAction*> actions = ui.menuNetwork->actions();
bool found = false;
bool found(false);
foreach (QAction* act, actions)
{
if (act->data().toInt() == LinkManager::instance()->getLinks().indexOf(link))
{
const int32_t& linkIndex(LinkManager::instance()->getLinks().indexOf(link));
const int32_t& linkID(LinkManager::instance()->getLinks()[linkIndex]->getId());
foreach (QAction* act, actions) {
if (act->data().toInt() == linkID) { // LinkManager::instance()->getLinks().indexOf(link)
found = true;
}
}
UDPLink* udp = dynamic_cast<UDPLink*>(link);
//UDPLink* udp = dynamic_cast<UDPLink*>(link);
if (!found || udp)
{
if (!found) { // || udp
CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this);
QAction* action = commWidget->getAction();
ui.menuNetwork->addAction(action);
......@@ -1498,3 +1499,108 @@ QList<QAction*> MainWindow::listLinkMenuActions(void)
{
return ui.menuNetwork->actions();
}
/*
void MainWindow::buildSenseSoarWidgets()
{
if (!linechartWidget)
{
// Center widgets
linechartWidget = new Linecharts(this);
addToCentralWidgetsMenu(linechartWidget, tr("Realtime Plot"), SLOT(showCentralWidget()), CENTRAL_LINECHART);
}
if (!hudWidget)
{
hudWidget = new HUD(320, 240, this);
addToCentralWidgetsMenu(hudWidget, tr("Head Up Display"), SLOT(showCentralWidget()), CENTRAL_HUD);
}
if (!dataplotWidget) {
dataplotWidget = new QGCDataPlot2D(this);
addToCentralWidgetsMenu(dataplotWidget, "Logfile Plot", SLOT(showCentralWidget()), CENTRAL_DATA_PLOT);
}
#ifdef QGC_OSG_ENABLED
if (!_3DWidget) {
_3DWidget = Q3DWidgetFactory::get("PIXHAWK");
addToCentralWidgetsMenu(_3DWidget, tr("Local 3D"), SLOT(showCentralWidget()), CENTRAL_3D_LOCAL);
}
#endif
#ifdef QGC_OSGEARTH_ENABLED
if (!_3DMapWidget) {
_3DMapWidget = Q3DWidgetFactory::get("MAP3D");
addToCentralWidgetsMenu(_3DMapWidget, tr("OSG Earth 3D"), SLOT(showCentralWidget()), CENTRAL_OSGEARTH);
}
#endif
#if (defined _MSC_VER) | (defined Q_OS_MAC)
if (!gEarthWidget) {
gEarthWidget = new QGCGoogleEarthView(this);
addToCentralWidgetsMenu(gEarthWidget, tr("Google Earth"), SLOT(showCentralWidget()), CENTRAL_GOOGLE_EARTH);
}
#endif
// Dock widgets
if (!parametersDockWidget) {
parametersDockWidget = new QDockWidget(tr("Calibration and Onboard Parameters"), this);
parametersDockWidget->setWidget( new ParameterInterface(this) );
parametersDockWidget->setObjectName("PARAMETER_INTERFACE_DOCKWIDGET");
addToToolsMenu (parametersDockWidget, tr("Calibration and Parameters"), SLOT(showToolWidget(bool)), MENU_PARAMETERS, Qt::RightDockWidgetArea);
}
if (!hsiDockWidget) {
hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this);
hsiDockWidget->setWidget( new HSIDisplay(this) );
hsiDockWidget->setObjectName("HORIZONTAL_SITUATION_INDICATOR_DOCK_WIDGET");
addToToolsMenu (hsiDockWidget, tr("Horizontal Situation"), SLOT(showToolWidget(bool)), MENU_HSI, Qt::BottomDockWidgetArea);
}
if (!rcViewDockWidget) {
rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
rcViewDockWidget->setObjectName("RADIO_CONTROL_CHANNELS_DOCK_WIDGET");
addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget(bool)), MENU_RC_VIEW, Qt::BottomDockWidgetArea);
}
if (!headUpDockWidget) {
headUpDockWidget = new QDockWidget(tr("HUD"), this);
headUpDockWidget->setWidget( new HUD(320, 240, this));
headUpDockWidget->setObjectName("HEAD_UP_DISPLAY_DOCK_WIDGET");
addToToolsMenu (headUpDockWidget, tr("Head Up Display"), SLOT(showToolWidget(bool)), MENU_HUD, Qt::RightDockWidgetArea);
}
}
void MainWindow::connectSenseSoarWidgets()
{
}
void MainWindow::arrangeSenseSoarCenterStack()
{
if (!centerStack) {
qDebug() << "Center Stack not Created!";
return;
}
if (linechartWidget && (centerStack->indexOf(linechartWidget) == -1)) centerStack->addWidget(linechartWidget);
#ifdef QGC_OSG_ENABLED
if (_3DWidget && (centerStack->indexOf(_3DWidget) == -1)) centerStack->addWidget(_3DWidget);
#endif
#ifdef QGC_OSGEARTH_ENABLED
if (_3DMapWidget && (centerStack->indexOf(_3DMapWidget) == -1)) centerStack->addWidget(_3DMapWidget);
#endif
#if (defined _MSC_VER) | (defined Q_OS_MAC)
if (gEarthWidget && (centerStack->indexOf(gEarthWidget) == -1)) centerStack->addWidget(gEarthWidget);
#endif
if (hudWidget && (centerStack->indexOf(hudWidget) == -1)) centerStack->addWidget(hudWidget);
if (dataplotWidget && (centerStack->indexOf(dataplotWidget) == -1)) centerStack->addWidget(dataplotWidget);
}
void MainWindow::connectSenseSoarActions()
{
}
*/
......@@ -290,6 +290,7 @@ protected:
void buildCommonWidgets();
void connectCommonWidgets();
void connectCommonActions();
void connectSenseSoarActions();
void loadSettings();
void storeSettings();
......
......@@ -60,8 +60,8 @@ public:
signals:
/** @brief A parameter was changed in the widget, NOT onboard */
void parameterChanged(int component, QString parametername, QVariant value);
/** @brief Request a single parameter by index */
//void parameterChanged(int component, QString parametername, float value); // defined in QGCUASParamManager already
/** @brief Request a single parameter */
void requestParameter(int component, int parameter);
/** @brief Request a single parameter by name */
void requestParameter(int component, const QString& parameter);
......
......@@ -5,6 +5,7 @@
#include <QDir>
#include <QSettings>
#include <QFileInfoList>
#include <qdatastream.h>
#ifdef _WIN32
#include <QextSerialEnumerator.h>
......@@ -207,26 +208,29 @@ XbeeConfigurationWindow::XbeeConfigurationWindow(LinkInterface* link, QWidget *p
baudLabel = new QLabel;
baudLabel->setText(tr("Baut Rate"));
baudBox = new QComboBox;
baudBox->addItem("1200",1200);
baudBox->addItem("2400",2400);
baudBox->addItem("4800",4800);
baudBox->addItem("9600",9600);
baudBox->addItem("19200",19200);
baudBox->addItem("38400",38400);
baudBox->addItem("57600",57600);
baudBox->setCurrentIndex(1);
baudLabel->setBuddy(baudBox);
portLabel = new QLabel;
portLabel->setText(tr("SerialPort"));
portBox = new QComboBox;
this->setupPortList();
portBox->setEditable(true);
portLabel->setBuddy(portBox);
highAddrLabel = new QLabel;
highAddrLabel->setText(tr("Remote hex Address &High"));
highAddr = new HexSpinBox(this);
highAddrLabel->setBuddy(highAddr);
lowAddrLabel = new QLabel;
lowAddrLabel->setText(tr("Remote hex Address &Low"));
lowAddr = new HexSpinBox(this);
lowAddrLabel->setBuddy(lowAddr);
actionLayout = new QGridLayout;
actionLayout->addWidget(baudLabel,1,1);
actionLayout->addWidget(baudBox,1,2);
actionLayout->addWidget(portLabel,2,1);
actionLayout->addWidget(portBox,2,2);
actionLayout->addWidget(highAddrLabel,3,1);
actionLayout->addWidget(highAddr,3,2);
actionLayout->addWidget(lowAddrLabel,4,1);
actionLayout->addWidget(lowAddr,4,2);
tmpLayout = new QVBoxLayout;
tmpLayout->addStretch();
tmpLayout->addLayout(actionLayout);
......@@ -240,6 +244,41 @@ XbeeConfigurationWindow::XbeeConfigurationWindow(LinkInterface* link, QWidget *p
connect(portBox,SIGNAL(currentIndexChanged(QString)),this,SLOT(setPortName(QString)));
connect(portBox,SIGNAL(editTextChanged(QString)),this,SLOT(setPortName(QString)));
connect(baudBox,SIGNAL(currentIndexChanged(QString)),this,SLOT(setBaudRateString(QString)));
connect(highAddr,SIGNAL(valueChanged(int)),this,SLOT(addrChangedHigh(int)));
connect(lowAddr,SIGNAL(valueChanged(int)),this,SLOT(addrChangedLow(int)));
connect(this,SIGNAL(addrHighChanged(quint32)),xbeeLink,SLOT(setRemoteAddressHigh(quint32)));
connect(this,SIGNAL(addrLowChanged(quint32)),xbeeLink,SLOT(setRemoteAddressLow(quint32)));
baudBox->addItem("1200",1200);
baudBox->addItem("2400",2400);
baudBox->addItem("4800",4800);
baudBox->addItem("9600",9600);
baudBox->addItem("19200",19200);
baudBox->addItem("38400",38400);
baudBox->addItem("57600",57600);
baudBox->setCurrentIndex(6);
// try to open xbeeConf file for last remote address
QFile in("Xbeeconf.txt");
if(in.open(QIODevice::ReadOnly))
{
QDataStream inStr(&in);
int tmpaddrHigh;
int tmpaddrLow;
inStr >> tmpaddrHigh;
inStr >> tmpaddrLow;
highAddr->setValue(tmpaddrHigh);
lowAddr->setValue(tmpaddrLow);
}
else
{
highAddr->setValue(0x13A200);
lowAddr->setValue(0x40DDDDDD);
}
this->setupPortList();
portCheckTimer = new QTimer(this);
portCheckTimer->setInterval(1000);
......@@ -381,4 +420,30 @@ void XbeeConfigurationWindow::setBaudRateString(QString baud)
{
int rate = baud.toInt();
this->link->setBaudRate(rate);
}
void XbeeConfigurationWindow::addrChangedHigh(int addr)
{
quint32 uaddr = static_cast<quint32>(addr);
QFile out("Xbeeconf.txt");
if(out.open(QIODevice::WriteOnly))
{
QDataStream outStr(&out);
outStr << this->highAddr->value();
outStr << this->lowAddr->value();
}
emit addrHighChanged(uaddr);
}
void XbeeConfigurationWindow::addrChangedLow(int addr)
{
quint32 uaddr = static_cast<quint32>(addr);
QFile out("Xbeeconf.txt");
if(out.open(QIODevice::WriteOnly))
{
QDataStream outStr(&out);
outStr << this->highAddr->value();
outStr << this->lowAddr->value();
}
emit addrLowChanged(uaddr);
}
\ No newline at end of file
......@@ -12,6 +12,7 @@
#include<QtGui\qlayout.h>
#include <LinkInterface.h>
#include"XbeeLinkInterface.h"
#include "../comm/HexSpinBox.h"
class XbeeConfigurationWindow : public QWidget
......@@ -30,6 +31,10 @@ public slots:
void setBaudRateString(QString baud);
void setupPortList();
private slots:
void addrChangedHigh(int addr);
void addrChangedLow(int addr);
protected:
void showEvent(QShowEvent* event);
void hideEvent(QHideEvent* event);
......@@ -46,6 +51,14 @@ private:
XbeeLinkInterface* link;
QAction* action;
QTimer* portCheckTimer;
HexSpinBox* highAddr;
HexSpinBox* lowAddr;
QLabel* highAddrLabel;
QLabel* lowAddrLabel;
signals:
void addrHighChanged(quint32 addrHigh);
void addrLowChanged(quint32 addrLow);
};
......
This diff is collapsed.
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Monday, August 15 2011, 15:40 UTC
*/
#ifndef SENSESOAR_H
#define SENSESOAR_H
#ifdef __cplusplus
extern "C" {
#endif
#include "../protocol.h"
#define MAVLINK_ENABLED_SENSESOAR
#include "../common/common.h"
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif
// ENUM DEFINITIONS
/** @brief Different flight modes */
enum SENSESOAR_MODE
{
SENSESOAR_MODE_GLIDING=0, /* */
SENSESOAR_MODE_AUTONOMOUS=1, /* */
SENSESOAR_MODE_MANUAL=2, /* */
SENSESOAR_MODE_ENUM_END
};
// MESSAGE DEFINITIONS
#include "./mavlink_msg_obs_position.h"
#include "./mavlink_msg_obs_velocity.h"
#include "./mavlink_msg_obs_attitude.h"
#include "./mavlink_msg_obs_wind.h"
#include "./mavlink_msg_obs_air_velocity.h"
#include "./mavlink_msg_obs_bias.h"
#include "./mavlink_msg_obs_qff.h"
#include "./mavlink_msg_obs_air_temp.h"
#include "./mavlink_msg_filt_rot_vel.h"
#include "./mavlink_msg_llc_out.h"
#include "./mavlink_msg_pm_elec.h"
#include "./mavlink_msg_sys_stat.h"
#include "./mavlink_msg_cmd_airspeed_chng.h"
#include "./mavlink_msg_cmd_airspeed_ack.h"
// MESSAGE LENGTHS
#undef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 0, 0, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 0, 0, 21, 0, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 0, 12, 0, 32, 0, 12, 0, 12, 0, 24, 0, 4, 4, 12, 0, 12, 0, 20, 0, 4, 0, 5, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 }
#ifdef __cplusplus
}
#endif
#endif
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Monday, August 15 2011, 15:40 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
#include "SenseSoar.h"
#endif
// MESSAGE CMD_AIRSPEED_ACK PACKING
#define MAVLINK_MSG_ID_CMD_AIRSPEED_ACK 194
typedef struct __mavlink_cmd_airspeed_ack_t
{
float spCmd; ///< commanded airspeed
uint8_t ack; ///< 0:ack, 1:nack
} mavlink_cmd_airspeed_ack_t;
/**
* @brief Pack a cmd_airspeed_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param spCmd commanded airspeed
* @param ack 0:ack, 1:nack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float spCmd, uint8_t ack)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_ACK;
i += put_float_by_index(spCmd, i, msg->payload); // commanded airspeed
i += put_uint8_t_by_index(ack, i, msg->payload); // 0:ack, 1:nack
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a cmd_airspeed_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param spCmd commanded airspeed
* @param ack 0:ack, 1:nack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float spCmd, uint8_t ack)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_ACK;
i += put_float_by_index(spCmd, i, msg->payload); // commanded airspeed
i += put_uint8_t_by_index(ack, i, msg->payload); // 0:ack, 1:nack
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a cmd_airspeed_ack struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param cmd_airspeed_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_cmd_airspeed_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cmd_airspeed_ack_t* cmd_airspeed_ack)
{
return mavlink_msg_cmd_airspeed_ack_pack(system_id, component_id, msg, cmd_airspeed_ack->spCmd, cmd_airspeed_ack->ack);
}
/**
* @brief Send a cmd_airspeed_ack message
* @param chan MAVLink channel to send the message
*
* @param spCmd commanded airspeed
* @param ack 0:ack, 1:nack
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_cmd_airspeed_ack_send(mavlink_channel_t chan, float spCmd, uint8_t ack)
{
mavlink_message_t msg;
mavlink_msg_cmd_airspeed_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, spCmd, ack);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE CMD_AIRSPEED_ACK UNPACKING
/**
* @brief Get field spCmd from cmd_airspeed_ack message
*
* @return commanded airspeed
*/
static inline float mavlink_msg_cmd_airspeed_ack_get_spCmd(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 ack from cmd_airspeed_ack message
*
* @return 0:ack, 1:nack
*/
static inline uint8_t mavlink_msg_cmd_airspeed_ack_get_ack(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(float))[0];
}
/**
* @brief Decode a cmd_airspeed_ack message into a struct
*
* @param msg The message to decode
* @param cmd_airspeed_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_cmd_airspeed_ack_decode(const mavlink_message_t* msg, mavlink_cmd_airspeed_ack_t* cmd_airspeed_ack)
{
cmd_airspeed_ack->spCmd = mavlink_msg_cmd_airspeed_ack_get_spCmd(msg);
cmd_airspeed_ack->ack = mavlink_msg_cmd_airspeed_ack_get_ack(msg);
}
// MESSAGE CMD_AIRSPEED_CHNG PACKING
#define MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG 192
typedef struct __mavlink_cmd_airspeed_chng_t
{
uint8_t target; ///< Target ID
float spCmd; ///< commanded airspeed
} mavlink_cmd_airspeed_chng_t;
/**
* @brief Pack a cmd_airspeed_chng message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target Target ID
* @param spCmd commanded airspeed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float spCmd)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG;
i += put_uint8_t_by_index(target, i, msg->payload); // Target ID
i += put_float_by_index(spCmd, i, msg->payload); // commanded airspeed
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a cmd_airspeed_chng message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target Target ID
* @param spCmd commanded airspeed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float spCmd)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG;
i += put_uint8_t_by_index(target, i, msg->payload); // Target ID
i += put_float_by_index(spCmd, i, msg->payload); // commanded airspeed
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a cmd_airspeed_chng struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param cmd_airspeed_chng C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_cmd_airspeed_chng_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cmd_airspeed_chng_t* cmd_airspeed_chng)
{
return mavlink_msg_cmd_airspeed_chng_pack(system_id, component_id, msg, cmd_airspeed_chng->target, cmd_airspeed_chng->spCmd);
}
/**
* @brief Send a cmd_airspeed_chng message
* @param chan MAVLink channel to send the message
*
* @param target Target ID
* @param spCmd commanded airspeed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_cmd_airspeed_chng_send(mavlink_channel_t chan, uint8_t target, float spCmd)
{
mavlink_message_t msg;
mavlink_msg_cmd_airspeed_chng_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, spCmd);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE CMD_AIRSPEED_CHNG UNPACKING
/**
* @brief Get field target from cmd_airspeed_chng message
*
* @return Target ID
*/
static inline uint8_t mavlink_msg_cmd_airspeed_chng_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field spCmd from cmd_airspeed_chng message
*
* @return commanded airspeed
*/
static inline float mavlink_msg_cmd_airspeed_chng_get_spCmd(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 Decode a cmd_airspeed_chng message into a struct
*
* @param msg The message to decode
* @param cmd_airspeed_chng C-struct to decode the message contents into
*/
static inline void mavlink_msg_cmd_airspeed_chng_decode(const mavlink_message_t* msg, mavlink_cmd_airspeed_chng_t* cmd_airspeed_chng)
{
cmd_airspeed_chng->target = mavlink_msg_cmd_airspeed_chng_get_target(msg);
cmd_airspeed_chng->spCmd = mavlink_msg_cmd_airspeed_chng_get_spCmd(msg);
}
// MESSAGE FILT_ROT_VEL PACKING
#define MAVLINK_MSG_ID_FILT_ROT_VEL 184
typedef struct __mavlink_filt_rot_vel_t
{
float rotVel[3]; ///< rotational velocity
} mavlink_filt_rot_vel_t;
#define MAVLINK_MSG_FILT_ROT_VEL_FIELD_ROTVEL_LEN 3
/**
* @brief Pack a filt_rot_vel message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param rotVel rotational velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_filt_rot_vel_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const float* rotVel)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_FILT_ROT_VEL;
i += put_array_by_index((const int8_t*)rotVel, sizeof(float)*3, i, msg->payload); // rotational velocity
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a filt_rot_vel message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param rotVel rotational velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_filt_rot_vel_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const float* rotVel)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_FILT_ROT_VEL;
i += put_array_by_index((const int8_t*)rotVel, sizeof(float)*3, i, msg->payload); // rotational velocity
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a filt_rot_vel struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param filt_rot_vel C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_filt_rot_vel_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_filt_rot_vel_t* filt_rot_vel)
{
return mavlink_msg_filt_rot_vel_pack(system_id, component_id, msg, filt_rot_vel->rotVel);
}
/**
* @brief Send a filt_rot_vel message
* @param chan MAVLink channel to send the message
*
* @param rotVel rotational velocity
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_filt_rot_vel_send(mavlink_channel_t chan, const float* rotVel)
{
mavlink_message_t msg;
mavlink_msg_filt_rot_vel_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, rotVel);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE FILT_ROT_VEL UNPACKING
/**
* @brief Get field rotVel from filt_rot_vel message
*
* @return rotational velocity
*/
static inline uint16_t mavlink_msg_filt_rot_vel_get_rotVel(const mavlink_message_t* msg, float* r_data)
{
memcpy(r_data, msg->payload, sizeof(float)*3);
return sizeof(float)*3;
}
/**
* @brief Decode a filt_rot_vel message into a struct
*
* @param msg The message to decode
* @param filt_rot_vel C-struct to decode the message contents into
*/
static inline void mavlink_msg_filt_rot_vel_decode(const mavlink_message_t* msg, mavlink_filt_rot_vel_t* filt_rot_vel)
{
mavlink_msg_filt_rot_vel_get_rotVel(msg, filt_rot_vel->rotVel);
}
// MESSAGE LLC_OUT PACKING
#define MAVLINK_MSG_ID_LLC_OUT 186
typedef struct __mavlink_llc_out_t
{
int16_t servoOut[4]; ///< Servo signal
int16_t MotorOut[2]; ///< motor signal
} mavlink_llc_out_t;
#define MAVLINK_MSG_LLC_OUT_FIELD_SERVOOUT_LEN 4
#define MAVLINK_MSG_LLC_OUT_FIELD_MOTOROUT_LEN 2
/**
* @brief Pack a llc_out message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param servoOut Servo signal
* @param MotorOut motor signal
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_llc_out_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const int16_t* servoOut, const int16_t* MotorOut)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_LLC_OUT;
i += put_array_by_index((const int8_t*)servoOut, sizeof(int16_t)*4, i, msg->payload); // Servo signal
i += put_array_by_index((const int8_t*)MotorOut, sizeof(int16_t)*2, i, msg->payload); // motor signal
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a llc_out message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param servoOut Servo signal
* @param MotorOut motor signal
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_llc_out_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const int16_t* servoOut, const int16_t* MotorOut)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_LLC_OUT;
i += put_array_by_index((const int8_t*)servoOut, sizeof(int16_t)*4, i, msg->payload); // Servo signal
i += put_array_by_index((const int8_t*)MotorOut, sizeof(int16_t)*2, i, msg->payload); // motor signal
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a llc_out struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param llc_out C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_llc_out_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_llc_out_t* llc_out)
{
return mavlink_msg_llc_out_pack(system_id, component_id, msg, llc_out->servoOut, llc_out->MotorOut);
}
/**
* @brief Send a llc_out message
* @param chan MAVLink channel to send the message
*
* @param servoOut Servo signal
* @param MotorOut motor signal
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_llc_out_send(mavlink_channel_t chan, const int16_t* servoOut, const int16_t* MotorOut)
{
mavlink_message_t msg;
mavlink_msg_llc_out_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, servoOut, MotorOut);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE LLC_OUT UNPACKING
/**
* @brief Get field servoOut from llc_out message
*
* @return Servo signal
*/
static inline uint16_t mavlink_msg_llc_out_get_servoOut(const mavlink_message_t* msg, int16_t* r_data)
{
memcpy(r_data, msg->payload, sizeof(int16_t)*4);
return sizeof(int16_t)*4;
}
/**
* @brief Get field MotorOut from llc_out message
*
* @return motor signal
*/
static inline uint16_t mavlink_msg_llc_out_get_MotorOut(const mavlink_message_t* msg, int16_t* r_data)
{
memcpy(r_data, msg->payload+sizeof(int16_t)*4, sizeof(int16_t)*2);
return sizeof(int16_t)*2;
}
/**
* @brief Decode a llc_out message into a struct
*
* @param msg The message to decode
* @param llc_out C-struct to decode the message contents into
*/
static inline void mavlink_msg_llc_out_decode(const mavlink_message_t* msg, mavlink_llc_out_t* llc_out)
{
mavlink_msg_llc_out_get_servoOut(msg, llc_out->servoOut);
mavlink_msg_llc_out_get_MotorOut(msg, llc_out->MotorOut);
}
// MESSAGE OBS_AIR_TEMP PACKING
#define MAVLINK_MSG_ID_OBS_AIR_TEMP 183
typedef struct __mavlink_obs_air_temp_t
{
float airT; ///< Air Temperatur
} mavlink_obs_air_temp_t;
/**
* @brief Pack a obs_air_temp message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param airT Air Temperatur
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_temp_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float airT)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_AIR_TEMP;
i += put_float_by_index(airT, i, msg->payload); // Air Temperatur
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_air_temp message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param airT Air Temperatur
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_temp_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float airT)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_AIR_TEMP;
i += put_float_by_index(airT, i, msg->payload); // Air Temperatur
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_air_temp struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_air_temp C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_air_temp_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_air_temp_t* obs_air_temp)
{
return mavlink_msg_obs_air_temp_pack(system_id, component_id, msg, obs_air_temp->airT);
}
/**
* @brief Send a obs_air_temp message
* @param chan MAVLink channel to send the message
*
* @param airT Air Temperatur
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_air_temp_send(mavlink_channel_t chan, float airT)
{
mavlink_message_t msg;
mavlink_msg_obs_air_temp_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, airT);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_AIR_TEMP UNPACKING
/**
* @brief Get field airT from obs_air_temp message
*
* @return Air Temperatur
*/
static inline float mavlink_msg_obs_air_temp_get_airT(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 Decode a obs_air_temp message into a struct
*
* @param msg The message to decode
* @param obs_air_temp C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_air_temp_decode(const mavlink_message_t* msg, mavlink_obs_air_temp_t* obs_air_temp)
{
obs_air_temp->airT = mavlink_msg_obs_air_temp_get_airT(msg);
}
// MESSAGE OBS_AIR_VELOCITY PACKING
#define MAVLINK_MSG_ID_OBS_AIR_VELOCITY 178
typedef struct __mavlink_obs_air_velocity_t
{
float magnitude; ///< Air speed
float aoa; ///< angle of attack
float slip; ///< slip angle
} mavlink_obs_air_velocity_t;
/**
* @brief Pack a obs_air_velocity message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param magnitude Air speed
* @param aoa angle of attack
* @param slip slip angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_velocity_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float magnitude, float aoa, float slip)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_AIR_VELOCITY;
i += put_float_by_index(magnitude, i, msg->payload); // Air speed
i += put_float_by_index(aoa, i, msg->payload); // angle of attack
i += put_float_by_index(slip, i, msg->payload); // slip angle
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_air_velocity message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param magnitude Air speed
* @param aoa angle of attack
* @param slip slip angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_velocity_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float magnitude, float aoa, float slip)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_AIR_VELOCITY;
i += put_float_by_index(magnitude, i, msg->payload); // Air speed
i += put_float_by_index(aoa, i, msg->payload); // angle of attack
i += put_float_by_index(slip, i, msg->payload); // slip angle
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_air_velocity struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_air_velocity C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_air_velocity_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_air_velocity_t* obs_air_velocity)
{
return mavlink_msg_obs_air_velocity_pack(system_id, component_id, msg, obs_air_velocity->magnitude, obs_air_velocity->aoa, obs_air_velocity->slip);
}
/**
* @brief Send a obs_air_velocity message
* @param chan MAVLink channel to send the message
*
* @param magnitude Air speed
* @param aoa angle of attack
* @param slip slip angle
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_air_velocity_send(mavlink_channel_t chan, float magnitude, float aoa, float slip)
{
mavlink_message_t msg;
mavlink_msg_obs_air_velocity_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, magnitude, aoa, slip);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_AIR_VELOCITY UNPACKING
/**
* @brief Get field magnitude from obs_air_velocity message
*
* @return Air speed
*/
static inline float mavlink_msg_obs_air_velocity_get_magnitude(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 aoa from obs_air_velocity message
*
* @return angle of attack
*/
static inline float mavlink_msg_obs_air_velocity_get_aoa(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 slip from obs_air_velocity message
*
* @return slip angle
*/
static inline float mavlink_msg_obs_air_velocity_get_slip(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 Decode a obs_air_velocity message into a struct
*
* @param msg The message to decode
* @param obs_air_velocity C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_air_velocity_decode(const mavlink_message_t* msg, mavlink_obs_air_velocity_t* obs_air_velocity)
{
obs_air_velocity->magnitude = mavlink_msg_obs_air_velocity_get_magnitude(msg);
obs_air_velocity->aoa = mavlink_msg_obs_air_velocity_get_aoa(msg);
obs_air_velocity->slip = mavlink_msg_obs_air_velocity_get_slip(msg);
}
// MESSAGE OBS_ATTITUDE PACKING
#define MAVLINK_MSG_ID_OBS_ATTITUDE 174
typedef struct __mavlink_obs_attitude_t
{
double quat[4]; ///< Quaternion re;im
} mavlink_obs_attitude_t;
#define MAVLINK_MSG_OBS_ATTITUDE_FIELD_QUAT_LEN 4
/**
* @brief Pack a obs_attitude message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param quat Quaternion re;im
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const double* quat)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_ATTITUDE;
i += put_array_by_index((const int8_t*)quat, sizeof(double)*4, i, msg->payload); // Quaternion re;im
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_attitude message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param quat Quaternion re;im
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const double* quat)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_ATTITUDE;
i += put_array_by_index((const int8_t*)quat, sizeof(double)*4, i, msg->payload); // Quaternion re;im
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_attitude struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_attitude C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_attitude_t* obs_attitude)
{
return mavlink_msg_obs_attitude_pack(system_id, component_id, msg, obs_attitude->quat);
}
/**
* @brief Send a obs_attitude message
* @param chan MAVLink channel to send the message
*
* @param quat Quaternion re;im
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_attitude_send(mavlink_channel_t chan, const double* quat)
{
mavlink_message_t msg;
mavlink_msg_obs_attitude_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, quat);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_ATTITUDE UNPACKING
/**
* @brief Get field quat from obs_attitude message
*
* @return Quaternion re;im
*/
static inline uint16_t mavlink_msg_obs_attitude_get_quat(const mavlink_message_t* msg, double* r_data)
{
memcpy(r_data, msg->payload, sizeof(double)*4);
return sizeof(double)*4;
}
/**
* @brief Decode a obs_attitude message into a struct
*
* @param msg The message to decode
* @param obs_attitude C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_attitude_decode(const mavlink_message_t* msg, mavlink_obs_attitude_t* obs_attitude)
{
mavlink_msg_obs_attitude_get_quat(msg, obs_attitude->quat);
}
// MESSAGE OBS_BIAS PACKING
#define MAVLINK_MSG_ID_OBS_BIAS 180
typedef struct __mavlink_obs_bias_t
{
float accBias[3]; ///< accelerometer bias
float gyroBias[3]; ///< gyroscope bias
} mavlink_obs_bias_t;
#define MAVLINK_MSG_OBS_BIAS_FIELD_ACCBIAS_LEN 3
#define MAVLINK_MSG_OBS_BIAS_FIELD_GYROBIAS_LEN 3
/**
* @brief Pack a obs_bias message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param accBias accelerometer bias
* @param gyroBias gyroscope bias
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const float* accBias, const float* gyroBias)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_BIAS;
i += put_array_by_index((const int8_t*)accBias, sizeof(float)*3, i, msg->payload); // accelerometer bias
i += put_array_by_index((const int8_t*)gyroBias, sizeof(float)*3, i, msg->payload); // gyroscope bias
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_bias message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param accBias accelerometer bias
* @param gyroBias gyroscope bias
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const float* accBias, const float* gyroBias)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_BIAS;
i += put_array_by_index((const int8_t*)accBias, sizeof(float)*3, i, msg->payload); // accelerometer bias
i += put_array_by_index((const int8_t*)gyroBias, sizeof(float)*3, i, msg->payload); // gyroscope bias
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_bias struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_bias C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_bias_t* obs_bias)
{
return mavlink_msg_obs_bias_pack(system_id, component_id, msg, obs_bias->accBias, obs_bias->gyroBias);
}
/**
* @brief Send a obs_bias message
* @param chan MAVLink channel to send the message
*
* @param accBias accelerometer bias
* @param gyroBias gyroscope bias
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_bias_send(mavlink_channel_t chan, const float* accBias, const float* gyroBias)
{
mavlink_message_t msg;
mavlink_msg_obs_bias_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, accBias, gyroBias);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_BIAS UNPACKING
/**
* @brief Get field accBias from obs_bias message
*
* @return accelerometer bias
*/
static inline uint16_t mavlink_msg_obs_bias_get_accBias(const mavlink_message_t* msg, float* r_data)
{
memcpy(r_data, msg->payload, sizeof(float)*3);
return sizeof(float)*3;
}
/**
* @brief Get field gyroBias from obs_bias message
*
* @return gyroscope bias
*/
static inline uint16_t mavlink_msg_obs_bias_get_gyroBias(const mavlink_message_t* msg, float* r_data)
{
memcpy(r_data, msg->payload+sizeof(float)*3, sizeof(float)*3);
return sizeof(float)*3;
}
/**
* @brief Decode a obs_bias message into a struct
*
* @param msg The message to decode
* @param obs_bias C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_bias_decode(const mavlink_message_t* msg, mavlink_obs_bias_t* obs_bias)
{
mavlink_msg_obs_bias_get_accBias(msg, obs_bias->accBias);
mavlink_msg_obs_bias_get_gyroBias(msg, obs_bias->gyroBias);
}
// MESSAGE OBS_POSITION PACKING
#define MAVLINK_MSG_ID_OBS_POSITION 170
typedef struct __mavlink_obs_position_t
{
int32_t lon; ///< Longitude expressed in 1E7
int32_t lat; ///< Latitude expressed in 1E7
int32_t alt; ///< Altitude expressed in milimeters
} mavlink_obs_position_t;
/**
* @brief Pack a obs_position message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param lon Longitude expressed in 1E7
* @param lat Latitude expressed in 1E7
* @param alt Altitude expressed in milimeters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int32_t lon, int32_t lat, int32_t alt)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_POSITION;
i += put_int32_t_by_index(lon, i, msg->payload); // Longitude expressed in 1E7
i += put_int32_t_by_index(lat, i, msg->payload); // Latitude expressed in 1E7
i += put_int32_t_by_index(alt, i, msg->payload); // Altitude expressed in milimeters
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_position message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param lon Longitude expressed in 1E7
* @param lat Latitude expressed in 1E7
* @param alt Altitude expressed in milimeters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int32_t lon, int32_t lat, int32_t alt)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_POSITION;
i += put_int32_t_by_index(lon, i, msg->payload); // Longitude expressed in 1E7
i += put_int32_t_by_index(lat, i, msg->payload); // Latitude expressed in 1E7
i += put_int32_t_by_index(alt, i, msg->payload); // Altitude expressed in milimeters
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_position struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_position C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_position_t* obs_position)
{
return mavlink_msg_obs_position_pack(system_id, component_id, msg, obs_position->lon, obs_position->lat, obs_position->alt);
}
/**
* @brief Send a obs_position message
* @param chan MAVLink channel to send the message
*
* @param lon Longitude expressed in 1E7
* @param lat Latitude expressed in 1E7
* @param alt Altitude expressed in milimeters
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_position_send(mavlink_channel_t chan, int32_t lon, int32_t lat, int32_t alt)
{
mavlink_message_t msg;
mavlink_msg_obs_position_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, lon, lat, alt);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_POSITION UNPACKING
/**
* @brief Get field lon from obs_position message
*
* @return Longitude expressed in 1E7
*/
static inline int32_t mavlink_msg_obs_position_get_lon(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 (int32_t)r.i;
}
/**
* @brief Get field lat from obs_position message
*
* @return Latitude expressed in 1E7
*/
static inline int32_t mavlink_msg_obs_position_get_lat(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(int32_t))[0];
r.b[2] = (msg->payload+sizeof(int32_t))[1];
r.b[1] = (msg->payload+sizeof(int32_t))[2];
r.b[0] = (msg->payload+sizeof(int32_t))[3];
return (int32_t)r.i;
}
/**
* @brief Get field alt from obs_position message
*
* @return Altitude expressed in milimeters
*/
static inline int32_t mavlink_msg_obs_position_get_alt(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[0];
r.b[2] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[1];
r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[2];
r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[3];
return (int32_t)r.i;
}
/**
* @brief Decode a obs_position message into a struct
*
* @param msg The message to decode
* @param obs_position C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_position_decode(const mavlink_message_t* msg, mavlink_obs_position_t* obs_position)
{
obs_position->lon = mavlink_msg_obs_position_get_lon(msg);
obs_position->lat = mavlink_msg_obs_position_get_lat(msg);
obs_position->alt = mavlink_msg_obs_position_get_alt(msg);
}
// MESSAGE OBS_QFF PACKING
#define MAVLINK_MSG_ID_OBS_QFF 182
typedef struct __mavlink_obs_qff_t
{
float qff; ///< Wind
} mavlink_obs_qff_t;
/**
* @brief Pack a obs_qff message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param qff Wind
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_qff_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float qff)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_QFF;
i += put_float_by_index(qff, i, msg->payload); // Wind
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_qff message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param qff Wind
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_qff_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float qff)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_QFF;
i += put_float_by_index(qff, i, msg->payload); // Wind
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_qff struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_qff C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_qff_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_qff_t* obs_qff)
{
return mavlink_msg_obs_qff_pack(system_id, component_id, msg, obs_qff->qff);
}
/**
* @brief Send a obs_qff message
* @param chan MAVLink channel to send the message
*
* @param qff Wind
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_qff_send(mavlink_channel_t chan, float qff)
{
mavlink_message_t msg;
mavlink_msg_obs_qff_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, qff);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_QFF UNPACKING
/**
* @brief Get field qff from obs_qff message
*
* @return Wind
*/
static inline float mavlink_msg_obs_qff_get_qff(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 Decode a obs_qff message into a struct
*
* @param msg The message to decode
* @param obs_qff C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_qff_decode(const mavlink_message_t* msg, mavlink_obs_qff_t* obs_qff)
{
obs_qff->qff = mavlink_msg_obs_qff_get_qff(msg);
}
// MESSAGE OBS_VELOCITY PACKING
#define MAVLINK_MSG_ID_OBS_VELOCITY 172
typedef struct __mavlink_obs_velocity_t
{
float vel[3]; ///< Velocity
} mavlink_obs_velocity_t;
#define MAVLINK_MSG_OBS_VELOCITY_FIELD_VEL_LEN 3
/**
* @brief Pack a obs_velocity message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param vel Velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_velocity_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const float* vel)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_VELOCITY;
i += put_array_by_index((const int8_t*)vel, sizeof(float)*3, i, msg->payload); // Velocity
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_velocity message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param vel Velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_velocity_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const float* vel)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_VELOCITY;
i += put_array_by_index((const int8_t*)vel, sizeof(float)*3, i, msg->payload); // Velocity
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_velocity struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_velocity C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_velocity_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_velocity_t* obs_velocity)
{
return mavlink_msg_obs_velocity_pack(system_id, component_id, msg, obs_velocity->vel);
}
/**
* @brief Send a obs_velocity message
* @param chan MAVLink channel to send the message
*
* @param vel Velocity
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_velocity_send(mavlink_channel_t chan, const float* vel)
{
mavlink_message_t msg;
mavlink_msg_obs_velocity_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, vel);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_VELOCITY UNPACKING
/**
* @brief Get field vel from obs_velocity message
*
* @return Velocity
*/
static inline uint16_t mavlink_msg_obs_velocity_get_vel(const mavlink_message_t* msg, float* r_data)
{
memcpy(r_data, msg->payload, sizeof(float)*3);
return sizeof(float)*3;
}
/**
* @brief Decode a obs_velocity message into a struct
*
* @param msg The message to decode
* @param obs_velocity C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_velocity_decode(const mavlink_message_t* msg, mavlink_obs_velocity_t* obs_velocity)
{
mavlink_msg_obs_velocity_get_vel(msg, obs_velocity->vel);
}
// MESSAGE OBS_WIND PACKING
#define MAVLINK_MSG_ID_OBS_WIND 176
typedef struct __mavlink_obs_wind_t
{
float wind[3]; ///< Wind
} mavlink_obs_wind_t;
#define MAVLINK_MSG_OBS_WIND_FIELD_WIND_LEN 3
/**
* @brief Pack a obs_wind message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param wind Wind
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_wind_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const float* wind)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_WIND;
i += put_array_by_index((const int8_t*)wind, sizeof(float)*3, i, msg->payload); // Wind
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_wind message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param wind Wind
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_wind_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const float* wind)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_WIND;
i += put_array_by_index((const int8_t*)wind, sizeof(float)*3, i, msg->payload); // Wind
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_wind struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_wind C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_wind_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_wind_t* obs_wind)
{
return mavlink_msg_obs_wind_pack(system_id, component_id, msg, obs_wind->wind);
}
/**
* @brief Send a obs_wind message
* @param chan MAVLink channel to send the message
*
* @param wind Wind
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_wind_send(mavlink_channel_t chan, const float* wind)
{
mavlink_message_t msg;
mavlink_msg_obs_wind_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, wind);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_WIND UNPACKING
/**
* @brief Get field wind from obs_wind message
*
* @return Wind
*/
static inline uint16_t mavlink_msg_obs_wind_get_wind(const mavlink_message_t* msg, float* r_data)
{
memcpy(r_data, msg->payload, sizeof(float)*3);
return sizeof(float)*3;
}
/**
* @brief Decode a obs_wind message into a struct
*
* @param msg The message to decode
* @param obs_wind C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_wind_decode(const mavlink_message_t* msg, mavlink_obs_wind_t* obs_wind)
{
mavlink_msg_obs_wind_get_wind(msg, obs_wind->wind);
}
// MESSAGE PM_ELEC PACKING
#define MAVLINK_MSG_ID_PM_ELEC 188
typedef struct __mavlink_pm_elec_t
{
float PwCons; ///< current power consumption
float BatStat; ///< battery status
float PwGen[3]; ///< Power generation from each module
} mavlink_pm_elec_t;
#define MAVLINK_MSG_PM_ELEC_FIELD_PWGEN_LEN 3
/**
* @brief Pack a pm_elec message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param PwCons current power consumption
* @param BatStat battery status
* @param PwGen Power generation from each module
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pm_elec_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float PwCons, float BatStat, const float* PwGen)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PM_ELEC;
i += put_float_by_index(PwCons, i, msg->payload); // current power consumption
i += put_float_by_index(BatStat, i, msg->payload); // battery status
i += put_array_by_index((const int8_t*)PwGen, sizeof(float)*3, i, msg->payload); // Power generation from each module
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a pm_elec message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param PwCons current power consumption
* @param BatStat battery status
* @param PwGen Power generation from each module
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pm_elec_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float PwCons, float BatStat, const float* PwGen)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PM_ELEC;
i += put_float_by_index(PwCons, i, msg->payload); // current power consumption
i += put_float_by_index(BatStat, i, msg->payload); // battery status
i += put_array_by_index((const int8_t*)PwGen, sizeof(float)*3, i, msg->payload); // Power generation from each module
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a pm_elec struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param pm_elec C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_pm_elec_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pm_elec_t* pm_elec)
{
return mavlink_msg_pm_elec_pack(system_id, component_id, msg, pm_elec->PwCons, pm_elec->BatStat, pm_elec->PwGen);
}
/**
* @brief Send a pm_elec message
* @param chan MAVLink channel to send the message
*
* @param PwCons current power consumption
* @param BatStat battery status
* @param PwGen Power generation from each module
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_pm_elec_send(mavlink_channel_t chan, float PwCons, float BatStat, const float* PwGen)
{
mavlink_message_t msg;
mavlink_msg_pm_elec_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, PwCons, BatStat, PwGen);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE PM_ELEC UNPACKING
/**
* @brief Get field PwCons from pm_elec message
*
* @return current power consumption
*/
static inline float mavlink_msg_pm_elec_get_PwCons(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 BatStat from pm_elec message
*
* @return battery status
*/
static inline float mavlink_msg_pm_elec_get_BatStat(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 PwGen from pm_elec message
*
* @return Power generation from each module
*/
static inline uint16_t mavlink_msg_pm_elec_get_PwGen(const mavlink_message_t* msg, float* r_data)
{
memcpy(r_data, msg->payload+sizeof(float)+sizeof(float), sizeof(float)*3);
return sizeof(float)*3;
}
/**
* @brief Decode a pm_elec message into a struct
*
* @param msg The message to decode
* @param pm_elec C-struct to decode the message contents into
*/
static inline void mavlink_msg_pm_elec_decode(const mavlink_message_t* msg, mavlink_pm_elec_t* pm_elec)
{
pm_elec->PwCons = mavlink_msg_pm_elec_get_PwCons(msg);
pm_elec->BatStat = mavlink_msg_pm_elec_get_BatStat(msg);
mavlink_msg_pm_elec_get_PwGen(msg, pm_elec->PwGen);
}
// MESSAGE SYS_STAT PACKING
#define MAVLINK_MSG_ID_SYS_STAT 190
typedef struct __mavlink_sys_stat_t
{
uint8_t gps; ///< gps status
uint8_t act; ///< actuator status
uint8_t mod; ///< module status
uint8_t commRssi; ///< module status
} mavlink_sys_stat_t;
/**
* @brief Pack a sys_stat message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param gps gps status
* @param act actuator status
* @param mod module status
* @param commRssi module status
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sys_stat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SYS_STAT;
i += put_uint8_t_by_index(gps, i, msg->payload); // gps status
i += put_uint8_t_by_index(act, i, msg->payload); // actuator status
i += put_uint8_t_by_index(mod, i, msg->payload); // module status
i += put_uint8_t_by_index(commRssi, i, msg->payload); // module status
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a sys_stat message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param gps gps status
* @param act actuator status
* @param mod module status
* @param commRssi module status
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sys_stat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SYS_STAT;
i += put_uint8_t_by_index(gps, i, msg->payload); // gps status
i += put_uint8_t_by_index(act, i, msg->payload); // actuator status
i += put_uint8_t_by_index(mod, i, msg->payload); // module status
i += put_uint8_t_by_index(commRssi, i, msg->payload); // module status
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a sys_stat struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param sys_stat C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sys_stat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_stat_t* sys_stat)
{
return mavlink_msg_sys_stat_pack(system_id, component_id, msg, sys_stat->gps, sys_stat->act, sys_stat->mod, sys_stat->commRssi);
}
/**
* @brief Send a sys_stat message
* @param chan MAVLink channel to send the message
*
* @param gps gps status
* @param act actuator status
* @param mod module status
* @param commRssi module status
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_sys_stat_send(mavlink_channel_t chan, uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi)
{
mavlink_message_t msg;
mavlink_msg_sys_stat_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, gps, act, mod, commRssi);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE SYS_STAT UNPACKING
/**
* @brief Get field gps from sys_stat message
*
* @return gps status
*/
static inline uint8_t mavlink_msg_sys_stat_get_gps(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field act from sys_stat message
*
* @return actuator status
*/
static inline uint8_t mavlink_msg_sys_stat_get_act(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field mod from sys_stat message
*
* @return module status
*/
static inline uint8_t mavlink_msg_sys_stat_get_mod(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field commRssi from sys_stat message
*
* @return module status
*/
static inline uint8_t mavlink_msg_sys_stat_get_commRssi(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Decode a sys_stat message into a struct
*
* @param msg The message to decode
* @param sys_stat C-struct to decode the message contents into
*/
static inline void mavlink_msg_sys_stat_decode(const mavlink_message_t* msg, mavlink_sys_stat_t* sys_stat)
{
sys_stat->gps = mavlink_msg_sys_stat_get_gps(msg);
sys_stat->act = mavlink_msg_sys_stat_get_act(msg);
sys_stat->mod = mavlink_msg_sys_stat_get_mod(msg);
sys_stat->commRssi = mavlink_msg_sys_stat_get_commRssi(msg);
}
<?xml version='1.0'?>
<mavlink>
<include>common.xml</include>
<enums>
<enum name="SENSESOAR_MODE">
<description> Different flight modes </description>
<entry name="SENSESOAR_MODE_GLIDING"> Gliding mode with motors off</entry>
<entry name="SENSESOAR_MODE_AUTONOMOUS"> Autonomous flight</entry>
<entry name="SENSESOAR_MODE_MANUAL"> RC controlled</entry>
</enum>
</enums>
<messages>
<message id="170" name="OBS_POSITION">
Position estimate of the observer in global frame
<field type="int32_t" name="lon">Longitude expressed in 1E7</field>
<field type="int32_t" name="lat">Latitude expressed in 1E7</field>
<field type="int32_t" name="alt">Altitude expressed in milimeters</field>
</message>
<message id="172" name="OBS_VELOCITY">
velocity estimate of the observer in NED inertial frame
<field type="float[3]" name="vel">Velocity</field>
</message>
<message id="174" name="OBS_ATTITUDE">
attitude estimate of the observer
<field type="double[4]" name="quat">Quaternion re;im</field>
</message>
<message id="176" name="OBS_WIND">
Wind estimate in NED inertial frame
<field type="float[3]" name="wind">Wind</field>
</message>
<message id="178" name="OBS_AIR_VELOCITY">
Estimate of the air velocity
<field type="float" name="magnitude">Air speed</field>
<field type="float" name="aoa">angle of attack</field>
<field type="float" name="slip">slip angle</field>
</message>
<message id="180" name="OBS_BIAS">
IMU biases
<field type="float[3]" name="accBias">accelerometer bias</field>
<field type="float[3]" name="gyroBias">gyroscope bias</field>
</message>
<message id="182" name="OBS_QFF">
estimate of the pressure at sea level
<field type="float" name="qff">Wind</field>
</message>
<message id="183" name="OBS_AIR_TEMP">
ambient air temperature
<field type="float" name="airT">Air Temperatur</field>
</message>
<message id="184" name="FILT_ROT_VEL">
filtered rotational velocity
<field type="float[3]" name="rotVel">rotational velocity</field>
</message>
<message id="186" name="LLC_OUT">
low level control output
<field type="int16_t[4]" name="servoOut">Servo signal</field>
<field type="int16_t[2]" name="MotorOut">motor signal</field>
</message>
<message id="188" name="PM_ELEC">
Power managment
<field type="float" name="PwCons">current power consumption</field>
<field type="float" name="BatStat">battery status</field>
<field type="float[3]" name="PwGen">Power generation from each module</field>
</message>
<message id="190" name="SYS_Stat">
system status
<field type="uint8_t" name="gps">gps status</field>
<field type="uint8_t" name="act">actuator status</field>
<field type="uint8_t" name="mod">module status</field>
<field type="uint8_t" name="commRssi">module status</field>
</message>
<message id="192" name="CMD_AIRSPEED_CHNG">
change commanded air speed
<field type="uint8_t" name="target">Target ID</field>
<field type="float" name="spCmd">commanded airspeed</field>
</message>
<message id="194" name="CMD_AIRSPEED_ACK">
accept change of airspeed
<field type="float" name="spCmd">commanded airspeed</field>
<field type="uint8_t" name="ack">0:ack, 1:nack</field>
</message>
</messages>
</mavlink>
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment