mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-12-01 09:24:10 +01:00
Merge remote-tracking branch 'origin/LP-183_more_qml_friendly_gcs_uav_object_generator' into filnet/LP-29_osgearth_integration
This commit is contained in:
commit
9b100bea4a
@ -1,159 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file cachedsvgitem.h
|
||||
* @author Dmytro Poplavskiy Copyright (C) 2011.
|
||||
* @{
|
||||
* @brief OpenGL texture cached SVG item
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "cachedsvgitem.h"
|
||||
#include <QDebug>
|
||||
|
||||
#ifndef GL_CLAMP_TO_EDGE
|
||||
#define GL_CLAMP_TO_EDGE 0x812F
|
||||
#endif
|
||||
|
||||
CachedSvgItem::CachedSvgItem(QGraphicsItem *parent) :
|
||||
QGraphicsSvgItem(parent),
|
||||
m_context(0),
|
||||
m_texture(0),
|
||||
m_scale(1.0)
|
||||
{
|
||||
setCacheMode(NoCache);
|
||||
}
|
||||
|
||||
CachedSvgItem::CachedSvgItem(const QString & fileName, QGraphicsItem *parent) :
|
||||
QGraphicsSvgItem(fileName, parent),
|
||||
m_context(0),
|
||||
m_texture(0),
|
||||
m_scale(1.0)
|
||||
{
|
||||
setCacheMode(NoCache);
|
||||
}
|
||||
|
||||
CachedSvgItem::~CachedSvgItem()
|
||||
{
|
||||
if (m_context && m_texture) {
|
||||
m_context->makeCurrent();
|
||||
glDeleteTextures(1, &m_texture);
|
||||
}
|
||||
}
|
||||
|
||||
void CachedSvgItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget)
|
||||
{
|
||||
if (painter->paintEngine()->type() != QPaintEngine::OpenGL &&
|
||||
painter->paintEngine()->type() != QPaintEngine::OpenGL2) {
|
||||
// Fallback to direct painting
|
||||
QGraphicsSvgItem::paint(painter, option, widget);
|
||||
return;
|
||||
}
|
||||
|
||||
QRectF br = boundingRect();
|
||||
QTransform transform = painter->worldTransform();
|
||||
qreal sceneScale = transform.map(QLineF(0, 0, 1, 0)).length();
|
||||
|
||||
bool stencilTestEnabled = glIsEnabled(GL_STENCIL_TEST);
|
||||
bool scissorTestEnabled = glIsEnabled(GL_SCISSOR_TEST);
|
||||
|
||||
painter->beginNativePainting();
|
||||
|
||||
if (stencilTestEnabled) {
|
||||
glEnable(GL_STENCIL_TEST);
|
||||
}
|
||||
if (scissorTestEnabled) {
|
||||
glEnable(GL_SCISSOR_TEST);
|
||||
}
|
||||
|
||||
bool dirty = false;
|
||||
if (!m_texture) {
|
||||
glGenTextures(1, &m_texture);
|
||||
m_context = const_cast<QGLContext *>(QGLContext::currentContext());
|
||||
|
||||
dirty = true;
|
||||
}
|
||||
|
||||
if (!qFuzzyCompare(sceneScale, m_scale)) {
|
||||
m_scale = sceneScale;
|
||||
dirty = true;
|
||||
}
|
||||
|
||||
int textureWidth = (int(br.width() * m_scale) + 3) & ~3;
|
||||
int textureHeight = (int(br.height() * m_scale) + 3) & ~3;
|
||||
|
||||
if (dirty) {
|
||||
// qDebug() << "re-render image";
|
||||
|
||||
QImage img(textureWidth, textureHeight, QImage::Format_ARGB32);
|
||||
{
|
||||
img.fill(Qt::transparent);
|
||||
QPainter p;
|
||||
p.begin(&img);
|
||||
p.setRenderHints(painter->renderHints());
|
||||
p.translate(br.topLeft());
|
||||
p.scale(m_scale, m_scale);
|
||||
QGraphicsSvgItem::paint(&p, option, 0);
|
||||
p.end();
|
||||
|
||||
img = img.rgbSwapped();
|
||||
}
|
||||
|
||||
glEnable(GL_TEXTURE_2D);
|
||||
|
||||
glBindTexture(GL_TEXTURE_2D, m_texture);
|
||||
glTexImage2D(
|
||||
GL_TEXTURE_2D,
|
||||
0,
|
||||
GL_RGBA,
|
||||
textureWidth,
|
||||
textureHeight,
|
||||
0,
|
||||
GL_RGBA,
|
||||
GL_UNSIGNED_BYTE,
|
||||
img.bits());
|
||||
|
||||
glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
|
||||
glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);
|
||||
glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
|
||||
glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
|
||||
|
||||
glDisable(GL_TEXTURE_2D);
|
||||
|
||||
dirty = false;
|
||||
}
|
||||
|
||||
glEnable(GL_BLEND);
|
||||
glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
|
||||
glEnable(GL_TEXTURE_2D);
|
||||
|
||||
glBindTexture(GL_TEXTURE_2D, m_texture);
|
||||
|
||||
// texture may be slightly large than svn image, ensure only used area is rendered
|
||||
qreal tw = br.width() * m_scale / textureWidth;
|
||||
qreal th = br.height() * m_scale / textureHeight;
|
||||
|
||||
glBegin(GL_QUADS);
|
||||
glTexCoord2d(0, 0); glVertex3d(br.left(), br.top(), -1);
|
||||
glTexCoord2d(tw, 0); glVertex3d(br.right(), br.top(), -1);
|
||||
glTexCoord2d(tw, th); glVertex3d(br.right(), br.bottom(), -1);
|
||||
glTexCoord2d(0, th); glVertex3d(br.left(), br.bottom(), -1);
|
||||
glEnd();
|
||||
glDisable(GL_TEXTURE_2D);
|
||||
|
||||
painter->endNativePainting();
|
||||
}
|
@ -1,54 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file cachedsvgitem.h
|
||||
* @author Dmytro Poplavskiy Copyright (C) 2011.
|
||||
* @{
|
||||
* @brief OpenGL texture cached SVG item
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef CACHEDSVGITEM_H
|
||||
#define CACHEDSVGITEM_H
|
||||
|
||||
#include <QGraphicsSvgItem>
|
||||
#include <QtOpenGL>
|
||||
#include <QtOpenGL/QGLContext>
|
||||
|
||||
#include "utils_global.h"
|
||||
|
||||
class QGLContext;
|
||||
|
||||
// Cache Svg item as GL Texture.
|
||||
// Texture is regenerated each time item is scaled
|
||||
// but it's reused during rotation, unlike DeviceCoordinateCache mode
|
||||
class QTCREATOR_UTILS_EXPORT CachedSvgItem : public QGraphicsSvgItem {
|
||||
Q_OBJECT
|
||||
public:
|
||||
CachedSvgItem(QGraphicsItem *parent = 0);
|
||||
CachedSvgItem(const QString & fileName, QGraphicsItem *parent = 0);
|
||||
~CachedSvgItem();
|
||||
|
||||
void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget);
|
||||
|
||||
private:
|
||||
QGLContext *m_context;
|
||||
GLuint m_texture;
|
||||
qreal m_scale;
|
||||
};
|
||||
|
||||
#endif // ifndef CACHEDSVGITEM_H
|
@ -31,7 +31,6 @@
|
||||
#include "utils_global.h"
|
||||
|
||||
#include <QSlider>
|
||||
#include <QtDesigner/QDesignerExportWidget>
|
||||
|
||||
class QTCREATOR_UTILS_EXPORT TextBubbleSlider : public QSlider {
|
||||
Q_OBJECT
|
||||
|
@ -1,7 +1,7 @@
|
||||
TEMPLATE = lib
|
||||
TARGET = Utils
|
||||
|
||||
QT += network xml svg opengl gui widgets qml quick quickwidgets
|
||||
QT += network xml svg gui widgets qml quick quickwidgets
|
||||
|
||||
DEFINES += QTCREATOR_UTILS_LIB
|
||||
|
||||
@ -52,7 +52,6 @@ SOURCES += \
|
||||
mytabbedstackwidget.cpp \
|
||||
mytabwidget.cpp \
|
||||
quickwidgetproxy.cpp \
|
||||
cachedsvgitem.cpp \
|
||||
svgimageprovider.cpp \
|
||||
hostosinfo.cpp \
|
||||
logfile.cpp \
|
||||
@ -116,7 +115,6 @@ HEADERS += \
|
||||
mytabbedstackwidget.h \
|
||||
mytabwidget.h \
|
||||
quickwidgetproxy.h \
|
||||
cachedsvgitem.h \
|
||||
svgimageprovider.h \
|
||||
hostosinfo.h \
|
||||
logfile.h \
|
||||
|
@ -28,6 +28,7 @@
|
||||
#include "levelcalibrationmodel.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "calibration/calibrationuiutils.h"
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
#include <attitudestate.h>
|
||||
#include <attitudesettings.h>
|
||||
|
@ -28,6 +28,7 @@
|
||||
#include "sixpointcalibrationmodel.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "calibration/calibrationuiutils.h"
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
#include <math.h>
|
||||
#include <QThread>
|
||||
|
@ -210,8 +210,8 @@ void UdpReceiver::onReadyRead()
|
||||
while (inSocket->hasPendingDatagrams()) {
|
||||
QByteArray datagram;
|
||||
datagram.resize(inSocket->pendingDatagramSize());
|
||||
quint64 datagramSize;
|
||||
datagramSize = inSocket->readDatagram(datagram.data(), datagram.size());
|
||||
// quint64 datagramSize;
|
||||
/*datagramSize =*/ inSocket->readDatagram(datagram.data(), datagram.size());
|
||||
|
||||
processDatagram(datagram);
|
||||
}
|
||||
|
@ -65,7 +65,7 @@
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include <coreplugin/icore.h>
|
||||
#include <coreplugin/threadmanager.h>
|
||||
#include <math.h>
|
||||
#include <cmath>
|
||||
|
||||
const float IL2Simulator::FT2M = 12 * .254;
|
||||
const float IL2Simulator::KT2MPS = 0.514444444;
|
||||
@ -194,13 +194,13 @@ void IL2Simulator::processUpdate(const QByteArray & inp)
|
||||
current.Y = old.Y + (current.dY * current.dT);
|
||||
|
||||
// accelerations (filtered)
|
||||
if (isnan(old.ddX) || isinf(old.ddX)) {
|
||||
if (std::isnan(old.ddX) || std::isinf(old.ddX)) {
|
||||
old.ddX = 0;
|
||||
}
|
||||
if (isnan(old.ddY) || isinf(old.ddY)) {
|
||||
if (std::isnan(old.ddY) || std::isinf(old.ddY)) {
|
||||
old.ddY = 0;
|
||||
}
|
||||
if (isnan(old.ddZ) || isinf(old.ddZ)) {
|
||||
if (std::isnan(old.ddZ) || std::isinf(old.ddZ)) {
|
||||
old.ddZ = 0;
|
||||
}
|
||||
#define SPEED_FILTER 10
|
||||
@ -210,13 +210,13 @@ void IL2Simulator::processUpdate(const QByteArray & inp)
|
||||
|
||||
#define TURN_FILTER 10
|
||||
// turn speeds (filtered)
|
||||
if (isnan(old.dAzimuth) || isinf(old.dAzimuth)) {
|
||||
if (std::isnan(old.dAzimuth) || std::isinf(old.dAzimuth)) {
|
||||
old.dAzimuth = 0;
|
||||
}
|
||||
if (isnan(old.dPitch) || isinf(old.dPitch)) {
|
||||
if (std::isnan(old.dPitch) || std::isinf(old.dPitch)) {
|
||||
old.dPitch = 0;
|
||||
}
|
||||
if (isnan(old.dRoll) || isinf(old.dRoll)) {
|
||||
if (std::isnan(old.dRoll) || std::isinf(old.dRoll)) {
|
||||
old.dRoll = 0;
|
||||
}
|
||||
current.dAzimuth = (angleDifference(current.azimuth, old.azimuth) / current.dT + TURN_FILTER * (old.dAzimuth)) / (TURN_FILTER + 1);
|
||||
|
@ -293,10 +293,8 @@ void modelMapProxy::rowsInserted(const QModelIndex &parent, int first, int last)
|
||||
{
|
||||
Q_UNUSED(parent);
|
||||
|
||||
|
||||
for (int x = first; x < last + 1; x++) {
|
||||
QModelIndex index;
|
||||
WayPointItem *item;
|
||||
internals::PointLatLng latlng;
|
||||
distBearingAltitude distBearing;
|
||||
double altitude;
|
||||
@ -318,9 +316,9 @@ void modelMapProxy::rowsInserted(const QModelIndex &parent, int first, int last)
|
||||
index = model->index(x, flightDataModel::ALTITUDE);
|
||||
altitude = index.data(Qt::DisplayRole).toDouble();
|
||||
if (relative) {
|
||||
item = myMap->WPInsert(distBearing, desc, x);
|
||||
myMap->WPInsert(distBearing, desc, x);
|
||||
} else {
|
||||
item = myMap->WPInsert(latlng, altitude, desc, x);
|
||||
myMap->WPInsert(latlng, altitude, desc, x);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -27,6 +27,7 @@
|
||||
#include "modeluavoproxy.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjecthelper.h"
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
#include <QProgressDialog>
|
||||
#include <math.h>
|
||||
|
@ -25,6 +25,10 @@
|
||||
*/
|
||||
#include "pathactioneditorgadgetwidget.h"
|
||||
#include "ui_pathactioneditor.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
#include "browseritemdelegate.h"
|
||||
|
||||
#include <QDebug>
|
||||
#include <QString>
|
||||
@ -33,9 +37,6 @@
|
||||
#include <QTextEdit>
|
||||
#include <QVBoxLayout>
|
||||
#include <QPushButton>
|
||||
#include "browseritemdelegate.h"
|
||||
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
|
||||
PathActionEditorGadgetWidget::PathActionEditorGadgetWidget(QWidget *parent) : QLabel(parent)
|
||||
{
|
||||
|
@ -35,6 +35,36 @@
|
||||
#include <QQmlContext>
|
||||
#include <QDebug>
|
||||
|
||||
/*
|
||||
* Convert a string to lower camel case.
|
||||
* Handles following cases :
|
||||
* - Property -> property
|
||||
* - MyProperty -> myProperty
|
||||
* - MYProperty -> myProperty
|
||||
* - MY_Property -> my_Property
|
||||
* - MY -> my
|
||||
*/
|
||||
// TODO move to some utility class
|
||||
QString toLowerCamelCase(const QString & name)
|
||||
{
|
||||
QString str = name;
|
||||
|
||||
for (int i = 0; i < str.length(); ++i) {
|
||||
if (str[i].isLower() || !str[i].isLetter()) {
|
||||
break;
|
||||
}
|
||||
if (i > 0 && i < str.length() - 1) {
|
||||
// after first, look ahead one
|
||||
if (str[i + 1].isLower()) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
str[i] = str[i].toLower();
|
||||
}
|
||||
|
||||
return str;
|
||||
}
|
||||
|
||||
PfdQmlContext::PfdQmlContext(QObject *parent) : QObject(parent),
|
||||
m_speedUnit("m/s"),
|
||||
m_speedFactor(1.0),
|
||||
@ -319,7 +349,8 @@ void PfdQmlContext::apply(QQmlContext *context)
|
||||
UAVObject *object = objManager->getObject(objectName);
|
||||
|
||||
if (object) {
|
||||
context->setContextProperty(objectName, object);
|
||||
// expose object with lower camel case name
|
||||
context->setContextProperty(toLowerCamelCase(objectName), object);
|
||||
} else {
|
||||
qWarning() << "PfdQmlContext::apply - failed to load object" << objectName;
|
||||
}
|
||||
|
@ -33,6 +33,9 @@
|
||||
|
||||
#include "$(NAMELC).h"
|
||||
#include "uavobjectfield.h"
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
#include <QtQml>
|
||||
|
||||
const QString $(NAME)::NAME = QString("$(NAME)");
|
||||
const QString $(NAME)::DESCRIPTION = QString("$(DESCRIPTION)");
|
||||
@ -47,7 +50,7 @@ $(NAME)::$(NAME)(): UAVDataObject(OBJID, ISSINGLEINST, ISSETTINGS, NAME)
|
||||
QList<UAVObjectField *> fields;
|
||||
$(FIELDSINIT)
|
||||
// Initialize object
|
||||
initializeFields(fields, (quint8 *)&data, NUMBYTES);
|
||||
initializeFields(fields, (quint8 *)&data_, NUMBYTES);
|
||||
// Set the default field values
|
||||
setDefaultFieldValues();
|
||||
// Set the object description
|
||||
@ -86,7 +89,7 @@ UAVObject::Metadata $(NAME)::getDefaultMetadata()
|
||||
*/
|
||||
void $(NAME)::setDefaultFieldValues()
|
||||
{
|
||||
$(INITFIELDS)
|
||||
$(FIELDSDEFAULT)
|
||||
}
|
||||
|
||||
/**
|
||||
@ -95,7 +98,7 @@ $(INITFIELDS)
|
||||
$(NAME)::DataFields $(NAME)::getData()
|
||||
{
|
||||
QMutexLocker locker(mutex);
|
||||
return data;
|
||||
return data_;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -108,7 +111,7 @@ void $(NAME)::setData(const DataFields& data)
|
||||
Metadata mdata = getMetadata();
|
||||
// Update object if the access mode permits
|
||||
if (UAVObject::GetGcsAccess(mdata) == ACCESS_READWRITE) {
|
||||
this->data = data;
|
||||
this->data_ = data;
|
||||
emit objectUpdatedAuto(this); // trigger object updated event
|
||||
emit objectUpdated(this);
|
||||
}
|
||||
@ -116,7 +119,7 @@ void $(NAME)::setData(const DataFields& data)
|
||||
|
||||
void $(NAME)::emitNotifications()
|
||||
{
|
||||
$(NOTIFY_PROPERTIES_CHANGED)
|
||||
$(NOTIFY_PROPERTIES_CHANGED)
|
||||
}
|
||||
|
||||
/**
|
||||
@ -148,4 +151,11 @@ $(NAME) *$(NAME)::GetInstance(UAVObjectManager *objMngr, quint32 instID)
|
||||
return dynamic_cast<$(NAME) *>(objMngr->getObject($(NAME)::OBJID, instID));
|
||||
}
|
||||
|
||||
/**
|
||||
* Static function to register QML types.
|
||||
*/
|
||||
void $(NAME)::registerQMLTypes() {
|
||||
$(REGISTER_QML_TYPES)
|
||||
}
|
||||
|
||||
$(PROPERTIES_IMPL)
|
||||
|
@ -37,9 +37,6 @@
|
||||
#include <QList>
|
||||
#include <QFile>
|
||||
#include <stdint.h>
|
||||
#include <QXmlStreamWriter>
|
||||
#include <QXmlStreamReader>
|
||||
#include <QJsonObject>
|
||||
|
||||
#include "uavobjectfield.h"
|
||||
|
||||
@ -53,6 +50,9 @@
|
||||
#define UAVOBJ_UPDATE_MODE_MASK 0x3
|
||||
|
||||
class UAVObjectField;
|
||||
class QXmlStreamWriter;
|
||||
class QXmlStreamReader;
|
||||
class QJsonObject;
|
||||
|
||||
class UAVOBJECTS_EXPORT UAVObject : public QObject {
|
||||
Q_OBJECT
|
||||
|
@ -34,13 +34,19 @@
|
||||
#define $(NAMEUC)_H
|
||||
|
||||
#include "uavdataobject.h"
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
class UAVObjectManager;
|
||||
|
||||
$(ENUMS)
|
||||
|
||||
class UAVOBJECTS_EXPORT $(NAME): public UAVDataObject
|
||||
{
|
||||
Q_OBJECT
|
||||
$(PROPERTIES)
|
||||
|
||||
// Deprecated properties
|
||||
$(DEPRECATED_PROPERTIES)
|
||||
|
||||
public:
|
||||
// Field structure
|
||||
typedef struct {
|
||||
@ -49,7 +55,7 @@ $(DATAFIELDS)
|
||||
|
||||
// Field information
|
||||
$(DATAFIELDINFO)
|
||||
|
||||
|
||||
// Constants
|
||||
static const quint32 OBJID = $(OBJIDHEX);
|
||||
static const QString NAME;
|
||||
@ -66,10 +72,12 @@ $(DATAFIELDINFO)
|
||||
void setData(const DataFields& data);
|
||||
Metadata getDefaultMetadata();
|
||||
UAVDataObject* clone(quint32 instID);
|
||||
UAVDataObject* dirtyClone();
|
||||
|
||||
UAVDataObject* dirtyClone();
|
||||
|
||||
static $(NAME)* GetInstance(UAVObjectManager* objMngr, quint32 instID = 0);
|
||||
|
||||
static void registerQMLTypes();
|
||||
|
||||
$(PROPERTY_GETTERS)
|
||||
|
||||
public slots:
|
||||
@ -80,9 +88,9 @@ $(PROPERTY_NOTIFICATIONS)
|
||||
|
||||
private slots:
|
||||
void emitNotifications();
|
||||
|
||||
|
||||
private:
|
||||
DataFields data;
|
||||
DataFields data_;
|
||||
|
||||
void setDefaultFieldValues();
|
||||
|
||||
|
@ -26,9 +26,13 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#include "uavobjectfield.h"
|
||||
|
||||
#include <QtEndian>
|
||||
#include <QDebug>
|
||||
#include <QtWidgets>
|
||||
#include <QXmlStreamWriter>
|
||||
#include <QXmlStreamReader>
|
||||
#include <QJsonObject>
|
||||
#include <QJsonArray>
|
||||
|
||||
UAVObjectField::UAVObjectField(const QString & name, const QString & description, const QString & units, FieldType type, quint32 numElements, const QStringList & options, const QString &limits)
|
||||
{
|
||||
|
@ -30,16 +30,18 @@
|
||||
|
||||
#include "uavobjects_global.h"
|
||||
#include "uavobject.h"
|
||||
|
||||
#include <QStringList>
|
||||
#include <QVariant>
|
||||
#include <QList>
|
||||
#include <QMap>
|
||||
#include <QXmlStreamWriter>
|
||||
#include <QXmlStreamReader>
|
||||
#include <QJsonObject>
|
||||
|
||||
class UAVObject;
|
||||
|
||||
class QXmlStreamWriter;
|
||||
class QXmlStreamReader;
|
||||
class QJsonObject;
|
||||
|
||||
class UAVOBJECTS_EXPORT UAVObjectField : public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
|
@ -3,6 +3,8 @@ TARGET = UAVObjects
|
||||
|
||||
DEFINES += UAVOBJECTS_LIBRARY
|
||||
|
||||
QT += qml
|
||||
|
||||
include(../../plugin.pri)
|
||||
include(uavobjects_dependencies.pri)
|
||||
|
||||
|
@ -27,6 +27,7 @@
|
||||
*/
|
||||
#include "uavobjectsplugin.h"
|
||||
#include "uavobjectsinit.h"
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
UAVObjectsPlugin::UAVObjectsPlugin()
|
||||
{}
|
||||
|
@ -30,8 +30,8 @@
|
||||
|
||||
#include "uavobjects_global.h"
|
||||
#include <extensionsystem/iplugin.h>
|
||||
|
||||
#include <QtPlugin>
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
class UAVOBJECTS_EXPORT UAVObjectsPlugin :
|
||||
public ExtensionSystem::IPlugin {
|
||||
|
@ -2,6 +2,10 @@ import QtQuick 2.4
|
||||
import Pfd 1.0
|
||||
import OsgQtQuick 1.0
|
||||
|
||||
import UAVTalk.AttitudeState 1.0
|
||||
import UAVTalk.HomeLocation 1.0
|
||||
import UAVTalk.GPSPositionSensor 1.0
|
||||
|
||||
OSGViewport {
|
||||
anchors.fill: parent
|
||||
focus: true
|
||||
@ -46,33 +50,33 @@ OSGViewport {
|
||||
position: uavPosition()
|
||||
|
||||
function uavAttitude() {
|
||||
return Qt.vector3d(AttitudeState.Pitch, AttitudeState.Roll, -AttitudeState.Yaw);
|
||||
return Qt.vector3d(attitudeState.pitch, attitudeState.roll, -attitudeState.yaw);
|
||||
}
|
||||
|
||||
function uavPosition() {
|
||||
switch(GPSPositionSensor.Status) {
|
||||
case 2: // Fix2D
|
||||
case 3: // Fix3D
|
||||
switch(gpsPositionSensor.status) {
|
||||
case Status.Fix2D:
|
||||
case Status.Fix3D:
|
||||
return uavGPSPosition();
|
||||
case 0: // NoGPS
|
||||
case 1: // NoFix
|
||||
case Status.NoFix:
|
||||
case Status.NoGPS:
|
||||
default:
|
||||
return (HomeLocation.Set == 1) ? uavHomePosition() : uavDefaultPosition();
|
||||
return (homeLocation.set == Set.True) ? uavHomePosition() : uavDefaultPosition();
|
||||
}
|
||||
}
|
||||
|
||||
function uavGPSPosition() {
|
||||
return Qt.vector3d(
|
||||
GPSPositionSensor.Longitude / 10000000.0,
|
||||
GPSPositionSensor.Latitude / 10000000.0,
|
||||
GPSPositionSensor.Altitude);
|
||||
gpsPositionSensor.longitude / 10000000.0,
|
||||
gpsPositionSensor.latitude / 10000000.0,
|
||||
gpsPositionSensor.altitude);
|
||||
}
|
||||
|
||||
function uavHomePosition() {
|
||||
return Qt.vector3d(
|
||||
HomeLocation.Longitude / 10000000.0,
|
||||
HomeLocation.Latitude / 10000000.0,
|
||||
HomeLocation.Altitude);
|
||||
homeLocation.longitude / 10000000.0,
|
||||
homeLocation.latitude / 10000000.0,
|
||||
homeLocation.altitude);
|
||||
}
|
||||
|
||||
function uavDefaultPosition() {
|
||||
|
@ -1,6 +1,8 @@
|
||||
import QtQuick 2.4
|
||||
import OsgQtQuick 1.0
|
||||
|
||||
import UAVTalk.AttitudeState 1.0
|
||||
|
||||
Item {
|
||||
|
||||
OSGViewport {
|
||||
@ -25,7 +27,7 @@ Item {
|
||||
OSGTransformNode {
|
||||
id: transformNode
|
||||
modelData: fileNode
|
||||
rotate: Qt.vector3d(AttitudeState.Pitch, AttitudeState.Roll, -AttitudeState.Yaw)
|
||||
rotate: Qt.vector3d(attitudeState.pitch, attitudeState.roll, -attitudeState.yaw)
|
||||
//scale: Qt.vector3d(0.001, 0.001, 0.001)
|
||||
}
|
||||
|
||||
|
@ -1,10 +1,14 @@
|
||||
import QtQuick 2.4
|
||||
|
||||
import UAVTalk.PositionState 1.0
|
||||
import UAVTalk.NedAccel 1.0
|
||||
import UAVTalk.PathDesired 1.0
|
||||
|
||||
Item {
|
||||
id: sceneItem
|
||||
property variant sceneSize
|
||||
|
||||
property real altitude : -qmlWidget.altitudeFactor * PositionState.Down
|
||||
property real altitude : -qmlWidget.altitudeFactor * positionState.down
|
||||
|
||||
SvgElementImage {
|
||||
id: altitude_window
|
||||
@ -60,7 +64,7 @@ Item {
|
||||
elementName: "altitude-vector"
|
||||
sceneSize: sceneItem.sceneSize
|
||||
|
||||
height: -NedAccel.Down * altitude_scale.height/10
|
||||
height: -nedAccel.down * altitude_scale.height / 10
|
||||
|
||||
anchors.left: parent.left
|
||||
anchors.bottom: parent.verticalCenter
|
||||
@ -70,12 +74,12 @@ Item {
|
||||
id: altitude_waypoint
|
||||
elementName: "altitude-waypoint"
|
||||
sceneSize: sceneItem.sceneSize
|
||||
visible: PathDesired.End_Down !== 0.0
|
||||
visible: (pathDesired.endDown != 0.0)
|
||||
|
||||
anchors.left: parent.left
|
||||
anchors.verticalCenter: parent.verticalCenter
|
||||
|
||||
anchors.verticalCenterOffset: -altitude_scale.height/10 * (PositionState.Down - PathDesired.End_Down) * qmlWidget.altitudeFactor
|
||||
anchors.verticalCenterOffset: -altitude_scale.height / 10 * (positionState.Down - pathDesired.endDown) * qmlWidget.altitudeFactor
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1,5 +1,12 @@
|
||||
import QtQuick 2.4
|
||||
|
||||
import UAVTalk.AttitudeState 1.0
|
||||
import UAVTalk.PositionState 1.0
|
||||
import UAVTalk.PathDesired 1.0
|
||||
import UAVTalk.TakeOffLocation 1.0
|
||||
|
||||
import "common.js" as Utils
|
||||
|
||||
Item {
|
||||
id: sceneItem
|
||||
property variant sceneSize
|
||||
@ -31,7 +38,7 @@ Item {
|
||||
x: Math.floor(scaledBounds.x * sceneItem.width)
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
|
||||
rotation: -AttitudeState.Yaw
|
||||
rotation: -attitudeState.yaw
|
||||
transformOrigin: Item.Center
|
||||
}
|
||||
|
||||
@ -44,12 +51,12 @@ Item {
|
||||
x: Math.floor(scaledBounds.x * sceneItem.width)
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
|
||||
property real home_degrees: 180/3.1415 * Math.atan2(TakeOffLocation.East - PositionState.East, TakeOffLocation.North - PositionState.North)
|
||||
property real home_degrees: 180 / 3.1415 * Math.atan2(takeOffLocation.east - positionState.east, takeOffLocation.north - positionState.north)
|
||||
|
||||
rotation: -AttitudeState.Yaw + home_degrees
|
||||
rotation: -attitudeState.yaw + home_degrees
|
||||
transformOrigin: Item.Bottom
|
||||
|
||||
visible: TakeOffLocation.Status == 0
|
||||
visible: (takeOffLocation.status == Status.Valid)
|
||||
}
|
||||
|
||||
SvgElementImage {
|
||||
@ -61,12 +68,13 @@ Item {
|
||||
x: Math.floor(scaledBounds.x * sceneItem.width)
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
|
||||
property real course_degrees: 180/3.1415 * Math.atan2(PathDesired.End_East - PositionState.East, PathDesired.End_North - PositionState.North)
|
||||
property real course_degrees: 180 / 3.1415 * Math.atan2(pathDesired.endEast - positionState.east, pathDesired.endNorth - positionState.north)
|
||||
|
||||
rotation: -AttitudeState.Yaw + course_degrees
|
||||
rotation: -attitudeState.yaw + course_degrees
|
||||
transformOrigin: Item.Center
|
||||
|
||||
visible: PathDesired.End_East !== 0.0 && PathDesired.End_East !== 0.0
|
||||
// FIXME : why test endEast twice?
|
||||
visible: ((pathDesired.endEast != 0.0) && (pathDesired.endEast != 0.0))
|
||||
}
|
||||
|
||||
Item {
|
||||
@ -81,7 +89,7 @@ Item {
|
||||
|
||||
Text {
|
||||
id: compass_text
|
||||
text: Math.floor(AttitudeState.Yaw).toFixed()
|
||||
text: Math.floor(attitudeState.yaw).toFixed()
|
||||
color: "white"
|
||||
font {
|
||||
family: pt_bold.name
|
||||
|
@ -1,5 +1,18 @@
|
||||
import QtQuick 2.4
|
||||
|
||||
import UAVTalk.HwSettings 1.0
|
||||
import UAVTalk.SystemAlarms 1.0
|
||||
import UAVTalk.VelocityState 1.0
|
||||
import UAVTalk.TakeOffLocation 1.0
|
||||
import UAVTalk.PathDesired 1.0
|
||||
import UAVTalk.WaypointActive 1.0
|
||||
import UAVTalk.GPSPositionSensor 1.0 as GPSPositionSensor
|
||||
import UAVTalk.GPSSatellites 1.0
|
||||
import UAVTalk.FlightBatterySettings 1.0
|
||||
import UAVTalk.FlightBatteryState 1.0
|
||||
|
||||
import "common.js" as Utils
|
||||
|
||||
Item {
|
||||
id: info
|
||||
property variant sceneSize
|
||||
@ -18,29 +31,29 @@ Item {
|
||||
|
||||
property bool init_dist: false
|
||||
|
||||
property real home_heading: 180/3.1415 * Math.atan2(TakeOffLocation.East - PositionState.East,
|
||||
TakeOffLocation.North - PositionState.North)
|
||||
property real home_heading: 180 / 3.1415 * Math.atan2(takeOffLocation.east - positionState.east,
|
||||
takeOffLocation.north - positionState.north)
|
||||
|
||||
property real home_distance: Math.sqrt(Math.pow((TakeOffLocation.East - PositionState.East),2) +
|
||||
Math.pow((TakeOffLocation.North - PositionState.North),2))
|
||||
property real home_distance: Math.sqrt(Math.pow((takeOffLocation.east - positionState.east), 2) +
|
||||
Math.pow((takeOffLocation.north - positionState.north), 2))
|
||||
|
||||
property real wp_heading: 180/3.1415 * Math.atan2(PathDesired.End_East - PositionState.East,
|
||||
PathDesired.End_North - PositionState.North)
|
||||
property real wp_heading: 180 / 3.1415 * Math.atan2(pathDesired.endEast - positionState.east,
|
||||
pathDesired.endNorth - positionState.north)
|
||||
|
||||
property real wp_distance: Math.sqrt(Math.pow((PathDesired.End_East - PositionState.East),2) +
|
||||
Math.pow(( PathDesired.End_North - PositionState.North),2))
|
||||
property real wp_distance: Math.sqrt(Math.pow((pathDesired.endEast - positionState.east), 2) +
|
||||
Math.pow((pathDesired.endNorth - positionState.north), 2))
|
||||
|
||||
property real current_velocity: Math.sqrt(Math.pow(VelocityState.North,2)+Math.pow(VelocityState.East,2))
|
||||
property real current_velocity: Math.sqrt(Math.pow(velocityState.north, 2) + Math.pow(velocityState.east, 2))
|
||||
|
||||
property real home_eta: (home_distance > 0 && current_velocity > 0 ? Math.round(home_distance/current_velocity) : 0)
|
||||
property real home_eta: (home_distance > 0 && current_velocity > 0 ? Math.round(home_distance / current_velocity) : 0)
|
||||
property real home_eta_h: (home_eta > 0 ? Math.floor(home_eta / 3600) : 0 )
|
||||
property real home_eta_m: (home_eta > 0 ? Math.floor((home_eta - home_eta_h*3600)/60) : 0)
|
||||
property real home_eta_s: (home_eta > 0 ? Math.floor(home_eta - home_eta_h*3600 - home_eta_m*60) : 0)
|
||||
property real home_eta_m: (home_eta > 0 ? Math.floor((home_eta - home_eta_h * 3600) / 60) : 0)
|
||||
property real home_eta_s: (home_eta > 0 ? Math.floor(home_eta - home_eta_h * 3600 - home_eta_m * 60) : 0)
|
||||
|
||||
property real wp_eta: (wp_distance > 0 && current_velocity > 0 ? Math.round(wp_distance/current_velocity) : 0)
|
||||
property real wp_eta_h: (wp_eta > 0 ? Math.floor(wp_eta / 3600) : 0 )
|
||||
property real wp_eta_m: (wp_eta > 0 ? Math.floor((wp_eta - wp_eta_h*3600)/60) : 0)
|
||||
property real wp_eta_s: (wp_eta > 0 ? Math.floor(wp_eta - wp_eta_h*3600 - wp_eta_m*60) : 0)
|
||||
property real wp_eta_m: (wp_eta > 0 ? Math.floor((wp_eta - wp_eta_h * 3600) / 60) : 0)
|
||||
property real wp_eta_s: (wp_eta > 0 ? Math.floor(wp_eta - wp_eta_h * 3600 - wp_eta_m * 60) : 0)
|
||||
|
||||
function reset_distance() {
|
||||
total_distance = 0;
|
||||
@ -48,8 +61,8 @@ Item {
|
||||
|
||||
function compute_distance(posEast,posNorth) {
|
||||
if (total_distance == 0 && !init_dist) { init_dist = "true"; posEast_old = posEast; posNorth_old = posNorth; }
|
||||
if (posEast > posEast_old+3 || posEast < posEast_old-3 || posNorth > posNorth_old+3 || posNorth < posNorth_old-3) {
|
||||
total_distance += Math.sqrt(Math.pow((posEast - posEast_old ),2) + Math.pow((posNorth - posNorth_old),2));
|
||||
if (posEast > posEast_old+3 || posEast < posEast_old - 3 || posNorth > posNorth_old + 3 || posNorth < posNorth_old - 3) {
|
||||
total_distance += Math.sqrt(Math.pow((posEast - posEast_old ), 2) + Math.pow((posNorth - posNorth_old), 2));
|
||||
total_distance_km = total_distance / 1000;
|
||||
|
||||
posEast_old = posEast;
|
||||
@ -58,15 +71,6 @@ Item {
|
||||
}
|
||||
}
|
||||
|
||||
function formatTime(time) {
|
||||
if (time == 0)
|
||||
return "00"
|
||||
if (time < 10)
|
||||
return "0" + time;
|
||||
else
|
||||
return time.toString();
|
||||
}
|
||||
|
||||
// End Functions
|
||||
//
|
||||
// Start Drawing
|
||||
@ -84,16 +88,14 @@ Item {
|
||||
//
|
||||
|
||||
property real bar_width: (info_bg.height + info_bg.width) / 110
|
||||
property int satsInView: String(GPSSatellites.SatsInView).charCodeAt(0)
|
||||
property variant gps_tooltip: "Altitude : "+GPSPositionSensor.Altitude.toFixed(2) +"m\n"+
|
||||
"H/V/P DOP : "+GPSPositionSensor.HDOP.toFixed(2)+"/"+GPSPositionSensor.VDOP.toFixed(2)+"/"+GPSPositionSensor.PDOP.toFixed(2)+"m\n"+
|
||||
satsInView+" Sats in view"
|
||||
property int satsInView: gpsSatellites.satsInView
|
||||
property variant gps_tooltip: "Altitude : " + gpsPositionSensor.altitude.toFixed(2) + "m\n" +
|
||||
"H/V/P DOP : " + gpsPositionSensor.hdop.toFixed(2) + "/" + gpsPositionSensor.vdop.toFixed(2) + "/" + gpsPositionSensor.pdop.toFixed(2) + "m\n" +
|
||||
satsInView + " Sats in view"
|
||||
|
||||
Repeater {
|
||||
id: satNumberBar
|
||||
//smooth: true
|
||||
// hack, qml/js treats qint8 as a char, necessary to convert it back to integer value
|
||||
property int satNumber : String(GPSPositionSensor.Satellites).charCodeAt(0)
|
||||
property int satNumber : gpsPositionSensor.satellites
|
||||
|
||||
model: 13
|
||||
Rectangle {
|
||||
@ -105,9 +107,9 @@ Item {
|
||||
text: gps_tooltip
|
||||
}
|
||||
|
||||
x: Math.round((bar_width*4.5) + (bar_width * 1.6 * index))
|
||||
x: Math.round((bar_width * 4.5) + (bar_width * 1.6 * index))
|
||||
height: bar_width * index * 0.6
|
||||
y: (bar_width*8) - height
|
||||
y: (bar_width * 8) - height
|
||||
color: "green"
|
||||
opacity: satNumberBar.satNumber >= minSatNumber ? 1 : 0.4
|
||||
}
|
||||
@ -122,10 +124,10 @@ Item {
|
||||
}
|
||||
|
||||
Text {
|
||||
property int satNumber : String(GPSPositionSensor.Satellites).charCodeAt(0)
|
||||
property int satNumber : gpsPositionSensor.satellites
|
||||
|
||||
text: [satNumber > 5 ? " " + satNumber.toString() + " sats - " : ""] +
|
||||
["NO GPS", "NO FIX", "2D", "3D"][GPSPositionSensor.Status]
|
||||
text: [satNumber > 5 ? " " + satNumber.toString() + " sats - " : ""] +
|
||||
["NO GPS", "NO FIX", "2D", "3D"][gpsPositionSensor.status]
|
||||
anchors.centerIn: parent
|
||||
font.pixelSize: parent.height*1.3
|
||||
font.family: pt_bold.name
|
||||
@ -154,7 +156,7 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
visible: SystemAlarms.Alarm_PathPlan == 1
|
||||
visible: (systemAlarms.alarmPathPlan == Alarm.OK)
|
||||
}
|
||||
|
||||
SvgElementPositionItem {
|
||||
@ -163,7 +165,7 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
visible: SystemAlarms.Alarm_PathPlan == 1
|
||||
visible: (systemAlarms.alarmPathPlan == Alarm.OK)
|
||||
|
||||
Text {
|
||||
text: " "+wp_heading.toFixed(1)+"°"
|
||||
@ -184,7 +186,7 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
visible: SystemAlarms.Alarm_PathPlan == 1
|
||||
visible: (systemAlarms.alarmPathPlan == Alarm.OK)
|
||||
|
||||
Text {
|
||||
text: " "+wp_distance.toFixed(0)+" m"
|
||||
@ -205,7 +207,7 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
visible: SystemAlarms.Alarm_PathPlan == 1
|
||||
visible: (systemAlarms.alarmPathPlan == Alarm.OK)
|
||||
|
||||
MouseArea { id: total_dist_mouseArea; anchors.fill: parent; cursorShape: Qt.PointingHandCursor; onClicked: reset_distance()}
|
||||
|
||||
@ -223,7 +225,7 @@ Item {
|
||||
|
||||
Timer {
|
||||
interval: 1000; running: true; repeat: true;
|
||||
onTriggered: {if (GPSPositionSensor.Status == 3) compute_distance(PositionState.East,PositionState.North)}
|
||||
onTriggered: { if (gpsPositionSensor.status == GPSPositionSensor.Status.Fix3D) compute_distance(positionState.east, positionState.north) }
|
||||
}
|
||||
}
|
||||
|
||||
@ -233,10 +235,10 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
visible: SystemAlarms.Alarm_PathPlan == 1
|
||||
visible: (systemAlarms.alarmPathPlan == Alarm.OK)
|
||||
|
||||
Text {
|
||||
text: formatTime(wp_eta_h) + ":" + formatTime(wp_eta_m) + ":" + formatTime(wp_eta_s)
|
||||
text: Utils.formatTime(wp_eta_h) + ":" + Utils.formatTime(wp_eta_m) + ":" + Utils.formatTime(wp_eta_s)
|
||||
anchors.centerIn: parent
|
||||
color: "cyan"
|
||||
|
||||
@ -254,10 +256,10 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
visible: SystemAlarms.Alarm_PathPlan == 1
|
||||
visible: (systemAlarms.alarmPathPlan == Alarm.OK)
|
||||
|
||||
Text {
|
||||
text: (WaypointActive.Index+1)+" / "+PathPlan.WaypointCount
|
||||
text: (waypointActive.index + 1) + " / " + pathPlan.waypointCount
|
||||
anchors.centerIn: parent
|
||||
color: "cyan"
|
||||
|
||||
@ -275,10 +277,10 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
visible: SystemAlarms.Alarm_PathPlan == 1
|
||||
visible: (systemAlarms.alarmPathPlan == Alarm.OK)
|
||||
|
||||
Text {
|
||||
text: ["GOTO ENDPOINT","FOLLOW VECTOR","CIRCLE RIGHT","CIRCLE LEFT","FIXED ATTITUDE","SET ACCESSORY","DISARM ALARM","LAND","BRAKE","VELOCITY","AUTO TAKEOFF"][PathDesired.Mode]
|
||||
text: ["GOTO ENDPOINT","FOLLOW VECTOR","CIRCLE RIGHT","CIRCLE LEFT","FIXED ATTITUDE","SET ACCESSORY","DISARM ALARM","LAND","BRAKE","VELOCITY","AUTO TAKEOFF"][pathDesired.mode]
|
||||
anchors.centerIn: parent
|
||||
color: "cyan"
|
||||
|
||||
@ -301,11 +303,11 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
y: scaledBounds.y * sceneItem.height
|
||||
visible: (SystemAlarms.Alarm_PathPlan != 1) && (HwSettings.OptionalModules_Battery == 1)
|
||||
visible: ((systemAlarms.alarmPathPlan != Alarm.OK) && (hwSettings.optionalModulesBattery == OptionalModules.Enabled))
|
||||
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
color: FlightBatterySettings.NbCells > 0 ? info.batColors[SystemAlarms.Alarm_Battery] : "black"
|
||||
color: (flightBatterySettings.nbCells > 0) ? info.batColors[systemAlarms.alarmBattery] : "black"
|
||||
|
||||
}
|
||||
}
|
||||
@ -316,7 +318,7 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
visible: (SystemAlarms.Alarm_PathPlan != 1) && (HwSettings.OptionalModules_Battery == 1)
|
||||
visible: ((systemAlarms.alarmPathPlan != Alarm.OK) && (hwSettings.optionalModulesBattery == OptionalModules.Enabled))
|
||||
}
|
||||
|
||||
SvgElementPositionItem {
|
||||
@ -327,14 +329,14 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
y: scaledBounds.y * sceneItem.height
|
||||
visible: (SystemAlarms.Alarm_PathPlan != 1) && (HwSettings.OptionalModules_Battery == 1)
|
||||
visible: ((systemAlarms.alarmPathPlan != Alarm.OK) && (hwSettings.optionalModulesBattery == OptionalModules.Enabled))
|
||||
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
color: "transparent"
|
||||
|
||||
Text {
|
||||
text: FlightBatteryState.Voltage.toFixed(2)
|
||||
text: flightBatteryState.voltage.toFixed(2)
|
||||
anchors.centerIn: parent
|
||||
color: "white"
|
||||
font {
|
||||
@ -354,14 +356,14 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
y: scaledBounds.y * sceneItem.height
|
||||
visible: (SystemAlarms.Alarm_PathPlan != 1) && (HwSettings.OptionalModules_Battery == 1)
|
||||
visible: ((systemAlarms.alarmPathPlan != Alarm.OK) && (hwSettings.optionalModulesBattery == OptionalModules.Enabled))
|
||||
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
color: "transparent"
|
||||
|
||||
Text {
|
||||
text: FlightBatteryState.Current.toFixed(2)
|
||||
text: flightBatteryState.current.toFixed(2)
|
||||
anchors.centerIn: parent
|
||||
color: "white"
|
||||
font {
|
||||
@ -381,7 +383,7 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
y: scaledBounds.y * sceneItem.height
|
||||
visible: (SystemAlarms.Alarm_PathPlan != 1) && (HwSettings.OptionalModules_Battery == 1)
|
||||
visible: ((systemAlarms.alarmPathPlan != Alarm.OK) && (hwSettings.optionalModulesBattery == OptionalModules.Enabled))
|
||||
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
@ -390,23 +392,23 @@ Item {
|
||||
text: "Reset consumed energy"
|
||||
}
|
||||
|
||||
MouseArea {
|
||||
id: reset_consumed_energy_mouseArea;
|
||||
MouseArea {
|
||||
id: reset_consumed_energy_mouseArea;
|
||||
anchors.fill: parent;
|
||||
cursorShape: Qt.PointingHandCursor;
|
||||
cursorShape: Qt.PointingHandCursor;
|
||||
onClicked: qmlWidget.resetConsumedEnergy();
|
||||
}
|
||||
|
||||
// Alarm based on FlightBatteryState.EstimatedFlightTime < 120s orange, < 60s red
|
||||
color: (FlightBatteryState.EstimatedFlightTime <= 120 && FlightBatteryState.EstimatedFlightTime > 60 ? "orange" :
|
||||
(FlightBatteryState.EstimatedFlightTime <= 60 ? "red": info.batColors[SystemAlarms.Alarm_Battery]))
|
||||
// Alarm based on flightBatteryState.estimatedFlightTime < 120s orange, < 60s red
|
||||
color: ((flightBatteryState.estimatedFlightTime <= 120) && (flightBatteryState.estimatedFlightTime > 60)) ? "orange" :
|
||||
(flightBatteryState.estimatedFlightTime <= 60) ? "red" : info.batColors[systemAlarms.alarmBattery]
|
||||
|
||||
border.color: "white"
|
||||
border.width: topbattery_volt.width * 0.01
|
||||
radius: border.width * 4
|
||||
|
||||
Text {
|
||||
text: FlightBatteryState.ConsumedEnergy.toFixed(0)
|
||||
text: flightBatteryState.consumedEnergy.toFixed(0)
|
||||
anchors.centerIn: parent
|
||||
color: "white"
|
||||
font {
|
||||
@ -427,7 +429,7 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
visible: SystemAlarms.Alarm_PathPlan != 1
|
||||
visible: (systemAlarms.alarmPathPlan != Alarm.OK)
|
||||
}
|
||||
|
||||
SvgElementPositionItem {
|
||||
@ -436,7 +438,7 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
visible: SystemAlarms.Alarm_PathPlan != 1
|
||||
visible: (systemAlarms.alarmPathPlan != Alarm.OK)
|
||||
|
||||
TooltipArea {
|
||||
text: "Reset distance counter"
|
||||
@ -458,7 +460,7 @@ Item {
|
||||
|
||||
Timer {
|
||||
interval: 1000; running: true; repeat: true;
|
||||
onTriggered: {if (GPSPositionSensor.Status == 3) compute_distance(PositionState.East,PositionState.North)}
|
||||
onTriggered: { if (gpsPositionSensor.status == GPSPositionSensor.Status.Fix3D) compute_distance(positionState.east, positionState.north) }
|
||||
}
|
||||
}
|
||||
|
||||
@ -477,7 +479,7 @@ Item {
|
||||
|
||||
states: State {
|
||||
name: "fading"
|
||||
when: TakeOffLocation.Status == 0
|
||||
when: (takeOffLocation.status == Status.Valid)
|
||||
PropertyChanges { target: home_bg; x: Math.floor(scaledBounds.x * sceneItem.width) - home_bg.width; }
|
||||
}
|
||||
|
||||
@ -498,7 +500,7 @@ Item {
|
||||
|
||||
states: State {
|
||||
name: "fading_heading"
|
||||
when: TakeOffLocation.Status == 0
|
||||
when: (takeOffLocation.status == Status.Valid)
|
||||
PropertyChanges { target: home_heading_text; x: Math.floor(scaledBounds.x * sceneItem.width) - home_bg.width; }
|
||||
}
|
||||
|
||||
@ -529,7 +531,7 @@ Item {
|
||||
|
||||
states: State {
|
||||
name: "fading_distance"
|
||||
when: TakeOffLocation.Status == 0
|
||||
when: (takeOffLocation.status == Status.Valid)
|
||||
PropertyChanges { target: home_distance_text; x: Math.floor(scaledBounds.x * sceneItem.width) - home_bg.width; }
|
||||
}
|
||||
|
||||
@ -560,7 +562,7 @@ Item {
|
||||
|
||||
states: State {
|
||||
name: "fading_distance"
|
||||
when: TakeOffLocation.Status == 0
|
||||
when: (takeOffLocation.status == Status.Valid)
|
||||
PropertyChanges { target: home_eta_text; x: Math.floor(scaledBounds.x * sceneItem.width) - home_bg.width; }
|
||||
}
|
||||
|
||||
@ -571,7 +573,7 @@ Item {
|
||||
}
|
||||
|
||||
Text {
|
||||
text: formatTime(home_eta_h) + ":" + formatTime(home_eta_m) + ":" + formatTime(home_eta_s)
|
||||
text: Utils.formatTime(home_eta_h) + ":" + Utils.formatTime(home_eta_m) + ":" + Utils.formatTime(home_eta_s)
|
||||
anchors.centerIn: parent
|
||||
color: "cyan"
|
||||
font {
|
||||
|
@ -1,22 +1,25 @@
|
||||
import QtQuick 2.4
|
||||
|
||||
import UAVTalk.SystemSettings 1.0
|
||||
import UAVTalk.RevoSettings 1.0
|
||||
import UAVTalk.SystemAlarms 1.0
|
||||
import UAVTalk.FlightBatteryState 1.0
|
||||
import UAVTalk.GPSPositionSensor 1.0
|
||||
import UAVTalk.ManualControlCommand 1.0
|
||||
import UAVTalk.MagState 1.0
|
||||
import UAVTalk.ReceiverStatus 1.0
|
||||
import UAVTalk.OPLinkStatus 1.0
|
||||
|
||||
import "common.js" as Utils
|
||||
|
||||
Item {
|
||||
id: panels
|
||||
property variant sceneSize
|
||||
|
||||
property real est_flight_time: Math.round(FlightBatteryState.EstimatedFlightTime)
|
||||
property real est_time_h: (est_flight_time > 0 ? Math.floor(est_flight_time / 3600) : 0 )
|
||||
property real est_time_m: (est_flight_time > 0 ? Math.floor((est_flight_time - est_time_h*3600)/60) : 0)
|
||||
property real est_time_s: (est_flight_time > 0 ? Math.floor(est_flight_time - est_time_h*3600 - est_time_m*60) : 0)
|
||||
|
||||
function formatTime(time) {
|
||||
if (time == 0)
|
||||
return "00"
|
||||
if (time < 10)
|
||||
return "0" + time;
|
||||
else
|
||||
return time.toString();
|
||||
}
|
||||
property real est_flight_time: Math.round(flightBatteryState.estimatedFlightTime)
|
||||
property real est_time_h: (est_flight_time > 0) ? Math.floor(est_flight_time / 3600) : 0
|
||||
property real est_time_m: (est_flight_time > 0) ? Math.floor((est_flight_time - est_time_h * 3600) / 60) : 0
|
||||
property real est_time_s: (est_flight_time > 0) ? Math.floor(est_flight_time - est_time_h * 3600 - est_time_m * 60) : 0
|
||||
|
||||
//
|
||||
// Panel functions
|
||||
@ -80,16 +83,16 @@ Item {
|
||||
|
||||
property real smeter_angle
|
||||
|
||||
property real memory_free : SystemStats.HeapRemaining > 1024 ? SystemStats.HeapRemaining / 1024 : SystemStats.HeapRemaining
|
||||
property real memory_free : (systemStats.heapRemaining > 1024) ? systemStats.heapRemaining / 1024 : systemStats.heapRemaining
|
||||
|
||||
// Needed to get correctly int8 value
|
||||
property int cpuTemp : SystemStats.CPUTemp
|
||||
property int cpuTemp : systemStats.cpuTemp
|
||||
|
||||
// Needed to get correctly int8 value, reset value (-127) on disconnect
|
||||
property int oplm0_db: telemetry_link == 1 ? OPLinkStatus.PairSignalStrengths_0 : -127
|
||||
property int oplm1_db: telemetry_link == 1 ? OPLinkStatus.PairSignalStrengths_1 : -127
|
||||
property int oplm2_db: telemetry_link == 1 ? OPLinkStatus.PairSignalStrengths_2 : -127
|
||||
property int oplm3_db: telemetry_link == 1 ? OPLinkStatus.PairSignalStrengths_3 : -127
|
||||
property int oplm0_db: (telemetry_link == 1) ? opLinkStatus.pairSignalStrengths0 : -127
|
||||
property int oplm1_db: (telemetry_link == 1) ? opLinkStatus.pairSignalStrengths1 : -127
|
||||
property int oplm2_db: (telemetry_link == 1) ? opLinkStatus.pairSignalStrengths2 : -127
|
||||
property int oplm3_db: (telemetry_link == 1) ? opLinkStatus.pairSignalStrengths3 : -127
|
||||
|
||||
property real telemetry_sum
|
||||
property real telemetry_sum_old
|
||||
@ -98,9 +101,10 @@ Item {
|
||||
// Hack : check if telemetry is active. Works with real link and log replay
|
||||
|
||||
function telemetry_check() {
|
||||
telemetry_sum = OPLinkStatus.RXRate + OPLinkStatus.RXRate
|
||||
// FIXME : why rxRate + rxRate?
|
||||
telemetry_sum = opLinkStatus.rxRate + opLinkStatus.rxRate
|
||||
|
||||
if (telemetry_sum != telemetry_sum_old || OPLinkStatus.LinkState == 4) {
|
||||
if (telemetry_sum != telemetry_sum_old || (opLinkStatus.linkState == LinkState.Connected)) {
|
||||
telemetry_link = 1
|
||||
} else {
|
||||
telemetry_link = 0
|
||||
@ -141,7 +145,7 @@ Item {
|
||||
}
|
||||
|
||||
property int smeter_filter
|
||||
property variant oplm_pair_id : OPLinkStatus.PairIDs_0
|
||||
property variant oplm_pair_id : opLinkStatus.pairIDs0
|
||||
|
||||
function select_oplm(index){
|
||||
smeter_filter0.running = false;
|
||||
@ -153,22 +157,22 @@ Item {
|
||||
case 0:
|
||||
smeter_filter0.running = true;
|
||||
smeter_filter = 0;
|
||||
oplm_pair_id = OPLinkStatus.PairIDs_0
|
||||
oplm_pair_id = opLinkStatus.pairIDs0
|
||||
break;
|
||||
case 1:
|
||||
smeter_filter1.running = true;
|
||||
smeter_filter = 1;
|
||||
oplm_pair_id = OPLinkStatus.PairIDs_1
|
||||
oplm_pair_id = opLinkStatus.pairIDs1
|
||||
break;
|
||||
case 2:
|
||||
smeter_filter2.running = true;
|
||||
smeter_filter = 2;
|
||||
oplm_pair_id = OPLinkStatus.PairIDs_2
|
||||
oplm_pair_id = opLinkStatus.pairIDs2
|
||||
break;
|
||||
case 3:
|
||||
smeter_filter3.running = true;
|
||||
smeter_filter = 3;
|
||||
oplm_pair_id = OPLinkStatus.PairIDs_3
|
||||
oplm_pair_id = opLinkStatus.pairIDs3
|
||||
break;
|
||||
}
|
||||
}
|
||||
@ -218,7 +222,7 @@ Item {
|
||||
elementName: "panel-open-icon"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: close_bg.z+1
|
||||
z: close_bg.z + 1
|
||||
opacity: show_panels == true ? 0 : 1
|
||||
|
||||
states: State {
|
||||
@ -241,7 +245,7 @@ Item {
|
||||
elementName: "close-panel-mousearea"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: close_bg.z+100
|
||||
z: close_bg.z + 100
|
||||
|
||||
TooltipArea {
|
||||
text: show_panels == true ? "Close panels" : "Open panels"
|
||||
@ -250,7 +254,7 @@ Item {
|
||||
MouseArea {
|
||||
id: hidedisp_close;
|
||||
anchors.fill: parent;
|
||||
cursorShape: Qt.PointingHandCursor
|
||||
cursorShape: Qt.PointingHandCursor
|
||||
onClicked: close_panels()
|
||||
}
|
||||
|
||||
@ -297,7 +301,7 @@ Item {
|
||||
elementName: "rc-input-labels"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: rc_input_bg.z+1
|
||||
z: rc_input_bg.z + 1
|
||||
|
||||
states: State {
|
||||
name: "fading"
|
||||
@ -306,9 +310,9 @@ Item {
|
||||
}
|
||||
|
||||
transitions: Transition {
|
||||
SequentialAnimation {
|
||||
PropertyAnimation { property: "x"; easing.type: anim_type; easing.amplitude: anim_amplitude; easing.period: anim_period; duration: duration_value }
|
||||
}
|
||||
SequentialAnimation {
|
||||
PropertyAnimation { property: "x"; easing.type: anim_type; easing.amplitude: anim_amplitude; easing.period: anim_period; duration: duration_value }
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -317,7 +321,7 @@ Item {
|
||||
elementName: "rc-input-panel-mousearea"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: rc_input_bg.z+1
|
||||
z: rc_input_bg.z + 1
|
||||
|
||||
TooltipArea {
|
||||
text: "RC panel"
|
||||
@ -337,9 +341,9 @@ Item {
|
||||
}
|
||||
|
||||
transitions: Transition {
|
||||
SequentialAnimation {
|
||||
PropertyAnimation { property: "x"; easing.type: anim_type; easing.amplitude: anim_amplitude; easing.period: anim_period; duration: duration_value }
|
||||
}
|
||||
SequentialAnimation {
|
||||
PropertyAnimation { property: "x"; easing.type: anim_type; easing.amplitude: anim_amplitude; easing.period: anim_period; duration: duration_value }
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -350,7 +354,7 @@ Item {
|
||||
z: rc_input_bg.z+2
|
||||
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: (scaledBounds.height * sceneItem.height) * (ManualControlCommand.Throttle)
|
||||
height: (scaledBounds.height * sceneItem.height) * (manualControlCommand.throttle)
|
||||
|
||||
x: scaledBounds.x * sceneItem.width
|
||||
y: (scaledBounds.y * sceneItem.height) - rc_throttle.height + (scaledBounds.height * sceneItem.height)
|
||||
@ -364,9 +368,9 @@ Item {
|
||||
}
|
||||
|
||||
transitions: Transition {
|
||||
SequentialAnimation {
|
||||
PropertyAnimation { property: "x"; easing.type: anim_type; easing.amplitude: anim_amplitude; easing.period: anim_period; duration: duration_value }
|
||||
}
|
||||
SequentialAnimation {
|
||||
PropertyAnimation { property: "x"; easing.type: anim_type; easing.amplitude: anim_amplitude; easing.period: anim_period; duration: duration_value }
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -379,13 +383,13 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
|
||||
y: (scaledBounds.y * sceneItem.height) + (ManualControlCommand.Pitch * rc_stick.width * 2.5)
|
||||
y: (scaledBounds.y * sceneItem.height) + (manualControlCommand.pitch * rc_stick.width * 2.5)
|
||||
|
||||
smooth: true
|
||||
|
||||
//rotate it around his center
|
||||
transform: Rotation {
|
||||
angle: ManualControlCommand.Yaw * 90
|
||||
angle: manualControlCommand.yaw * 90
|
||||
origin.y : rc_stick.height / 2
|
||||
origin.x : rc_stick.width / 2
|
||||
}
|
||||
@ -393,13 +397,13 @@ Item {
|
||||
states: State {
|
||||
name: "fading"
|
||||
when: show_panels == true
|
||||
PropertyChanges { target: rc_stick; x: Math.floor(scaledBounds.x * sceneItem.width) + (ManualControlCommand.Roll * rc_stick.width * 2.5) + offset_value; }
|
||||
PropertyChanges { target: rc_stick; x: Math.floor(scaledBounds.x * sceneItem.width) + (manualControlCommand.roll * rc_stick.width * 2.5) + offset_value; }
|
||||
}
|
||||
|
||||
transitions: Transition {
|
||||
SequentialAnimation {
|
||||
PropertyAnimation { property: "x"; easing.type: anim_type; easing.amplitude: anim_amplitude; easing.period: anim_period; duration: duration_value }
|
||||
}
|
||||
SequentialAnimation {
|
||||
PropertyAnimation { property: "x"; easing.type: anim_type; easing.amplitude: anim_amplitude; easing.period: anim_period; duration: duration_value }
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -421,9 +425,9 @@ Item {
|
||||
}
|
||||
|
||||
transitions: Transition {
|
||||
SequentialAnimation {
|
||||
PropertyAnimation { property: "x"; easing.type: anim_type; easing.amplitude: anim_amplitude; easing.period: anim_period; duration: duration_value }
|
||||
}
|
||||
SequentialAnimation {
|
||||
PropertyAnimation { property: "x"; easing.type: anim_type; easing.amplitude: anim_amplitude; easing.period: anim_period; duration: duration_value }
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -431,7 +435,7 @@ Item {
|
||||
id: battery_volt
|
||||
sceneSize: panels.sceneSize
|
||||
elementName: "battery-volt-text"
|
||||
z: battery_bg.z+1
|
||||
z: battery_bg.z + 1
|
||||
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
@ -451,13 +455,13 @@ Item {
|
||||
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
color: panels.batColors[SystemAlarms.Alarm_Battery]
|
||||
color: panels.batColors[systemAlarms.alarmBattery]
|
||||
border.color: "white"
|
||||
border.width: battery_volt.width * 0.01
|
||||
radius: border.width * 4
|
||||
|
||||
Text {
|
||||
text: FlightBatteryState.Voltage.toFixed(2)
|
||||
text: flightBatteryState.voltage.toFixed(2)
|
||||
anchors.centerIn: parent
|
||||
color: "white"
|
||||
font {
|
||||
@ -492,13 +496,13 @@ Item {
|
||||
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
color: panels.batColors[SystemAlarms.Alarm_Battery]
|
||||
color: panels.batColors[systemAlarms.alarmBattery]
|
||||
border.color: "white"
|
||||
border.width: battery_volt.width * 0.01
|
||||
radius: border.width * 4
|
||||
|
||||
Text {
|
||||
text: FlightBatteryState.Current.toFixed(2)
|
||||
text: flightBatteryState.current.toFixed(2)
|
||||
anchors.centerIn: parent
|
||||
color: "white"
|
||||
font {
|
||||
@ -539,24 +543,24 @@ Item {
|
||||
visible: display_bat == true ? 1 : 0
|
||||
}
|
||||
|
||||
MouseArea {
|
||||
id: reset_panel_consumed_energy_mouseArea;
|
||||
MouseArea {
|
||||
id: reset_panel_consumed_energy_mouseArea;
|
||||
anchors.fill: parent;
|
||||
cursorShape: Qt.PointingHandCursor;
|
||||
visible: display_bat == true ? 1 : 0
|
||||
onClicked: qmlWidget.resetConsumedEnergy();
|
||||
}
|
||||
|
||||
// Alarm based on FlightBatteryState.EstimatedFlightTime < 120s orange, < 60s red
|
||||
color: (FlightBatteryState.EstimatedFlightTime <= 120 && FlightBatteryState.EstimatedFlightTime > 60 ? "orange" :
|
||||
(FlightBatteryState.EstimatedFlightTime <= 60 ? "red": panels.batColors[SystemAlarms.Alarm_Battery]))
|
||||
// Alarm based on flightBatteryState.estimatedFlightTime < 120s orange, < 60s red
|
||||
color: (flightBatteryState.estimatedFlightTime <= 120 && flightBatteryState.estimatedFlightTime > 60 ? "orange" :
|
||||
(flightBatteryState.estimatedFlightTime <= 60 ? "red": panels.batColors[systemAlarms.alarmBattery]))
|
||||
|
||||
border.color: "white"
|
||||
border.width: battery_volt.width * 0.01
|
||||
radius: border.width * 4
|
||||
|
||||
Text {
|
||||
text: FlightBatteryState.ConsumedEnergy.toFixed(0)
|
||||
text: flightBatteryState.consumedEnergy.toFixed(0)
|
||||
anchors.centerIn: parent
|
||||
color: "white"
|
||||
font {
|
||||
@ -591,31 +595,31 @@ Item {
|
||||
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
//color: panels.batColors[SystemAlarms.Alarm_Battery]
|
||||
//color: panels.batColors[systemAlarms.alarmBattery]
|
||||
|
||||
TooltipArea {
|
||||
text: "Reset consumed energy"
|
||||
visible: display_bat == true ? 1 : 0
|
||||
}
|
||||
|
||||
MouseArea {
|
||||
id: reset_panel_consumed_energy_mouseArea2;
|
||||
MouseArea {
|
||||
id: reset_panel_consumed_energy_mouseArea2;
|
||||
anchors.fill: parent;
|
||||
cursorShape: Qt.PointingHandCursor;
|
||||
cursorShape: Qt.PointingHandCursor;
|
||||
visible: display_bat == true ? 1 : 0
|
||||
onClicked: qmlWidget.resetConsumedEnergy();
|
||||
}
|
||||
|
||||
// Alarm based on FlightBatteryState.EstimatedFlightTime < 120s orange, < 60s red
|
||||
color: (FlightBatteryState.EstimatedFlightTime <= 120 && FlightBatteryState.EstimatedFlightTime > 60 ? "orange" :
|
||||
(FlightBatteryState.EstimatedFlightTime <= 60 ? "red": panels.batColors[SystemAlarms.Alarm_Battery]))
|
||||
// Alarm based on flightBatteryState.estimatedFlightTime < 120s orange, < 60s red
|
||||
color: (flightBatteryState.estimatedFlightTime <= 120) && (flightBatteryState.estimatedFlightTime > 60) ? "orange" :
|
||||
(flightBatteryState.estimatedFlightTime <= 60) ? "red" : panels.batColors[systemAlarms.alarmBattery]
|
||||
|
||||
border.color: "white"
|
||||
border.width: battery_volt.width * 0.01
|
||||
radius: border.width * 4
|
||||
|
||||
Text {
|
||||
text: formatTime(est_time_h) + ":" + formatTime(est_time_m) + ":" + formatTime(est_time_s)
|
||||
text: Utils.formatTime(est_time_h) + ":" + Utils.formatTime(est_time_m) + ":" + Utils.formatTime(est_time_s)
|
||||
anchors.centerIn: parent
|
||||
color: "white"
|
||||
font {
|
||||
@ -706,7 +710,7 @@ Item {
|
||||
elementName: "smeter-bg"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: oplm_bg.z+1
|
||||
z: oplm_bg.z + 1
|
||||
|
||||
states: State {
|
||||
name: "fading"
|
||||
@ -726,7 +730,7 @@ Item {
|
||||
elementName: "smeter-scale"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: oplm_bg.z+2
|
||||
z: oplm_bg.z + 2
|
||||
|
||||
states: State {
|
||||
name: "fading"
|
||||
@ -746,7 +750,7 @@ Item {
|
||||
elementName: "smeter-needle"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: oplm_bg.z+3
|
||||
z: oplm_bg.z + 3
|
||||
|
||||
states: State {
|
||||
name: "fading"
|
||||
@ -774,7 +778,7 @@ Item {
|
||||
width: smeter_scale.width * 1.09
|
||||
//anchors.horizontalCenter: smeter_scale
|
||||
|
||||
z: oplm_bg.z+4
|
||||
z: oplm_bg.z + 4
|
||||
|
||||
states: State {
|
||||
name: "fading"
|
||||
@ -796,7 +800,7 @@ Item {
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
width: smeter_mask.width
|
||||
|
||||
z: oplm_bg.z+5
|
||||
z: oplm_bg.z + 5
|
||||
|
||||
states: State {
|
||||
name: "fading"
|
||||
@ -815,7 +819,7 @@ Item {
|
||||
model: 4
|
||||
|
||||
SvgElementImage {
|
||||
z: oplm_bg.z+5
|
||||
z: oplm_bg.z + 5
|
||||
property variant idButton_oplm: "oplm_button_" + index
|
||||
property variant idButton_oplm_mousearea: "oplm_button_mousearea" + index
|
||||
property variant button_color: "button"+index+"_color"
|
||||
@ -861,7 +865,7 @@ Item {
|
||||
elementName: "oplm-id-label"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: oplm_bg.z+6
|
||||
z: oplm_bg.z + 6
|
||||
|
||||
states: State {
|
||||
name: "fading"
|
||||
@ -880,7 +884,7 @@ Item {
|
||||
id: oplm_id_text
|
||||
sceneSize: panels.sceneSize
|
||||
elementName: "oplm-id-text"
|
||||
z: oplm_bg.z+7
|
||||
z: oplm_bg.z + 7
|
||||
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
@ -916,7 +920,7 @@ Item {
|
||||
elementName: "rx-quality-label"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: oplm_bg.z+8
|
||||
z: oplm_bg.z + 8
|
||||
|
||||
states: State {
|
||||
name: "fading"
|
||||
@ -935,7 +939,7 @@ Item {
|
||||
id: rx_quality_text
|
||||
sceneSize: panels.sceneSize
|
||||
elementName: "rx-quality-text"
|
||||
z: oplm_bg.z+9
|
||||
z: oplm_bg.z + 9
|
||||
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
@ -954,7 +958,7 @@ Item {
|
||||
}
|
||||
|
||||
Text {
|
||||
text: ReceiverStatus.Quality > 0 ? ReceiverStatus.Quality+"%" : "?? %"
|
||||
text: (receiverStatus.quality > 0) ? receiverStatus.quality + "%" : "?? %"
|
||||
anchors.centerIn: parent
|
||||
color: "white"
|
||||
font {
|
||||
@ -1026,7 +1030,7 @@ Item {
|
||||
elementName: "system-frame-type"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: system_bg.z+1
|
||||
z: system_bg.z + 1
|
||||
|
||||
states: State {
|
||||
name: "fading"
|
||||
@ -1043,7 +1047,7 @@ Item {
|
||||
Text {
|
||||
text: ["FixedWing", "FixedWingElevon", "FixedWingVtail", "VTOL", "HeliCP", "QuadX", "QuadP",
|
||||
"Hexa+", "Octo+", "Custom", "HexaX", "HexaH", "OctoV", "OctoCoaxP", "OctoCoaxX", "OctoX", "HexaCoax",
|
||||
"Tricopter", "GroundVehicleCar", "GroundVehicleDiff", "GroundVehicleMoto"][SystemSettings.AirframeType]
|
||||
"Tricopter", "GroundVehicleCar", "GroundVehicleDiff", "GroundVehicleMoto"][systemSettings.airframeType]
|
||||
anchors.right: parent.right
|
||||
color: "white"
|
||||
font {
|
||||
@ -1059,7 +1063,7 @@ Item {
|
||||
elementName: "system-cpu-load-temp"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: system_bg.z+1
|
||||
z: system_bg.z + 1
|
||||
|
||||
states: State {
|
||||
name: "fading"
|
||||
@ -1075,8 +1079,7 @@ Item {
|
||||
|
||||
Text {
|
||||
// Coptercontrol detect with mem free : Only display Cpu load, no temperature available.
|
||||
text: SystemStats.CPULoad+"%"+
|
||||
[SystemStats.HeapRemaining < 3000 ? "" : " | "+cpuTemp+"°C"]
|
||||
text: systemStats.cpuLoad + "%" + [(systemStats.heapRemaining < 3000) ? "" : " | " + cpuTemp + "°C"]
|
||||
anchors.right: parent.right
|
||||
color: "white"
|
||||
font {
|
||||
@ -1092,7 +1095,7 @@ Item {
|
||||
elementName: "system-mem-free"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: system_bg.z+1
|
||||
z: system_bg.z + 1
|
||||
|
||||
states: State {
|
||||
name: "fading"
|
||||
@ -1107,7 +1110,7 @@ Item {
|
||||
}
|
||||
|
||||
Text {
|
||||
text: SystemStats.HeapRemaining > 1024 ? memory_free.toFixed(2) +"Kb" : memory_free +"bytes"
|
||||
text: (systemStats.heapRemaining > 1024) ? memory_free.toFixed(2) +"Kb" : memory_free +"bytes"
|
||||
anchors.right: parent.right
|
||||
color: "white"
|
||||
font {
|
||||
@ -1123,7 +1126,7 @@ Item {
|
||||
elementName: "system-attitude-estimation-algo"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: system_bg.z+1
|
||||
z: system_bg.z + 1
|
||||
|
||||
states: State {
|
||||
name: "fading"
|
||||
@ -1138,7 +1141,7 @@ Item {
|
||||
}
|
||||
|
||||
Text {
|
||||
text: ["None", "Basic (No Nav)", "CompMag", "Comp+Mag+GPS", "EKFIndoor", "GPS Nav (INS13)"][RevoSettings.FusionAlgorithm]
|
||||
text: ["None", "Basic (No Nav)", "CompMag", "Comp+Mag+GPS", "EKFIndoor", "GPS Nav (INS13)"][revoSettings.fusionAlgorithm]
|
||||
anchors.right: parent.right
|
||||
color: "white"
|
||||
font {
|
||||
@ -1154,7 +1157,7 @@ Item {
|
||||
elementName: "system-mag-used"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: system_bg.z+1
|
||||
z: system_bg.z + 1
|
||||
|
||||
states: State {
|
||||
name: "fading"
|
||||
@ -1169,7 +1172,7 @@ Item {
|
||||
}
|
||||
|
||||
Text {
|
||||
text: ["Invalid", "OnBoard", "External"][MagState.Source]
|
||||
text: ["Invalid", "OnBoard", "External"][magState.source]
|
||||
anchors.right: parent.right
|
||||
color: "white"
|
||||
font {
|
||||
@ -1185,7 +1188,7 @@ Item {
|
||||
elementName: "system-gps-type"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: system_bg.z+1
|
||||
z: system_bg.z + 1
|
||||
|
||||
states: State {
|
||||
name: "fading"
|
||||
@ -1200,7 +1203,7 @@ Item {
|
||||
}
|
||||
|
||||
Text {
|
||||
text: ["Unknown", "NMEA", "UBX", "UBX7", "UBX8"][GPSPositionSensor.SensorType]
|
||||
text: ["Unknown", "NMEA", "UBX", "UBX7", "UBX8"][gpsPositionSensor.sensorType]
|
||||
anchors.right: parent.right
|
||||
color: "white"
|
||||
font {
|
||||
@ -1216,7 +1219,7 @@ Item {
|
||||
elementName: "system-panel-mousearea"
|
||||
sceneSize: panels.sceneSize
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
z: system_bg.z+1
|
||||
z: system_bg.z + 1
|
||||
|
||||
TooltipArea {
|
||||
text: "System panel"
|
||||
|
@ -1,67 +0,0 @@
|
||||
import QtQuick 2.4
|
||||
|
||||
Item {
|
||||
id: sceneItem
|
||||
property variant sceneSize
|
||||
|
||||
//telemetry status arrow
|
||||
SvgElementImage {
|
||||
id: telemetry_status
|
||||
elementName: "gcstelemetry-"+statusName
|
||||
sceneSize: sceneItem.sceneSize
|
||||
|
||||
property string statusName : ["Disconnected","HandshakeReq","HandshakeAck","Connected"][GCSTelemetryStats.Status]
|
||||
|
||||
scaledBounds: svgRenderer.scaledElementBounds("pfd/pfd.svg", "gcstelemetry-Disconnected")
|
||||
x: Math.floor(scaledBounds.x * sceneItem.width)
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
}
|
||||
|
||||
//telemetry rate text
|
||||
Text {
|
||||
id: telemetry_rate
|
||||
text: GCSTelemetryStats.TxDataRate.toFixed()+"/"+GCSTelemetryStats.RxDataRate.toFixed()
|
||||
color: "white"
|
||||
font.family: pt_bold.name
|
||||
font.pixelSize: telemetry_status.height * 0.75
|
||||
|
||||
anchors.top: telemetry_status.bottom
|
||||
anchors.horizontalCenter: telemetry_status.horizontalCenter
|
||||
}
|
||||
|
||||
Text {
|
||||
id: gps_text
|
||||
text: "GPS: " + GPSPositionSensor.Satellites + "\nPDP: " + Math.round(GPSPositionSensor.PDOP*10)/10
|
||||
color: "white"
|
||||
font.family: pt_bold.name
|
||||
font.pixelSize: telemetry_status.height * 0.75
|
||||
|
||||
visible: GPSPositionSensor.Satellites > 0
|
||||
|
||||
property variant scaledBounds: svgRenderer.scaledElementBounds("pfd/pfd.svg", "gps-txt")
|
||||
x: Math.floor(scaledBounds.x * sceneItem.width)
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
}
|
||||
|
||||
Text {
|
||||
id: battery_text
|
||||
|
||||
text: FlightBatteryState.Voltage.toFixed(2)+" V\n" +
|
||||
FlightBatteryState.Current.toFixed(2)+" A\n" +
|
||||
FlightBatteryState.ConsumedEnergy.toFixed()+" mAh"
|
||||
|
||||
|
||||
color: "white"
|
||||
font.family: pt_bold.name
|
||||
|
||||
//I think it should be pixel size,
|
||||
//but making it more consistent with C++ version instead
|
||||
font.pointSize: scaledBounds.height * sceneItem.height
|
||||
|
||||
visible: FlightBatteryState.Voltage > 0 || FlightBatteryState.Current > 0
|
||||
|
||||
property variant scaledBounds: svgRenderer.scaledElementBounds("pfd/pfd.svg", "battery-txt")
|
||||
x: Math.floor(scaledBounds.x * sceneItem.width)
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
}
|
||||
}
|
@ -2,9 +2,13 @@ import QtQuick 2.4
|
||||
import Pfd 1.0
|
||||
import OsgQtQuick 1.0
|
||||
|
||||
import UAVTalk.AttitudeState 1.0
|
||||
import UAVTalk.HomeLocation 1.0
|
||||
import UAVTalk.GPSPositionSensor 1.0
|
||||
|
||||
OSGViewport {
|
||||
id: fullview
|
||||
// anchors.fill: parent
|
||||
//anchors.fill: parent
|
||||
focus: true
|
||||
sceneData: skyNode
|
||||
camera: camera
|
||||
@ -15,7 +19,7 @@ OSGViewport {
|
||||
property double factor: 0.04
|
||||
|
||||
// Stretch height and apply offset
|
||||
///height: height * (1 + factor)
|
||||
//height: height * (1 + factor)
|
||||
y: -height * factor
|
||||
|
||||
OSGSkyNode {
|
||||
@ -53,33 +57,33 @@ OSGViewport {
|
||||
position: uavPosition()
|
||||
|
||||
function uavAttitude() {
|
||||
return Qt.vector3d(AttitudeState.Pitch, AttitudeState.Roll, -AttitudeState.Yaw);
|
||||
return Qt.vector3d(attitudeState.pitch, attitudeState.roll, -attitudeState.yaw);
|
||||
}
|
||||
|
||||
function uavPosition() {
|
||||
switch(GPSPositionSensor.Status) {
|
||||
case 2: // Fix2D
|
||||
case 3: // Fix3D
|
||||
switch(gpsPositionSensor.status) {
|
||||
case Status.Fix2D:
|
||||
case Status.Fix3D:
|
||||
return uavGPSPosition();
|
||||
case 0: // NoGPS
|
||||
case 1: // NoFix
|
||||
case Status.NoFix:
|
||||
case Status.NoGPS:
|
||||
default:
|
||||
return (HomeLocation.Set == 1) ? uavHomePosition() : uavDefaultPosition();
|
||||
return (homeLocation.set == Set.True) ? uavHomePosition() : uavDefaultPosition();
|
||||
}
|
||||
}
|
||||
|
||||
function uavGPSPosition() {
|
||||
return Qt.vector3d(
|
||||
GPSPositionSensor.Longitude / 10000000.0,
|
||||
GPSPositionSensor.Latitude / 10000000.0,
|
||||
GPSPositionSensor.Altitude);
|
||||
gpsPositionSensor.longitude / 10000000.0,
|
||||
gpsPositionSensor.latitude / 10000000.0,
|
||||
gpsPositionSensor.altitude);
|
||||
}
|
||||
|
||||
function uavHomePosition() {
|
||||
return Qt.vector3d(
|
||||
HomeLocation.Longitude / 10000000.0,
|
||||
HomeLocation.Latitude / 10000000.0,
|
||||
HomeLocation.Altitude);
|
||||
homeLocation.longitude / 10000000.0,
|
||||
homeLocation.latitude / 10000000.0,
|
||||
homeLocation.altitude);
|
||||
}
|
||||
|
||||
function uavDefaultPosition() {
|
||||
@ -96,13 +100,13 @@ OSGViewport {
|
||||
opacity: 0
|
||||
|
||||
property variant scaledBounds: svgRenderer.scaledElementBounds("pfd/pfd.svg", "horizon")
|
||||
width: Math.round(sceneItem.width*scaledBounds.width/2)*2
|
||||
height: Math.round(sceneItem.height*scaledBounds.height/2)*3
|
||||
width: Math.round(sceneItem.width * scaledBounds.width / 2) * 2
|
||||
height: Math.round(sceneItem.height * scaledBounds.height / 2) * 3
|
||||
|
||||
property double pitch1DegScaledHeight: (svgRenderer.scaledElementBounds("pfd/pfd.svg", "pitch-90").y -
|
||||
svgRenderer.scaledElementBounds("pfd/pfd.svg", "pitch90").y)/180.0
|
||||
svgRenderer.scaledElementBounds("pfd/pfd.svg", "pitch90").y) / 180.0
|
||||
|
||||
property double pitch1DegHeight: sceneItem.height*pitch1DegScaledHeight
|
||||
property double pitch1DegHeight: sceneItem.height * pitch1DegScaledHeight
|
||||
|
||||
|
||||
transform: [
|
||||
@ -110,12 +114,11 @@ OSGViewport {
|
||||
id: pitchTranslate
|
||||
x: Math.round((world.parent.width - world.width)/2)
|
||||
// y is centered around world_center element
|
||||
y: Math.round(horizontCenter - world.height/2 +
|
||||
AttitudeState.Pitch*world.pitch1DegHeight)
|
||||
y: Math.round(horizontCenter - world.height / 2 + attitudeState.pitch * world.pitch1DegHeight)
|
||||
},
|
||||
Rotation {
|
||||
angle: -AttitudeState.Roll
|
||||
origin.x : world.parent.width/2
|
||||
angle: -attitudeState.roll
|
||||
origin.x : world.parent.width / 2
|
||||
origin.y : horizontCenter
|
||||
}
|
||||
]
|
||||
@ -131,7 +134,7 @@ OSGViewport {
|
||||
width: Math.floor(scaledBounds.width * sceneItem.width)
|
||||
height: Math.floor(scaledBounds.height * sceneItem.height)
|
||||
|
||||
rotation: -AttitudeState.Roll
|
||||
rotation: -attitudeState.roll
|
||||
transformOrigin: Item.Center
|
||||
|
||||
smooth: true
|
||||
@ -145,8 +148,8 @@ OSGViewport {
|
||||
sceneSize: background.sceneSize
|
||||
anchors.centerIn: parent
|
||||
//see comment for world transform
|
||||
anchors.verticalCenterOffset: AttitudeState.Pitch*world.pitch1DegHeight
|
||||
border: 64 //sometimes numbers are excluded from bounding rect
|
||||
anchors.verticalCenterOffset: attitudeState.pitch * world.pitch1DegHeight
|
||||
border: 64 // sometimes numbers are excluded from bounding rect
|
||||
|
||||
smooth: true
|
||||
}
|
||||
@ -157,11 +160,11 @@ OSGViewport {
|
||||
|
||||
opacity: 0.5
|
||||
|
||||
//worldView is loaded with Loader, so background element is visible
|
||||
// worldView is loaded with Loader, so background element is visible
|
||||
sceneSize: background.sceneSize
|
||||
anchors.centerIn: parent
|
||||
|
||||
anchors.verticalCenterOffset: AttitudeState.Pitch*world.pitch1DegHeight
|
||||
anchors.verticalCenterOffset: attitudeState.pitch * world.pitch1DegHeight
|
||||
border: 1
|
||||
smooth: true
|
||||
}
|
||||
@ -172,7 +175,7 @@ OSGViewport {
|
||||
|
||||
sceneSize: background.sceneSize
|
||||
anchors.centerIn: parent
|
||||
anchors.verticalCenterOffset: AttitudeState.Pitch*world.pitch1DegHeight
|
||||
anchors.verticalCenterOffset: attitudeState.pitch * world.pitch1DegHeight
|
||||
border: 1
|
||||
smooth: true
|
||||
}
|
||||
|
@ -1,5 +1,7 @@
|
||||
import QtQuick 2.4
|
||||
|
||||
import UAVTalk.AttitudeState 1.0
|
||||
|
||||
Item {
|
||||
id: worldView
|
||||
property real horizontCenter : horizontCenterItem.horizontCenter
|
||||
@ -32,10 +34,10 @@ Item {
|
||||
x: Math.round((world.parent.width - world.width)/2)
|
||||
// y is centered around world_center element
|
||||
y: Math.round(horizontCenter - world.height/2 +
|
||||
AttitudeState.Pitch*world.pitch1DegHeight)
|
||||
attitudeState.pitch * world.pitch1DegHeight)
|
||||
},
|
||||
Rotation {
|
||||
angle: -AttitudeState.Roll
|
||||
angle: -attitudeState.roll
|
||||
origin.x : world.parent.width/2
|
||||
origin.y : horizontCenter
|
||||
}
|
||||
@ -72,7 +74,7 @@ Item {
|
||||
width: Math.floor(scaledBounds.width * sceneItem.width)
|
||||
height: Math.floor(scaledBounds.height * sceneItem.height)
|
||||
|
||||
rotation: -AttitudeState.Roll
|
||||
rotation: -attitudeState.roll
|
||||
transformOrigin: Item.Center
|
||||
|
||||
smooth: true
|
||||
@ -85,7 +87,7 @@ Item {
|
||||
sceneSize: background.sceneSize
|
||||
anchors.centerIn: parent
|
||||
//see comment for world transform
|
||||
anchors.verticalCenterOffset: AttitudeState.Pitch*world.pitch1DegHeight
|
||||
anchors.verticalCenterOffset: attitudeState.pitch * world.pitch1DegHeight
|
||||
border: 64 //sometimes numbers are excluded from bounding rect
|
||||
|
||||
smooth: true
|
||||
|
@ -1,11 +1,14 @@
|
||||
import QtQuick 2.4
|
||||
|
||||
import UAVTalk.AttitudeState 1.0
|
||||
|
||||
Item {
|
||||
id: sceneItem
|
||||
|
||||
property variant sceneSize
|
||||
property real horizontCenter
|
||||
|
||||
//onHorizontCenterChanged: console.log("horizont center:"+horizontCenter)
|
||||
//onHorizontCenterChanged: console.log("horizont center:" + horizontCenter)
|
||||
|
||||
SvgElementImage {
|
||||
id: rollscale
|
||||
@ -22,9 +25,9 @@ Item {
|
||||
|
||||
// rotate it around the center of horizon
|
||||
transform: Rotation {
|
||||
angle: -AttitudeState.Roll
|
||||
origin.y : rollscale.height*2.4
|
||||
origin.x : rollscale.width/2
|
||||
angle: -attitudeState.roll
|
||||
origin.y : rollscale.height * 2.4
|
||||
origin.x : rollscale.width / 2
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1,10 +1,12 @@
|
||||
import QtQuick 2.4
|
||||
|
||||
import UAVTalk.VelocityState 1.0
|
||||
import UAVTalk.PathDesired 1.0
|
||||
|
||||
Item {
|
||||
id: sceneItem
|
||||
property variant sceneSize
|
||||
property real groundSpeed : qmlWidget.speedFactor * Math.sqrt(Math.pow(VelocityState.North,2)+
|
||||
Math.pow(VelocityState.East,2))
|
||||
property real groundSpeed : qmlWidget.speedFactor * Math.sqrt(Math.pow(velocityState.north, 2) + Math.pow(velocityState.east, 2))
|
||||
|
||||
SvgElementImage {
|
||||
id: speed_window
|
||||
@ -63,12 +65,12 @@ Item {
|
||||
id: speed_waypoint
|
||||
elementName: "speed-waypoint"
|
||||
sceneSize: sceneItem.sceneSize
|
||||
visible: PathDesired.EndingVelocity !== 0.0
|
||||
visible: (pathDesired.endingVelocity != 0.0)
|
||||
|
||||
anchors.right: parent.right
|
||||
anchors.verticalCenter: parent.verticalCenter
|
||||
|
||||
anchors.verticalCenterOffset: speed_scale.height/10 * (sceneItem.groundSpeed - (PathDesired.EndingVelocity * qmlWidget.speedFactor))
|
||||
anchors.verticalCenterOffset: speed_scale.height / 10 * (sceneItem.groundSpeed - (pathDesired.endingVelocity * qmlWidget.speedFactor))
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1,5 +1,10 @@
|
||||
import QtQuick 2.4
|
||||
|
||||
import UAVTalk.FlightStatus 1.0
|
||||
import UAVTalk.VelocityDesired 1.0
|
||||
|
||||
import "common.js" as Utils
|
||||
|
||||
Item {
|
||||
id: sceneItem
|
||||
property variant sceneSize
|
||||
@ -7,7 +12,7 @@ Item {
|
||||
|
||||
Timer {
|
||||
interval: 100; running: true; repeat: true
|
||||
onTriggered: vert_velocity = (0.9 * vert_velocity) + (0.1 * VelocityState.Down)
|
||||
onTriggered: vert_velocity = (0.9 * vert_velocity) + (0.1 * velocityState.down)
|
||||
}
|
||||
|
||||
SvgElementImage {
|
||||
@ -22,11 +27,11 @@ Item {
|
||||
y: scaledBounds.y * sceneItem.height
|
||||
|
||||
smooth: true
|
||||
visible: VelocityDesired.Down !== 0.0 && FlightStatus.FlightMode > 7
|
||||
visible: ((velocityDesired.down != 0.0) && (flightStatus.flightMode > FlightMode.PositionHold))
|
||||
|
||||
//rotate it around the center
|
||||
// rotate it around the center
|
||||
transform: Rotation {
|
||||
angle: -VelocityDesired.Down * 5
|
||||
angle: -velocityDesired.down * 5
|
||||
origin.y : vsi_waypoint.height / 2
|
||||
origin.x : vsi_waypoint.width * 33
|
||||
}
|
||||
@ -35,7 +40,7 @@ Item {
|
||||
SvgElementImage {
|
||||
id: vsi_scale_meter
|
||||
|
||||
visible: qmlWidget.altitudeUnit == "m"
|
||||
visible: (qmlWidget.altitudeUnit == "m")
|
||||
elementName: "vsi-scale-meter"
|
||||
sceneSize: sceneItem.sceneSize
|
||||
|
||||
@ -47,7 +52,7 @@ Item {
|
||||
SvgElementImage {
|
||||
id: vsi_scale_ft
|
||||
|
||||
visible: qmlWidget.altitudeUnit == "ft"
|
||||
visible: (qmlWidget.altitudeUnit == "ft")
|
||||
elementName: "vsi-scale-ft"
|
||||
sceneSize: sceneItem.sceneSize
|
||||
|
||||
@ -69,9 +74,9 @@ Item {
|
||||
|
||||
smooth: true
|
||||
|
||||
//rotate it around the center : limit value to +/-6m/s
|
||||
// rotate it around the center, limit value to +/-6m/s
|
||||
transform: Rotation {
|
||||
angle: vert_velocity > 6 ? -30 : vert_velocity < -6 ? 30 : -vert_velocity * 5
|
||||
angle: (vert_velocity > 6) ? -30 : (vert_velocity < -6) ? 30 : -vert_velocity * 5
|
||||
origin.y : vsi_arrow.height / 2
|
||||
origin.x : vsi_arrow.width * 3.15
|
||||
}
|
||||
@ -83,7 +88,7 @@ Item {
|
||||
sceneSize: sceneItem.sceneSize
|
||||
|
||||
Text {
|
||||
text: qmlWidget.altitudeUnit == "m" ? "m/s" : "ft/s"
|
||||
text: (qmlWidget.altitudeUnit == "m") ? "m/s" : "ft/s"
|
||||
color: "cyan"
|
||||
font {
|
||||
family: pt_bold.name
|
||||
|
@ -1,51 +1,46 @@
|
||||
import QtQuick 2.4
|
||||
|
||||
import UAVTalk.SystemSettings 1.0
|
||||
import UAVTalk.SystemAlarms 1.0
|
||||
import UAVTalk.FlightStatus 1.0
|
||||
import UAVTalk.VtolPathFollowerSettings 1.0
|
||||
|
||||
import "common.js" as Utils
|
||||
|
||||
Item {
|
||||
id: warnings
|
||||
|
||||
property variant sceneSize
|
||||
// Uninitialised, OK, Warning, Error, Critical
|
||||
|
||||
// Uninitialised, OK, Warning, Error, Critical
|
||||
property variant statusColors : ["gray", "green", "red", "red", "red"]
|
||||
|
||||
// DisArmed , Arming, Armed
|
||||
// DisArmed , Arming, Armed
|
||||
property variant armColors : ["gray", "orange", "green"]
|
||||
|
||||
// All 'manual modes' are green, 'assisted' modes in cyan
|
||||
// "MANUAL","STAB 1","STAB 2", "STAB 3", "STAB 4", "STAB 5", "STAB 6",
|
||||
// "POS HOLD", "COURSE LOCK", "POS ROAM", "HOME LEASH", "ABS POS", "RTB", "LAND", "PATHPLANNER", "POI", "AUTOCRUISE"
|
||||
|
||||
// "POS HOLD", "COURSELOCK","VEL ROAM", "HOME LEASH", "ABS POS", "RTB", "LAND", "PATHPLAN", "POI", "AUTOCRUISE", "AUTOTAKEOFF"
|
||||
property variant flightmodeColors : ["gray", "green", "green", "green", "green", "green", "green",
|
||||
"cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan"]
|
||||
"cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan"]
|
||||
|
||||
// Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Acro+,Rattitude,
|
||||
// AltitudeHold,AltitudeVario,CruiseControl + Auto mode (VTOL/Wing pathfollower)
|
||||
// Manual,Rate,RateTrainer,Attitude,AxisLock,WeakLeveling,VirtualBar,Acro+,Rattitude,
|
||||
// AltitudeHold,AltitudeVario,CruiseControl" + Auto mode (VTOL/Wing pathfollower)
|
||||
// grey : 'disabled' modes
|
||||
|
||||
property variant thrustmodeColors : ["green", "grey", "grey", "grey", "grey", "grey", "grey", "grey",
|
||||
property variant thrustmodeColors : ["green", "grey", "grey", "grey", "grey", "grey", "grey", "grey", "grey",
|
||||
"green", "green", "green", "cyan"]
|
||||
|
||||
// SystemSettings.AirframeType 3 - 17 : VtolPathFollower, check ThrustControl
|
||||
// systemSettings.airframeType 3 - 17 : VtolPathFollower, check ThrustControl
|
||||
property var thrust_mode: (flightStatus.flightMode < FlightMode.PositionHold) ? stabilizationDesired.stabilizationModeThrust :
|
||||
(flightStatus.flightMode >= FlightMode.PositionHold) && (systemSettings.airframeType > AirframeType.FixedWingVtail) &&
|
||||
(systemSettings.airframeType < AirframeType.GroundVehicleCar) && (vtolPathFollowerSettings.thrustControl == ThrustControl.Auto) ? 12 :
|
||||
(flightStatus.flightMode >= FlightMode.PositionHold) && (systemSettings.airframeType < AirframeType.VTOL) ? 12 : 0
|
||||
|
||||
property var thrust_mode: FlightStatus.FlightMode < 7 ? StabilizationDesired.StabilizationMode_Thrust :
|
||||
FlightStatus.FlightMode > 6 && SystemSettings.AirframeType > 2 && SystemSettings.AirframeType < 18
|
||||
&& VtolPathFollowerSettings.ThrustControl == 1 ? 11 :
|
||||
FlightStatus.FlightMode > 6 && SystemSettings.AirframeType < 3 ? 11: 0
|
||||
|
||||
|
||||
property real flight_time: Math.round(SystemStats.FlightTime / 1000)
|
||||
property real flight_time: Math.round(systemStats.flightTime / 1000)
|
||||
property real time_h: (flight_time > 0 ? Math.floor(flight_time / 3600) : 0 )
|
||||
property real time_m: (flight_time > 0 ? Math.floor((flight_time - time_h*3600)/60) : 0)
|
||||
property real time_s: (flight_time > 0 ? Math.floor(flight_time - time_h*3600 - time_m*60) : 0)
|
||||
|
||||
function formatTime(time) {
|
||||
if (time == 0)
|
||||
return "00"
|
||||
if (time < 10)
|
||||
return "0" + time;
|
||||
else
|
||||
return time.toString();
|
||||
}
|
||||
|
||||
SvgElementImage {
|
||||
id: warning_bg
|
||||
elementName: "warnings-bg"
|
||||
@ -65,11 +60,11 @@ Item {
|
||||
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
color: (SystemStats.FlightTime > 0 ? "green" : "grey")
|
||||
color: (systemStats.flightTime > 0) ? "green" : "grey"
|
||||
|
||||
Text {
|
||||
anchors.centerIn: parent
|
||||
text: formatTime(time_h) + ":" + formatTime(time_m) + ":" + formatTime(time_s)
|
||||
text: Utils.formatTime(time_h) + ":" + Utils.formatTime(time_m) + ":" + Utils.formatTime(time_s)
|
||||
font {
|
||||
family: pt_bold.name
|
||||
pixelSize: Math.floor(parent.height * 0.8)
|
||||
@ -90,11 +85,11 @@ Item {
|
||||
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
color: warnings.armColors[FlightStatus.Armed]
|
||||
color: warnings.armColors[flightStatus.armed]
|
||||
|
||||
Text {
|
||||
anchors.centerIn: parent
|
||||
text: ["DISARMED","ARMING","ARMED"][FlightStatus.Armed]
|
||||
text: ["DISARMED","ARMING","ARMED"][flightStatus.armed]
|
||||
font {
|
||||
family: pt_bold.name
|
||||
pixelSize: Math.floor(parent.height * 0.74)
|
||||
@ -115,7 +110,7 @@ Item {
|
||||
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
color: warnings.statusColors[SystemAlarms.Alarm_ManualControl]
|
||||
color: warnings.statusColors[systemAlarms.alarmManualControl]
|
||||
|
||||
Text {
|
||||
anchors.centerIn: parent
|
||||
@ -138,11 +133,11 @@ Item {
|
||||
x: scaledBounds.x * sceneItem.width
|
||||
y: scaledBounds.y * sceneItem.height
|
||||
|
||||
property bool warningActive: (SystemAlarms.Alarm_BootFault > 1 ||
|
||||
SystemAlarms.Alarm_OutOfMemory > 1 ||
|
||||
SystemAlarms.Alarm_StackOverflow > 1 ||
|
||||
SystemAlarms.Alarm_CPUOverload > 1 ||
|
||||
SystemAlarms.Alarm_EventSystem > 1)
|
||||
property bool warningActive: ((systemAlarms.alarmBootFault > Alarm.OK) ||
|
||||
(systemAlarms.alarmOutOfMemory > Alarm.OK) ||
|
||||
(systemAlarms.alarmStackOverflow > Alarm.OK) ||
|
||||
(systemAlarms.alarmCPUOverload > Alarm.OK) ||
|
||||
(systemAlarms.alarmEventSystem > Alarm.OK))
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
color: parent.warningActive ? "red" : "red"
|
||||
@ -172,7 +167,7 @@ Item {
|
||||
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
color: warnings.statusColors[SystemAlarms.Alarm_Guidance]
|
||||
color: warnings.statusColors[systemAlarms.alarmGuidance]
|
||||
|
||||
Text {
|
||||
anchors.centerIn: parent
|
||||
@ -197,12 +192,12 @@ Item {
|
||||
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
color: warnings.flightmodeColors[FlightStatus.FlightMode]
|
||||
color: warnings.flightmodeColors[flightStatus.flightMode]
|
||||
|
||||
Text {
|
||||
anchors.centerIn: parent
|
||||
text: ["MANUAL","STAB 1","STAB 2", "STAB 3", "STAB 4", "STAB 5", "STAB 6", "POS HOLD", "COURSELOCK",
|
||||
"POS ROAM", "HOME LEASH", "ABS POS", "RTB", "LAND", "PATHPLAN", "POI", "AUTOCRUISE"][FlightStatus.FlightMode]
|
||||
"VEL ROAM", "HOME LEASH", "ABS POS", "RTB", "LAND", "PATHPLAN", "POI", "AUTOCRUISE", "AUTOTAKEOFF"][flightStatus.flightMode]
|
||||
font {
|
||||
family: pt_bold.name
|
||||
pixelSize: Math.floor(parent.height * 0.74)
|
||||
@ -223,15 +218,12 @@ Item {
|
||||
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
color: FlightStatus.FlightMode < 1 ? "grey" : warnings.thrustmodeColors[thrust_mode.toString()]
|
||||
color: (flightStatus.flightMode == FlightMode.Manual) ? "grey" : warnings.thrustmodeColors[thrust_mode]
|
||||
|
||||
// Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Acro+,Rattitude,
|
||||
// AltitudeHold,AltitudeVario,CruiseControl
|
||||
// grey : 'disabled' modes
|
||||
// grey : 'disabled' modes
|
||||
Text {
|
||||
anchors.centerIn: parent
|
||||
text: ["MANUAL"," "," ", " ", " ", " ", " ", " ",
|
||||
"ALT HOLD", "ALT VARIO", "CRUISECTRL", "AUTO"][thrust_mode.toString()]
|
||||
text: ["MANUAL"," "," ", " ", " ", " ", " ", " ", " ", "ALT HOLD", "ALT VARIO", "CRUISECTRL", "AUTO"][thrust_mode]
|
||||
font {
|
||||
family: pt_bold.name
|
||||
pixelSize: Math.floor(parent.height * 0.74)
|
||||
@ -246,7 +238,7 @@ Item {
|
||||
elementName: "warning-gps"
|
||||
sceneSize: warnings.sceneSize
|
||||
|
||||
visible: SystemAlarms.Alarm_GPS > 1
|
||||
visible: (systemAlarms.alarmGPS > Alarm.OK)
|
||||
}
|
||||
|
||||
SvgElementImage {
|
||||
@ -254,6 +246,6 @@ Item {
|
||||
elementName: "warning-attitude"
|
||||
sceneSize: warnings.sceneSize
|
||||
anchors.centerIn: background.centerIn
|
||||
visible: SystemAlarms.Alarm_Attitude > 1
|
||||
visible: (systemAlarms.alarmAttitude > Alarm.OK)
|
||||
}
|
||||
}
|
||||
|
18
ground/gcs/src/share/qml/pfd/common.js
Normal file
18
ground/gcs/src/share/qml/pfd/common.js
Normal file
@ -0,0 +1,18 @@
|
||||
// ***********************
|
||||
// common.js
|
||||
//
|
||||
// Common javascript utils
|
||||
//
|
||||
// Librepilot
|
||||
// ***********************
|
||||
|
||||
// Format time
|
||||
function formatTime(time) {
|
||||
if (time === 0)
|
||||
return "00"
|
||||
if (time < 10)
|
||||
return "0" + time;
|
||||
else
|
||||
return time.toString();
|
||||
}
|
||||
|
@ -25,16 +25,521 @@
|
||||
*/
|
||||
|
||||
#include "uavobjectgeneratorgcs.h"
|
||||
|
||||
#define VERBOSE false
|
||||
#define DEPRECATED true
|
||||
|
||||
#define DEFAULT_ENUM_PREFIX "E_"
|
||||
|
||||
using namespace std;
|
||||
|
||||
void error(QString msg)
|
||||
{
|
||||
cerr << "error: " << msg.toStdString() << endl;
|
||||
}
|
||||
|
||||
void warning(ObjectInfo *object, QString msg)
|
||||
{
|
||||
cerr << "warning: " << object->filename.toStdString() << ": " << msg.toStdString() << endl;
|
||||
}
|
||||
|
||||
void info(ObjectInfo *object, QString msg)
|
||||
{
|
||||
if (VERBOSE) {
|
||||
cout << "info: " << object->filename.toStdString() << ": " << msg.toStdString() << endl;
|
||||
}
|
||||
}
|
||||
|
||||
struct Context {
|
||||
ObjectInfo *object;
|
||||
// enums
|
||||
QString enums;
|
||||
QString registerImpl;
|
||||
// interface
|
||||
QString fields;
|
||||
QString fieldsInfo;
|
||||
QString properties;
|
||||
QString deprecatedProperties;
|
||||
QString getters;
|
||||
QString setters;
|
||||
QString notifications;
|
||||
// implementation
|
||||
QString fieldsInit;
|
||||
QString fieldsDefault;
|
||||
QString propertiesImpl;
|
||||
QString notificationsImpl;
|
||||
};
|
||||
|
||||
struct FieldContext {
|
||||
FieldInfo *field;
|
||||
// field
|
||||
QString fieldName;
|
||||
QString fieldType;
|
||||
// property
|
||||
QString propName;
|
||||
QString ucPropName;
|
||||
QString propType;
|
||||
QString propRefType;
|
||||
// deprecation
|
||||
bool hasDeprecatedProperty;
|
||||
bool hasDeprecatedGetter;
|
||||
bool hasDeprecatedSetter;
|
||||
bool hasDeprecatedNotification;
|
||||
};
|
||||
|
||||
QString fieldTypeStrCPP(int type)
|
||||
{
|
||||
QStringList fieldTypeStrCPP;
|
||||
|
||||
fieldTypeStrCPP << "qint8" << "qint16" << "qint32" << "quint8" << "quint16" << "quint32" << "float" << "quint8";
|
||||
return fieldTypeStrCPP[type];
|
||||
}
|
||||
|
||||
QString fieldTypeStrCPPClass(int type)
|
||||
{
|
||||
QStringList fieldTypeStrCPPClass;
|
||||
|
||||
fieldTypeStrCPPClass << "INT8" << "INT16" << "INT32" << "UINT8" << "UINT16" << "UINT32" << "FLOAT32" << "ENUM";
|
||||
return fieldTypeStrCPPClass[type];
|
||||
}
|
||||
|
||||
QString toPropertyName(const QString & name)
|
||||
{
|
||||
QString str = name;
|
||||
|
||||
// make sure 1st letter is upper case
|
||||
str[0] = str[0].toUpper();
|
||||
|
||||
// handle underscore
|
||||
int p = str.indexOf('_');
|
||||
while (p != -1) {
|
||||
str.remove(p, 1);
|
||||
str[p] = str[p].toUpper();
|
||||
p = str.indexOf('_', p);
|
||||
}
|
||||
|
||||
return str;
|
||||
}
|
||||
|
||||
/*
|
||||
* Convert a string to lower camel case.
|
||||
* Handles following cases :
|
||||
* - Property -> property
|
||||
* - MyProperty -> myProperty
|
||||
* - MYProperty -> myProperty
|
||||
* - MY_Property -> my_Property
|
||||
* - MY -> my
|
||||
*/
|
||||
QString toLowerCamelCase(const QString & name)
|
||||
{
|
||||
QString str = name;
|
||||
|
||||
for (int i = 0; i < str.length(); ++i) {
|
||||
if (str[i].isLower() || !str[i].isLetter()) {
|
||||
break;
|
||||
}
|
||||
if (i > 0 && i < str.length() - 1) {
|
||||
// after first, look ahead one
|
||||
if (str[i + 1].isLower()) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
str[i] = str[i].toLower();
|
||||
}
|
||||
|
||||
return str;
|
||||
}
|
||||
|
||||
QString toEnumName(ObjectInfo *object, FieldInfo *field, int index)
|
||||
{
|
||||
QString option = field->options[index];
|
||||
|
||||
if (option.contains(QRegExp(ENUM_SPECIAL_CHARS))) {
|
||||
info(object, "Enumeration value \"" + option + "\" contains special chars, cleaning.");
|
||||
option.replace(QRegExp(ENUM_SPECIAL_CHARS), "");
|
||||
}
|
||||
if (option[0].isDigit()) {
|
||||
info(object, "Enumeration value \"" + option + "\" starts with a digit, prefixing with \"" + DEFAULT_ENUM_PREFIX "\".");
|
||||
option = DEFAULT_ENUM_PREFIX + option;
|
||||
}
|
||||
if (option == option.toLower()) {
|
||||
warning(object, "Enumeration value \"" + option + "\" is all lower case, consider capitalizing.");
|
||||
}
|
||||
if (option[0].isLower()) {
|
||||
warning(object, "Enumeration value \"" + option + "\" does not start with an upper case letter.");
|
||||
option[0] = option[0].toUpper();
|
||||
}
|
||||
if (option == "FALSE") {
|
||||
warning(object, "Invalid enumeration name FALSE, converting to False.");
|
||||
option = "False";
|
||||
}
|
||||
if (option == "TRUE") {
|
||||
warning(object, "Invalid enumeration name TRUE, converting to True.");
|
||||
option = "True";
|
||||
}
|
||||
return option;
|
||||
}
|
||||
|
||||
QString toEnumStringList(ObjectInfo *object, FieldInfo *field)
|
||||
{
|
||||
QString enumListString;
|
||||
|
||||
for (int m = 0; m < field->options.length(); ++m) {
|
||||
if (m > 0) {
|
||||
enumListString.append(", ");
|
||||
}
|
||||
QString option = toEnumName(object, field, m);
|
||||
enumListString.append(option);
|
||||
}
|
||||
|
||||
return enumListString;
|
||||
}
|
||||
|
||||
|
||||
QString generate(Context &ctxt, const QString &fragment)
|
||||
{
|
||||
QString str = fragment;
|
||||
|
||||
str.replace(":ClassName", ctxt.object->name);
|
||||
str.replace(":className", ctxt.object->namelc);
|
||||
|
||||
return str;
|
||||
}
|
||||
|
||||
QString generate(Context &ctxt, FieldContext &fieldCtxt, const QString &fragment)
|
||||
{
|
||||
QString str = generate(ctxt, fragment);
|
||||
|
||||
str.replace(":PropName", fieldCtxt.ucPropName);
|
||||
str.replace(":propName", fieldCtxt.propName);
|
||||
str.replace(":propType", fieldCtxt.propType);
|
||||
str.replace(":propRefType", fieldCtxt.propRefType);
|
||||
|
||||
str.replace(":fieldName", fieldCtxt.fieldName);
|
||||
str.replace(":fieldType", fieldCtxt.fieldType);
|
||||
str.replace(":fieldDesc", fieldCtxt.field->description);
|
||||
str.replace(":fieldUnits", fieldCtxt.field->units);
|
||||
str.replace(":fieldLimitValues", fieldCtxt.field->limitValues);
|
||||
|
||||
str.replace(":elementCount", QString::number(fieldCtxt.field->numElements));
|
||||
|
||||
return str;
|
||||
}
|
||||
|
||||
void generateFieldInfo(Context &ctxt, FieldContext &fieldCtxt)
|
||||
{
|
||||
ctxt.fieldsInfo += generate(ctxt, fieldCtxt, " // :fieldName\n");
|
||||
|
||||
if (fieldCtxt.field->type == FIELDTYPE_ENUM) {
|
||||
QStringList options = fieldCtxt.field->options;
|
||||
ctxt.fieldsInfo += " typedef enum { ";
|
||||
for (int m = 0; m < options.length(); ++m) {
|
||||
if (m > 0) {
|
||||
ctxt.fieldsInfo.append(", ");
|
||||
}
|
||||
ctxt.fieldsInfo += generate(ctxt, fieldCtxt, "%1_%2=%3")
|
||||
.arg(fieldCtxt.field->name.toUpper())
|
||||
.arg(options[m].toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), ""))
|
||||
.arg(m);
|
||||
}
|
||||
ctxt.fieldsInfo += generate(ctxt, fieldCtxt, " } :fieldNameOptions;\n");
|
||||
}
|
||||
|
||||
// Generate element names (only if field has more than one element)
|
||||
if (fieldCtxt.field->numElements > 1 && !fieldCtxt.field->defaultElementNames) {
|
||||
QStringList elemNames = fieldCtxt.field->elementNames;
|
||||
ctxt.fieldsInfo += " typedef enum { ";
|
||||
for (int m = 0; m < elemNames.length(); ++m) {
|
||||
if (m > 0) {
|
||||
ctxt.fieldsInfo.append(", ");
|
||||
}
|
||||
ctxt.fieldsInfo += QString("%1_%2=%3")
|
||||
.arg(fieldCtxt.field->name.toUpper())
|
||||
.arg(elemNames[m].toUpper())
|
||||
.arg(m);
|
||||
}
|
||||
ctxt.fieldsInfo += generate(ctxt, fieldCtxt, " } :fieldNameElem;\n");
|
||||
}
|
||||
|
||||
// Generate array information
|
||||
if (fieldCtxt.field->numElements > 1) {
|
||||
ctxt.fieldsInfo += generate(ctxt, fieldCtxt, " static const quint32 %1_NUMELEM = :elementCount;\n")
|
||||
.arg(fieldCtxt.field->name.toUpper());
|
||||
}
|
||||
}
|
||||
|
||||
void generateFieldInit(Context &ctxt, FieldContext &fieldCtxt)
|
||||
{
|
||||
ctxt.fieldsInit += generate(ctxt, fieldCtxt, " // :fieldName\n");
|
||||
|
||||
// Setup element names
|
||||
ctxt.fieldsInit += generate(ctxt, fieldCtxt, " QStringList :fieldNameElemNames;\n");
|
||||
QStringList elemNames = fieldCtxt.field->elementNames;
|
||||
ctxt.fieldsInit += generate(ctxt, fieldCtxt, " :fieldNameElemNames");
|
||||
for (int m = 0; m < elemNames.length(); ++m) {
|
||||
ctxt.fieldsInit += QString(" << \"%1\"").arg(elemNames[m]);
|
||||
}
|
||||
ctxt.fieldsInit += ";\n";
|
||||
|
||||
if (fieldCtxt.field->type == FIELDTYPE_ENUM) {
|
||||
ctxt.fieldsInit += generate(ctxt, fieldCtxt, " QStringList :fieldNameEnumOptions;\n");
|
||||
QStringList options = fieldCtxt.field->options;
|
||||
ctxt.fieldsInit += generate(ctxt, fieldCtxt, " :fieldNameEnumOptions");
|
||||
for (int m = 0; m < options.length(); ++m) {
|
||||
ctxt.fieldsInit += QString(" << \"%1\"").arg(options[m]);
|
||||
}
|
||||
ctxt.fieldsInit += ";\n";
|
||||
ctxt.fieldsInit += generate(ctxt, fieldCtxt,
|
||||
" fields.append(new UAVObjectField(\":fieldName\", tr(\":fieldDesc\"), \":fieldUnits\", UAVObjectField::ENUM, :fieldNameElemNames, :fieldNameEnumOptions, \":fieldLimitValues\"));\n");
|
||||
} else {
|
||||
ctxt.fieldsInit += generate(ctxt, fieldCtxt,
|
||||
" fields.append(new UAVObjectField(\":fieldName\", tr(\":fieldDesc\"), \":fieldUnits\", UAVObjectField::%1, :fieldNameElemNames, QStringList(), \":fieldLimitValues\"));\n")
|
||||
.arg(fieldTypeStrCPPClass(fieldCtxt.field->type));
|
||||
}
|
||||
}
|
||||
|
||||
void generateFieldDefault(Context &ctxt, FieldContext &fieldCtxt)
|
||||
{
|
||||
if (!fieldCtxt.field->defaultValues.isEmpty()) {
|
||||
// For non-array fields
|
||||
if (fieldCtxt.field->numElements == 1) {
|
||||
ctxt.fieldsDefault += generate(ctxt, fieldCtxt, " // :fieldName\n");
|
||||
if (fieldCtxt.field->type == FIELDTYPE_ENUM) {
|
||||
ctxt.fieldsDefault += generate(ctxt, fieldCtxt, " data_.:fieldName = %1;\n")
|
||||
.arg(fieldCtxt.field->options.indexOf(fieldCtxt.field->defaultValues[0]));
|
||||
} else if (fieldCtxt.field->type == FIELDTYPE_FLOAT32) {
|
||||
ctxt.fieldsDefault += generate(ctxt, fieldCtxt, " data_.:fieldName = %1;\n")
|
||||
.arg(fieldCtxt.field->defaultValues[0].toFloat());
|
||||
} else {
|
||||
ctxt.fieldsDefault += generate(ctxt, fieldCtxt, " data_.:fieldName = %1;\n")
|
||||
.arg(fieldCtxt.field->defaultValues[0].toInt());
|
||||
}
|
||||
} else {
|
||||
// Initialize all fields in the array
|
||||
ctxt.fieldsDefault += generate(ctxt, fieldCtxt, " // :fieldName\n");
|
||||
for (int idx = 0; idx < fieldCtxt.field->numElements; ++idx) {
|
||||
if (fieldCtxt.field->type == FIELDTYPE_ENUM) {
|
||||
ctxt.fieldsDefault += generate(ctxt, fieldCtxt, " data_.:fieldName[%1] = %2;\n")
|
||||
.arg(idx)
|
||||
.arg(fieldCtxt.field->options.indexOf(fieldCtxt.field->defaultValues[idx]));
|
||||
} else if (fieldCtxt.field->type == FIELDTYPE_FLOAT32) {
|
||||
ctxt.fieldsDefault += generate(ctxt, fieldCtxt, " data_.:fieldName[%1] = %2;\n")
|
||||
.arg(idx)
|
||||
.arg(fieldCtxt.field->defaultValues[idx].toFloat());
|
||||
} else {
|
||||
ctxt.fieldsDefault += generate(ctxt, fieldCtxt, " data_.:fieldName[%1] = %2;\n")
|
||||
.arg(idx)
|
||||
.arg(fieldCtxt.field->defaultValues[idx].toInt());
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void generateField(Context &ctxt, FieldContext &fieldCtxt)
|
||||
{
|
||||
if (fieldCtxt.field->numElements > 1) {
|
||||
ctxt.fields += generate(ctxt, fieldCtxt, " :fieldType :fieldName[:elementCount];\n");
|
||||
} else {
|
||||
ctxt.fields += generate(ctxt, fieldCtxt, " :fieldType :fieldName;\n");
|
||||
}
|
||||
generateFieldInfo(ctxt, fieldCtxt);
|
||||
generateFieldInit(ctxt, fieldCtxt);
|
||||
generateFieldDefault(ctxt, fieldCtxt);
|
||||
}
|
||||
|
||||
void generateEnum(Context &ctxt, FieldContext &fieldCtxt)
|
||||
{
|
||||
Q_ASSERT(fieldCtxt.field->type == FIELDTYPE_ENUM);
|
||||
|
||||
QString enumStringList = toEnumStringList(ctxt.object, fieldCtxt.field);
|
||||
|
||||
ctxt.enums += generate(ctxt, fieldCtxt,
|
||||
"class :ClassName_:PropName : public QObject {\n"
|
||||
" Q_OBJECT\n"
|
||||
"public:\n"
|
||||
" enum Enum { %1 };\n"
|
||||
" Q_ENUMS(Enum) // TODO switch to Q_ENUM once on Qt 5.5\n"
|
||||
"};\n\n").arg(enumStringList);
|
||||
|
||||
ctxt.registerImpl += generate(ctxt, fieldCtxt,
|
||||
" qmlRegisterType<:ClassName_:PropName>(\"%1.:ClassName\", 1, 0, \":PropName\");\n").arg("UAVTalk");
|
||||
}
|
||||
|
||||
void generateBaseProperty(Context &ctxt, FieldContext &fieldCtxt)
|
||||
{
|
||||
ctxt.properties += generate(ctxt, fieldCtxt,
|
||||
" Q_PROPERTY(:propType :propName READ :propName WRITE set:PropName NOTIFY :propNameChanged)\n");
|
||||
|
||||
ctxt.getters += generate(ctxt, fieldCtxt, " :propType :propName() const;\n");
|
||||
ctxt.setters += generate(ctxt, fieldCtxt, " void set:PropName(const :propRefType value);\n");
|
||||
|
||||
ctxt.notifications += generate(ctxt, fieldCtxt, " void :propNameChanged(const :propRefType value);\n");
|
||||
ctxt.notificationsImpl += generate(ctxt, fieldCtxt, " emit :propNameChanged(:propName());\n");
|
||||
|
||||
if (DEPRECATED) {
|
||||
// generate deprecated property for retro compatibility
|
||||
if (fieldCtxt.hasDeprecatedProperty) {
|
||||
ctxt.deprecatedProperties += generate(ctxt, fieldCtxt,
|
||||
" /*DEPRECATED*/ Q_PROPERTY(:fieldType :fieldName READ get:fieldName WRITE set:fieldName NOTIFY :fieldNameChanged);\n");
|
||||
}
|
||||
if (fieldCtxt.hasDeprecatedGetter) {
|
||||
ctxt.getters += generate(ctxt, fieldCtxt,
|
||||
" /*DEPRECATED*/ Q_INVOKABLE :fieldType get:fieldName() const { return static_cast<:fieldType>(:propName()); }\n");
|
||||
}
|
||||
if (fieldCtxt.hasDeprecatedSetter) {
|
||||
ctxt.setters += generate(ctxt, fieldCtxt,
|
||||
" /*DEPRECATED*/ void set:fieldName(:fieldType value) { set:fieldName(static_cast<:propType>(value)); }\n");
|
||||
}
|
||||
if (fieldCtxt.hasDeprecatedNotification) {
|
||||
ctxt.notifications += generate(ctxt, fieldCtxt,
|
||||
" /*DEPRECATED*/ void :fieldNameChanged(:fieldType value);\n");
|
||||
|
||||
ctxt.notificationsImpl += generate(ctxt, fieldCtxt,
|
||||
" /*DEPRECATED*/ emit :fieldNameChanged(get:fieldName());\n");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void generateSimpleProperty(Context &ctxt, FieldContext &fieldCtxt)
|
||||
{
|
||||
if (fieldCtxt.field->type == FIELDTYPE_ENUM) {
|
||||
generateEnum(ctxt, fieldCtxt);
|
||||
}
|
||||
|
||||
generateBaseProperty(ctxt, fieldCtxt);
|
||||
|
||||
// getter implementation
|
||||
ctxt.propertiesImpl += generate(ctxt, fieldCtxt,
|
||||
":propType :ClassName:::propName() const\n"
|
||||
"{\n"
|
||||
" QMutexLocker locker(mutex);\n"
|
||||
" return static_cast<:propType>(data_.:fieldName);\n"
|
||||
"}\n");
|
||||
|
||||
// emitters
|
||||
QString emitters = generate(ctxt, fieldCtxt, "emit :propNameChanged(value);");
|
||||
|
||||
if (fieldCtxt.hasDeprecatedNotification) {
|
||||
emitters += " ";
|
||||
emitters += generate(ctxt, fieldCtxt, "emit :fieldNameChanged(static_cast<:fieldType>(value));");
|
||||
}
|
||||
|
||||
// setter implementation
|
||||
ctxt.propertiesImpl += generate(ctxt, fieldCtxt,
|
||||
"void :ClassName::set:PropName(const :propRefType value)\n"
|
||||
"{\n"
|
||||
" mutex->lock();\n"
|
||||
" bool changed = (data_.:fieldName != static_cast<:fieldType>(value));\n"
|
||||
" data_.:fieldName = static_cast<:fieldType>(value);\n"
|
||||
" mutex->unlock();\n"
|
||||
" if (changed) { %1 }\n"
|
||||
"}\n\n").arg(emitters);
|
||||
}
|
||||
|
||||
void generateIndexedProperty(Context &ctxt, FieldContext &fieldCtxt)
|
||||
{
|
||||
if (fieldCtxt.field->type == FIELDTYPE_ENUM) {
|
||||
generateEnum(ctxt, fieldCtxt);
|
||||
}
|
||||
|
||||
// indexed getter/setter
|
||||
ctxt.getters += generate(ctxt, fieldCtxt, " Q_INVOKABLE :propType :propName(quint32 index) const;\n");
|
||||
ctxt.setters += generate(ctxt, fieldCtxt, " Q_INVOKABLE void set:PropName(quint32 index, const :propRefType value);\n");
|
||||
|
||||
// getter implementation
|
||||
ctxt.propertiesImpl += generate(ctxt, fieldCtxt,
|
||||
":propType :ClassName:::propName(quint32 index) const\n"
|
||||
"{\n"
|
||||
" QMutexLocker locker(mutex);\n"
|
||||
" return static_cast<:propType>(data_.:fieldName[index]);\n"
|
||||
"}\n");
|
||||
|
||||
// emitters
|
||||
QString emitters = generate(ctxt, fieldCtxt, "emit :propNameChanged(index, value);");
|
||||
|
||||
if (fieldCtxt.hasDeprecatedNotification) {
|
||||
emitters += " ";
|
||||
emitters += generate(ctxt, fieldCtxt, "emit :fieldNameChanged(index, static_cast<:fieldType>(value));");
|
||||
}
|
||||
|
||||
// setter implementation
|
||||
ctxt.propertiesImpl += generate(ctxt, fieldCtxt,
|
||||
"void :ClassName::set:PropName(quint32 index, const :propRefType value)\n"
|
||||
"{\n"
|
||||
" mutex->lock();\n"
|
||||
" bool changed = (data_.:fieldName[index] != static_cast<:fieldType>(value));\n"
|
||||
" data_.:fieldName[index] = static_cast<:fieldType>(value);\n"
|
||||
" mutex->unlock();\n"
|
||||
" if (changed) { %1 }\n"
|
||||
"}\n\n").arg(emitters);
|
||||
|
||||
ctxt.notifications += generate(ctxt, fieldCtxt, " void :propNameChanged(quint32 index, const :propRefType value);\n");
|
||||
|
||||
if (DEPRECATED) {
|
||||
// backward compatibility
|
||||
if (fieldCtxt.hasDeprecatedGetter) {
|
||||
ctxt.getters += generate(ctxt, fieldCtxt,
|
||||
" /*DEPRECATED*/ Q_INVOKABLE :fieldType get:fieldName(quint32 index) const { return static_cast<:fieldType>(:propName(index)); }\n");
|
||||
}
|
||||
if (fieldCtxt.hasDeprecatedSetter) {
|
||||
ctxt.setters += generate(ctxt, fieldCtxt,
|
||||
" /*DEPRECATED*/ void set:fieldName(quint32 index, :fieldType value) { set:fieldName(index, static_cast<:propType>(value)); }\n");
|
||||
}
|
||||
|
||||
if (fieldCtxt.hasDeprecatedNotification) {
|
||||
ctxt.notifications += generate(ctxt, fieldCtxt,
|
||||
" /*DEPRECATED*/ void :fieldNameChanged(quint32 index, :fieldType value);\n");
|
||||
}
|
||||
}
|
||||
|
||||
for (int elementIndex = 0; elementIndex < fieldCtxt.field->numElements; elementIndex++) {
|
||||
QString elementName = fieldCtxt.field->elementNames[elementIndex];
|
||||
|
||||
FieldContext elementCtxt;
|
||||
elementCtxt.field = fieldCtxt.field;
|
||||
elementCtxt.fieldName = fieldCtxt.fieldName + "_" + elementName;
|
||||
elementCtxt.fieldType = fieldCtxt.fieldType;
|
||||
elementCtxt.propName = fieldCtxt.propName + elementName;
|
||||
elementCtxt.ucPropName = fieldCtxt.ucPropName + elementName;
|
||||
elementCtxt.propType = fieldCtxt.propType;
|
||||
elementCtxt.propRefType = fieldCtxt.propRefType;
|
||||
// deprecation
|
||||
elementCtxt.hasDeprecatedProperty = (elementCtxt.fieldName != elementCtxt.propName) && DEPRECATED;
|
||||
elementCtxt.hasDeprecatedGetter = DEPRECATED;
|
||||
elementCtxt.hasDeprecatedSetter = ((elementCtxt.fieldName != elementCtxt.ucPropName) || (elementCtxt.fieldType != elementCtxt.propType)) && DEPRECATED;
|
||||
elementCtxt.hasDeprecatedNotification = ((elementCtxt.fieldName != elementCtxt.propName) || (elementCtxt.fieldType != elementCtxt.propType)) && DEPRECATED;
|
||||
|
||||
|
||||
generateBaseProperty(ctxt, elementCtxt);
|
||||
|
||||
ctxt.propertiesImpl += generate(ctxt, elementCtxt,
|
||||
":propType :ClassName:::propName() const { return %1(%2); }\n").arg(fieldCtxt.propName).arg(elementIndex);
|
||||
|
||||
ctxt.propertiesImpl += generate(ctxt, elementCtxt,
|
||||
"void :ClassName::set:PropName(const :propRefType value) { set%1(%2, value); }\n").arg(fieldCtxt.ucPropName).arg(elementIndex);
|
||||
}
|
||||
}
|
||||
|
||||
void generateProperty(Context &ctxt, FieldContext &fieldCtxt)
|
||||
{
|
||||
// do some checks
|
||||
QString fieldName = fieldCtxt.fieldName;
|
||||
|
||||
if (fieldName[0].isLower()) {
|
||||
info(ctxt.object, "Field \"" + fieldName + "\" does not start with an upper case letter.");
|
||||
}
|
||||
|
||||
// generate all properties
|
||||
if (fieldCtxt.field->numElements > 1) {
|
||||
generateIndexedProperty(ctxt, fieldCtxt);
|
||||
} else {
|
||||
generateSimpleProperty(ctxt, fieldCtxt);
|
||||
}
|
||||
}
|
||||
|
||||
bool UAVObjectGeneratorGCS::generate(UAVObjectParser *parser, QString templatepath, QString outputpath)
|
||||
{
|
||||
fieldTypeStrCPP << "qint8" << "qint16" << "qint32" <<
|
||||
"quint8" << "quint16" << "quint32" << "float" << "quint8";
|
||||
|
||||
fieldTypeStrCPPClass << "INT8" << "INT16" << "INT32"
|
||||
<< "UINT8" << "UINT16" << "UINT32" << "FLOAT32" << "ENUM";
|
||||
|
||||
gcsCodePath = QDir(templatepath + QString(GCS_CODE_DIR));
|
||||
gcsOutputPath = QDir(outputpath);
|
||||
gcsOutputPath.mkpath(gcsOutputPath.absolutePath());
|
||||
@ -44,7 +549,7 @@ bool UAVObjectGeneratorGCS::generate(UAVObjectParser *parser, QString templatepa
|
||||
QString gcsInitTemplate = readFile(gcsCodePath.absoluteFilePath("uavobjectsinit.cpp.template"));
|
||||
|
||||
if (gcsCodeTemplate.isEmpty() || gcsIncludeTemplate.isEmpty() || gcsInitTemplate.isEmpty()) {
|
||||
std::cerr << "Problem reading gcs code templates" << endl;
|
||||
error("Error: Failed to read gcs code templates.");
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -52,29 +557,42 @@ bool UAVObjectGeneratorGCS::generate(UAVObjectParser *parser, QString templatepa
|
||||
QString gcsObjInit;
|
||||
|
||||
for (int objidx = 0; objidx < parser->getNumObjects(); ++objidx) {
|
||||
ObjectInfo *info = parser->getObjectByIndex(objidx);
|
||||
process_object(info);
|
||||
ObjectInfo *object = parser->getObjectByIndex(objidx);
|
||||
process_object(object);
|
||||
|
||||
gcsObjInit.append(" objMngr->registerObject( new " + info->name + "() );\n");
|
||||
objInc.append("#include \"" + info->namelc + ".h\"\n");
|
||||
Context ctxt;
|
||||
ctxt.object = object;
|
||||
|
||||
objInc.append(QString("#include \"%1.h\"\n").arg(object->namelc));
|
||||
|
||||
gcsObjInit += ::generate(ctxt, " objMngr->registerObject( new :ClassName() );\n");
|
||||
gcsObjInit += ::generate(ctxt, " :ClassName::registerQMLTypes();\n");
|
||||
}
|
||||
|
||||
// Write the gcs object inialization files
|
||||
gcsInitTemplate.replace(QString("$(OBJINC)"), objInc);
|
||||
gcsInitTemplate.replace(QString("$(OBJINIT)"), gcsObjInit);
|
||||
// Write the gcs object initialization files
|
||||
gcsInitTemplate.replace("$(OBJINC)", objInc);
|
||||
gcsInitTemplate.replace("$(OBJINIT)", gcsObjInit);
|
||||
|
||||
bool res = writeFileIfDifferent(gcsOutputPath.absolutePath() + "/uavobjectsinit.cpp", gcsInitTemplate);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write output files" << endl;
|
||||
error("Error: Could not write output files");
|
||||
return false;
|
||||
}
|
||||
|
||||
return true; // if we come here everything should be fine
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Generate the GCS object files
|
||||
*
|
||||
* TODO add getter to get enum names
|
||||
*
|
||||
* TODO handle "char" unit
|
||||
* TODO handle "bool" unit
|
||||
* TODO handle "hex" unit
|
||||
* TODO handle Vector
|
||||
*/
|
||||
bool UAVObjectGeneratorGCS::process_object(ObjectInfo *info)
|
||||
bool UAVObjectGeneratorGCS::process_object(ObjectInfo *object)
|
||||
{
|
||||
if (info == NULL) {
|
||||
return false;
|
||||
@ -85,300 +603,80 @@ bool UAVObjectGeneratorGCS::process_object(ObjectInfo *info)
|
||||
QString outCode = gcsCodeTemplate;
|
||||
|
||||
// Replace common tags
|
||||
replaceCommonTags(outInclude, info);
|
||||
replaceCommonTags(outCode, info);
|
||||
|
||||
// Replace the $(DATAFIELDS) tag
|
||||
QString type;
|
||||
QString fields;
|
||||
for (int n = 0; n < info->fields.length(); ++n) {
|
||||
// Determine type
|
||||
type = fieldTypeStrCPP[info->fields[n]->type];
|
||||
// Append field
|
||||
if (info->fields[n]->numElements > 1) {
|
||||
fields.append(QString(" %1 %2[%3];\n").arg(type).arg(info->fields[n]->name)
|
||||
.arg(info->fields[n]->numElements));
|
||||
} else {
|
||||
fields.append(QString(" %1 %2;\n").arg(type).arg(info->fields[n]->name));
|
||||
}
|
||||
}
|
||||
outInclude.replace(QString("$(DATAFIELDS)"), fields);
|
||||
|
||||
// Replace $(PROPERTIES) and related tags
|
||||
QString properties;
|
||||
QString propertiesImpl;
|
||||
QString propertyGetters;
|
||||
QString propertySetters;
|
||||
QString propertyNotifications;
|
||||
QString propertyNotificationsImpl;
|
||||
replaceCommonTags(outInclude, object);
|
||||
replaceCommonTags(outCode, object);
|
||||
|
||||
// to avoid name conflicts
|
||||
QStringList reservedProperties;
|
||||
reservedProperties << "Description" << "Metadata";
|
||||
|
||||
for (int n = 0; n < info->fields.length(); ++n) {
|
||||
FieldInfo *field = info->fields[n];
|
||||
Context ctxt;
|
||||
ctxt.object = object;
|
||||
|
||||
ctxt.registerImpl += ::generate(ctxt,
|
||||
" qmlRegisterType<:ClassName>(\"%1.:ClassName\", 1, 0, \":ClassName\");\n").arg("UAVTalk");
|
||||
|
||||
for (int n = 0; n < object->fields.length(); ++n) {
|
||||
FieldInfo *field = object->fields[n];
|
||||
|
||||
// field context
|
||||
FieldContext fieldCtxt;
|
||||
fieldCtxt.field = field;
|
||||
|
||||
// field properties
|
||||
fieldCtxt.fieldName = field->name;
|
||||
fieldCtxt.fieldType = fieldTypeStrCPP(field->type);
|
||||
|
||||
fieldCtxt.ucPropName = toPropertyName(field->name);
|
||||
fieldCtxt.propName = toLowerCamelCase(fieldCtxt.ucPropName);
|
||||
fieldCtxt.propType = fieldCtxt.fieldType;
|
||||
fieldCtxt.propRefType = fieldCtxt.fieldType;
|
||||
if (field->type == FIELDTYPE_ENUM) {
|
||||
QString enumClassName = object->name + "_" + fieldCtxt.ucPropName;
|
||||
fieldCtxt.propType = enumClassName + "::Enum";
|
||||
fieldCtxt.propRefType = fieldCtxt.propType;
|
||||
}
|
||||
|
||||
// deprecation
|
||||
fieldCtxt.hasDeprecatedProperty = (fieldCtxt.fieldName != fieldCtxt.propName) && DEPRECATED;
|
||||
fieldCtxt.hasDeprecatedGetter = DEPRECATED;
|
||||
fieldCtxt.hasDeprecatedSetter = ((fieldCtxt.fieldName != fieldCtxt.ucPropName) || (fieldCtxt.fieldType != fieldCtxt.propType)) && DEPRECATED;
|
||||
fieldCtxt.hasDeprecatedNotification = ((fieldCtxt.fieldName != fieldCtxt.propName) || (fieldCtxt.fieldType != fieldCtxt.propType)) && DEPRECATED;
|
||||
|
||||
generateField(ctxt, fieldCtxt);
|
||||
|
||||
if (reservedProperties.contains(field->name)) {
|
||||
warning(object, "Ignoring reserved property " + field->name + ".");
|
||||
continue;
|
||||
}
|
||||
|
||||
// Determine type
|
||||
type = fieldTypeStrCPP[field->type];
|
||||
// Append field
|
||||
if (field->numElements > 1) {
|
||||
// add both field(elementIndex)/setField(elemntIndex,value) and field_element properties
|
||||
// field_element is more convenient if only certain element is used
|
||||
// and much easier to use from the qml side
|
||||
propertyGetters +=
|
||||
QString(" Q_INVOKABLE %1 get%2(quint32 index) const;\n")
|
||||
.arg(type).arg(field->name);
|
||||
propertiesImpl +=
|
||||
QString("%1 %2::get%3(quint32 index) const\n"
|
||||
"{\n"
|
||||
" QMutexLocker locker(mutex);\n"
|
||||
" return data.%3[index];\n"
|
||||
"}\n")
|
||||
.arg(type).arg(info->name).arg(field->name);
|
||||
propertySetters +=
|
||||
QString(" void set%1(quint32 index, %2 value);\n")
|
||||
.arg(field->name).arg(type);
|
||||
propertiesImpl +=
|
||||
QString("void %1::set%2(quint32 index, %3 value)\n"
|
||||
"{\n"
|
||||
" mutex->lock();\n"
|
||||
" bool changed = data.%2[index] != value;\n"
|
||||
" data.%2[index] = value;\n"
|
||||
" mutex->unlock();\n"
|
||||
" if (changed) emit %2Changed(index,value);\n"
|
||||
"}\n\n")
|
||||
.arg(info->name).arg(field->name).arg(type);
|
||||
propertyNotifications +=
|
||||
QString(" void %1Changed(quint32 index, %2 value);\n")
|
||||
.arg(field->name).arg(type);
|
||||
|
||||
for (int elementIndex = 0; elementIndex < field->numElements; elementIndex++) {
|
||||
QString elementName = field->elementNames[elementIndex];
|
||||
properties += QString(" Q_PROPERTY(%1 %2 READ get%2 WRITE set%2 NOTIFY %2Changed);\n")
|
||||
.arg(type).arg(field->name + "_" + elementName);
|
||||
propertyGetters +=
|
||||
QString(" Q_INVOKABLE %1 get%2_%3() const;\n")
|
||||
.arg(type).arg(field->name).arg(elementName);
|
||||
propertiesImpl +=
|
||||
QString("%1 %2::get%3_%4() const\n"
|
||||
"{\n"
|
||||
" QMutexLocker locker(mutex);\n"
|
||||
" return data.%3[%5];\n"
|
||||
"}\n")
|
||||
.arg(type).arg(info->name).arg(field->name).arg(elementName).arg(elementIndex);
|
||||
propertySetters +=
|
||||
QString(" void set%1_%2(%3 value);\n")
|
||||
.arg(field->name).arg(elementName).arg(type);
|
||||
propertiesImpl +=
|
||||
QString("void %1::set%2_%3(%4 value)\n"
|
||||
"{\n"
|
||||
" mutex->lock();\n"
|
||||
" bool changed = data.%2[%5] != value;\n"
|
||||
" data.%2[%5] = value;\n"
|
||||
" mutex->unlock();\n"
|
||||
" if (changed) emit %2_%3Changed(value);\n"
|
||||
"}\n\n")
|
||||
.arg(info->name).arg(field->name).arg(elementName).arg(type).arg(elementIndex);
|
||||
propertyNotifications +=
|
||||
QString(" void %1_%2Changed(%3 value);\n")
|
||||
.arg(field->name).arg(elementName).arg(type);
|
||||
propertyNotificationsImpl +=
|
||||
QString(" //if (data.%1[%2] != oldData.%1[%2])\n"
|
||||
" emit %1_%3Changed(data.%1[%2]);\n")
|
||||
.arg(field->name).arg(elementIndex).arg(elementName);
|
||||
}
|
||||
} else {
|
||||
properties += QString(" Q_PROPERTY(%1 %2 READ get%2 WRITE set%2 NOTIFY %2Changed);\n")
|
||||
.arg(type).arg(field->name);
|
||||
propertyGetters +=
|
||||
QString(" Q_INVOKABLE %1 get%2() const;\n")
|
||||
.arg(type).arg(field->name);
|
||||
propertiesImpl +=
|
||||
QString("%1 %2::get%3() const\n"
|
||||
"{\n"
|
||||
" QMutexLocker locker(mutex);\n"
|
||||
" return data.%3;\n"
|
||||
"}\n")
|
||||
.arg(type).arg(info->name).arg(field->name);
|
||||
propertySetters +=
|
||||
QString(" void set%1(%2 value);\n")
|
||||
.arg(field->name).arg(type);
|
||||
propertiesImpl +=
|
||||
QString("void %1::set%2(%3 value)\n"
|
||||
"{\n"
|
||||
" mutex->lock();\n"
|
||||
" bool changed = data.%2 != value;\n"
|
||||
" data.%2 = value;\n"
|
||||
" mutex->unlock();\n"
|
||||
" if (changed) emit %2Changed(value);\n"
|
||||
"}\n\n")
|
||||
.arg(info->name).arg(field->name).arg(type);
|
||||
propertyNotifications +=
|
||||
QString(" void %1Changed(%2 value);\n")
|
||||
.arg(field->name).arg(type);
|
||||
propertyNotificationsImpl +=
|
||||
QString(" //if (data.%1 != oldData.%1)\n"
|
||||
" emit %1Changed(data.%1);\n")
|
||||
.arg(field->name);
|
||||
}
|
||||
generateProperty(ctxt, fieldCtxt);
|
||||
}
|
||||
|
||||
outInclude.replace(QString("$(PROPERTIES)"), properties);
|
||||
outInclude.replace(QString("$(PROPERTY_GETTERS)"), propertyGetters);
|
||||
outInclude.replace(QString("$(PROPERTY_SETTERS)"), propertySetters);
|
||||
outInclude.replace(QString("$(PROPERTY_NOTIFICATIONS)"), propertyNotifications);
|
||||
outInclude.replace("$(ENUMS)", ctxt.enums);
|
||||
outInclude.replace("$(DATAFIELDS)", ctxt.fields);
|
||||
outInclude.replace("$(DATAFIELDINFO)", ctxt.fieldsInfo);
|
||||
outInclude.replace("$(PROPERTIES)", ctxt.properties);
|
||||
outInclude.replace("$(DEPRECATED_PROPERTIES)", ctxt.deprecatedProperties);
|
||||
outInclude.replace("$(PROPERTY_GETTERS)", ctxt.getters);
|
||||
outInclude.replace("$(PROPERTY_SETTERS)", ctxt.setters);
|
||||
outInclude.replace("$(PROPERTY_NOTIFICATIONS)", ctxt.notifications);
|
||||
|
||||
outCode.replace(QString("$(PROPERTIES_IMPL)"), propertiesImpl);
|
||||
outCode.replace(QString("$(NOTIFY_PROPERTIES_CHANGED)"), propertyNotificationsImpl);
|
||||
|
||||
// Replace the $(FIELDSINIT) tag
|
||||
QString finit;
|
||||
for (int n = 0; n < info->fields.length(); ++n) {
|
||||
// Setup element names
|
||||
QString varElemName = info->fields[n]->name + "ElemNames";
|
||||
finit.append(QString(" QStringList %1;\n").arg(varElemName));
|
||||
QStringList elemNames = info->fields[n]->elementNames;
|
||||
for (int m = 0; m < elemNames.length(); ++m) {
|
||||
finit.append(QString(" %1.append(\"%2\");\n")
|
||||
.arg(varElemName)
|
||||
.arg(elemNames[m]));
|
||||
}
|
||||
|
||||
// Only for enum types
|
||||
if (info->fields[n]->type == FIELDTYPE_ENUM) {
|
||||
QString varOptionName = info->fields[n]->name + "EnumOptions";
|
||||
finit.append(QString(" QStringList %1;\n").arg(varOptionName));
|
||||
QStringList options = info->fields[n]->options;
|
||||
for (int m = 0; m < options.length(); ++m) {
|
||||
finit.append(QString(" %1.append(\"%2\");\n")
|
||||
.arg(varOptionName)
|
||||
.arg(options[m]));
|
||||
}
|
||||
finit.append(QString(" fields.append( new UAVObjectField(QString(\"%1\"), tr(\"%2\"), QString(\"%3\"), UAVObjectField::ENUM, %4, %5, QString(\"%6\")));\n")
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(info->fields[n]->description)
|
||||
.arg(info->fields[n]->units)
|
||||
.arg(varElemName)
|
||||
.arg(varOptionName)
|
||||
.arg(info->fields[n]->limitValues));
|
||||
}
|
||||
// For all other types
|
||||
else {
|
||||
finit.append(QString(" fields.append( new UAVObjectField(QString(\"%1\"), tr(\"%2\"), QString(\"%3\"), UAVObjectField::%4, %5, QStringList(), QString(\"%6\")));\n")
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(info->fields[n]->description)
|
||||
.arg(info->fields[n]->units)
|
||||
.arg(fieldTypeStrCPPClass[info->fields[n]->type])
|
||||
.arg(varElemName)
|
||||
.arg(info->fields[n]->limitValues));
|
||||
}
|
||||
}
|
||||
outCode.replace(QString("$(FIELDSINIT)"), finit);
|
||||
|
||||
// Replace the $(DATAFIELDINFO) tag
|
||||
QString name;
|
||||
QString enums;
|
||||
for (int n = 0; n < info->fields.length(); ++n) {
|
||||
enums.append(QString(" // Field %1 information\n").arg(info->fields[n]->name));
|
||||
// Only for enum types
|
||||
if (info->fields[n]->type == FIELDTYPE_ENUM) {
|
||||
enums.append(QString(" /* Enumeration options for field %1 */\n").arg(info->fields[n]->name));
|
||||
enums.append(" typedef enum { ");
|
||||
// Go through each option
|
||||
QStringList options = info->fields[n]->options;
|
||||
for (int m = 0; m < options.length(); ++m) {
|
||||
QString s = (m != (options.length() - 1)) ? "%1_%2=%3, " : "%1_%2=%3";
|
||||
enums.append(s.arg(info->fields[n]->name.toUpper())
|
||||
.arg(options[m].toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), ""))
|
||||
.arg(m));
|
||||
}
|
||||
enums.append(QString(" } %1Options;\n")
|
||||
.arg(info->fields[n]->name));
|
||||
}
|
||||
// Generate element names (only if field has more than one element)
|
||||
if (info->fields[n]->numElements > 1 && !info->fields[n]->defaultElementNames) {
|
||||
enums.append(QString(" /* Array element names for field %1 */\n").arg(info->fields[n]->name));
|
||||
enums.append(" typedef enum { ");
|
||||
// Go through the element names
|
||||
QStringList elemNames = info->fields[n]->elementNames;
|
||||
for (int m = 0; m < elemNames.length(); ++m) {
|
||||
QString s = (m != (elemNames.length() - 1)) ? "%1_%2=%3, " : "%1_%2=%3";
|
||||
enums.append(s.arg(info->fields[n]->name.toUpper())
|
||||
.arg(elemNames[m].toUpper())
|
||||
.arg(m));
|
||||
}
|
||||
enums.append(QString(" } %1Elem;\n")
|
||||
.arg(info->fields[n]->name));
|
||||
}
|
||||
// Generate array information
|
||||
if (info->fields[n]->numElements > 1) {
|
||||
enums.append(QString(" /* Number of elements for field %1 */\n").arg(info->fields[n]->name));
|
||||
enums.append(QString(" static const quint32 %1_NUMELEM = %2;\n")
|
||||
.arg(info->fields[n]->name.toUpper())
|
||||
.arg(info->fields[n]->numElements));
|
||||
}
|
||||
}
|
||||
outInclude.replace(QString("$(DATAFIELDINFO)"), enums);
|
||||
|
||||
// Replace the $(INITFIELDS) tag
|
||||
QString initfields;
|
||||
for (int n = 0; n < info->fields.length(); ++n) {
|
||||
if (!info->fields[n]->defaultValues.isEmpty()) {
|
||||
// For non-array fields
|
||||
if (info->fields[n]->numElements == 1) {
|
||||
if (info->fields[n]->type == FIELDTYPE_ENUM) {
|
||||
initfields.append(QString(" data.%1 = %2;\n")
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(info->fields[n]->options.indexOf(info->fields[n]->defaultValues[0])));
|
||||
} else if (info->fields[n]->type == FIELDTYPE_FLOAT32) {
|
||||
initfields.append(QString(" data.%1 = %2;\n")
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(info->fields[n]->defaultValues[0].toFloat()));
|
||||
} else {
|
||||
initfields.append(QString(" data.%1 = %2;\n")
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(info->fields[n]->defaultValues[0].toInt()));
|
||||
}
|
||||
} else {
|
||||
// Initialize all fields in the array
|
||||
for (int idx = 0; idx < info->fields[n]->numElements; ++idx) {
|
||||
if (info->fields[n]->type == FIELDTYPE_ENUM) {
|
||||
initfields.append(QString(" data.%1[%2] = %3;\n")
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(idx)
|
||||
.arg(info->fields[n]->options.indexOf(info->fields[n]->defaultValues[idx])));
|
||||
} else if (info->fields[n]->type == FIELDTYPE_FLOAT32) {
|
||||
initfields.append(QString(" data.%1[%2] = %3;\n")
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(idx)
|
||||
.arg(info->fields[n]->defaultValues[idx].toFloat()));
|
||||
} else {
|
||||
initfields.append(QString(" data.%1[%2] = %3;\n")
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(idx)
|
||||
.arg(info->fields[n]->defaultValues[idx].toInt()));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
outCode.replace(QString("$(INITFIELDS)"), initfields);
|
||||
outCode.replace("$(FIELDSINIT)", ctxt.fieldsInit);
|
||||
outCode.replace("$(FIELDSDEFAULT)", ctxt.fieldsDefault);
|
||||
outCode.replace("$(PROPERTIES_IMPL)", ctxt.propertiesImpl);
|
||||
outCode.replace("$(NOTIFY_PROPERTIES_CHANGED)", ctxt.notificationsImpl);
|
||||
outCode.replace("$(REGISTER_QML_TYPES)", ctxt.registerImpl);
|
||||
|
||||
// Write the GCS code
|
||||
bool res = writeFileIfDifferent(gcsOutputPath.absolutePath() + "/" + info->namelc + ".cpp", outCode);
|
||||
bool res = writeFileIfDifferent(gcsOutputPath.absolutePath() + "/" + object->namelc + ".cpp", outCode);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write gcs output files" << endl;
|
||||
error("Error: Could not write gcs output files");
|
||||
return false;
|
||||
}
|
||||
res = writeFileIfDifferent(gcsOutputPath.absolutePath() + "/" + info->namelc + ".h", outInclude);
|
||||
res = writeFileIfDifferent(gcsOutputPath.absolutePath() + "/" + object->namelc + ".h", outInclude);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write gcs output files" << endl;
|
||||
error("Error: Could not write gcs output files");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -39,7 +39,6 @@ private:
|
||||
bool process_object(ObjectInfo *info);
|
||||
|
||||
QString gcsCodeTemplate, gcsIncludeTemplate;
|
||||
QStringList fieldTypeStrCPP, fieldTypeStrCPPClass;
|
||||
QDir gcsCodePath;
|
||||
QDir gcsOutputPath;
|
||||
};
|
||||
|
@ -16,15 +16,17 @@ s,<GITWEB_URL>,$(GITWEB_URL),g; \
|
||||
|
||||
# Are we using a debian based distro?
|
||||
ifneq ($(wildcard /etc/apt/sources.list),)
|
||||
include $(ROOT_DIR)/package/linux/deb.mk
|
||||
PKG_TYPE := deb
|
||||
# Are we using a rpm based distro?
|
||||
else ifneq ($(wildcard /etc/yum.repos.d/*),)
|
||||
include $(ROOT_DIR)/package/linux/rpm.mk
|
||||
PKG_TYPE := rpm
|
||||
# Are we using an Arch based distro?
|
||||
else ifneq ($(wildcard /etc/pacman.conf),)
|
||||
$(info TODO: built in arch package)
|
||||
endif
|
||||
|
||||
-include $(ROOT_DIR)/package/linux/$(PKG_TYPE).mk
|
||||
|
||||
##############################
|
||||
#
|
||||
# Install Linux Target
|
||||
|
@ -1,7 +1,4 @@
|
||||
# Get some info about the distro
|
||||
-include /etc/lsb-release
|
||||
|
||||
DEB_DIST := $(DISTRIB_CODENAME)
|
||||
DEB_DIST := $(shell lsb_release -c -s)
|
||||
# Instead of RELEASE-15.01-RC1 debian wants 15.01~RC1
|
||||
UPSTREAM_VER := $(subst -,~,$(subst RELEASE-,,$(PACKAGE_LBL)))
|
||||
ifeq ($(DEB_DIST), unstable) # This should be set manually for a submission to Debian or similar
|
||||
|
@ -2,8 +2,8 @@ RPM_NAME := $(PACKAGE_NAME)
|
||||
UPSTREAM_VER := $(subst -,~,$(subst RELEASE-,,$(DIST_LBL)))
|
||||
RPM_REL := 1
|
||||
RPM_ARCH := $(shell rpm --eval '%{_arch}')
|
||||
RPM_PACKAGE_NAME := $(RPM_NAME)-$(UPSTREAM_VER)-$(RPM_REL)$(shell rpm --eval '%{?dist}').$(RPM_ARCH).rpm
|
||||
RPM_PACKAGE_FILE := $(PACKAGE_DIR)/RPMS/$(RPM_ARCH)/$(RPM_PACKAGE_NAME)
|
||||
RPM_PACKAGE_NAME := $(RPM_NAME)-$(UPSTREAM_VER)-$(RPM_REL)
|
||||
RPM_PACKAGE_FILE := $(PACKAGE_DIR)/RPMS/$(RPM_ARCH)/$(RPM_PACKAGE_NAME)$(shell rpm --eval '%{?dist}').$(RPM_ARCH).rpm
|
||||
RPM_PACKAGE_SRC := $(PACKAGE_DIR)/SRPMS/$(RPM_PACKAGE_NAME).src.rpm
|
||||
|
||||
SED_SCRIPT := $(SED_SCRIPT)' \
|
||||
|
@ -8,11 +8,11 @@
|
||||
<field name="ChannelMin" units="us" type="int16" elements="12" defaultvalue="1000"/>
|
||||
<field name="ChannelType" units="" type="enum" elements="12" options="PWM,MK,ASTEC4,PWM Alarm Buzzer,Arming led,Info led" defaultvalue="PWM"/>
|
||||
<field name="ChannelAddr" units="" type="uint8" elements="12" defaultvalue="0,1,2,3,4,5,6,7,8,9,10,11"/>
|
||||
<field name="MotorsSpinWhileArmed" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="LowThrottleZeroAxis" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="FALSE,TRUE" defaultvalue="FALSE,FALSE,FALSE"/>
|
||||
<field name="MotorsSpinWhileArmed" units="" type="enum" elements="1" options="False,True" defaultvalue="False"/>
|
||||
<field name="LowThrottleZeroAxis" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="False,True" defaultvalue="False,False,False"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
</object>
|
||||
</object>
|
||||
</xml>
|
||||
|
@ -9,8 +9,8 @@
|
||||
<field name="MagKp" units="" type="float" elements="1" defaultvalue="0.01"/>
|
||||
<field name="AccelTau" units="" type="float" elements="1" defaultvalue="0"/>
|
||||
<field name="YawBiasRate" units="channel" type="float" elements="1" defaultvalue="0.000001"/>
|
||||
<field name="ZeroDuringArming" units="channel" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
|
||||
<field name="BiasCorrectGyro" units="channel" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
|
||||
<field name="ZeroDuringArming" units="channel" type="enum" elements="1" options="False,True" defaultvalue="True"/>
|
||||
<field name="BiasCorrectGyro" units="channel" type="enum" elements="1" options="False,True" defaultvalue="True"/>
|
||||
<field name="TrimFlight" units="channel" type="enum" elements="1" options="NORMAL,START,LOAD" defaultvalue="NORMAL"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
|
@ -13,8 +13,8 @@
|
||||
<field name="MaxAccel" units="units/sec" type="uint16" elements="1" defaultvalue="500"/>
|
||||
<field name="AccelTime" units="ms" type="uint8" elementnames="Roll,Pitch,Yaw" defaultvalue="5"/>
|
||||
<field name="DecelTime" units="ms" type="uint8" elementnames="Roll,Pitch,Yaw" defaultvalue="5"/>
|
||||
<field name="Servo1PitchReverse" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="Servo2PitchReverse" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="Servo1PitchReverse" units="" type="enum" elements="1" options="False,True" defaultvalue="False"/>
|
||||
<field name="Servo2PitchReverse" units="" type="enum" elements="1" options="False,True" defaultvalue="False"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
|
@ -7,7 +7,7 @@
|
||||
<field name="Capacity" units="mAh" type="uint32" elements="1" defaultvalue="2200"/>
|
||||
<field name="CellVoltageThresholds" units="V" type="float" elementnames="Warning, Alarm" defaultvalue="3.4,3.1"/>
|
||||
<field name="SensorCalibrations" units="" type="float" elementnames="VoltageFactor, CurrentFactor, VoltageZero, CurrentZero" defaultvalue="1.0, 1.0, 0.0, 0.0"/>
|
||||
<field name="ResetConsumedEnergy" units="bool" type="enum" elements="1" options="false,true" defaultvalue="false"/>
|
||||
<field name="ResetConsumedEnergy" units="bool" type="enum" elements="1" options="False,True" defaultvalue="False"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
|
@ -75,11 +75,11 @@
|
||||
%NE:POI:AutoCruise; \
|
||||
%NE:POI:AutoCruise;" />
|
||||
|
||||
<field name="AlwaysStabilizeWhenArmed" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE" description="For Multirotors. Always stabilize no matter the throttle setting when vehicle is armed. Does not work when vehicle is set to Always Armed."/>
|
||||
<field name="AlwaysStabilizeWhenArmed" units="" type="enum" elements="1" options="False,True" defaultvalue="False" description="For Multirotors. Always stabilize no matter the throttle setting when vehicle is armed. Does not work when vehicle is set to Always Armed."/>
|
||||
<field name="ArmedTimeout" units="ms" type="uint16" elements="1" defaultvalue="30000"/>
|
||||
<field name="ArmingSequenceTime" units="ms" type="uint16" elements="1" defaultvalue="1000"/>
|
||||
<field name="DisarmingSequenceTime" units="ms" type="uint16" elements="1" defaultvalue="1000"/>
|
||||
<field name="DisableSanityChecks" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="DisableSanityChecks" units="" type="enum" elements="1" options="False,True" defaultvalue="False"/>
|
||||
<field name="ReturnToBaseAltitudeOffset" units="m" type="float" elements="1" defaultvalue="10"/>
|
||||
<field name="ReturnToBaseNextCommand" units="" type="enum" elements="1" options="Hold,Land" defaultvalue="Hold"/>
|
||||
<field name="LandingVelocity" units="m" type="float" elements="1" defaultvalue="0.6"/>
|
||||
|
@ -10,7 +10,7 @@
|
||||
<field name="AssistedControlState" units="" type="enum" elements="1" options="Primary,Brake,Hold" defaultvalue="Primary"/>
|
||||
<field name="AssistedThrottleState" units="" type="enum" elements="1" options="Manual,Auto,AutoOverride" defaultvalue="Manual"/>
|
||||
|
||||
<field name="ControlChain" units="bool" type="enum" options="false,true">
|
||||
<field name="ControlChain" units="bool" type="enum" options="False,True">
|
||||
<elementnames>
|
||||
<elementname>Stabilization</elementname>
|
||||
<elementname>PathFollower</elementname>
|
||||
|
@ -13,7 +13,7 @@
|
||||
<field name="HDOP" units="" type="float" elements="1"/>
|
||||
<field name="VDOP" units="" type="float" elements="1"/>
|
||||
<field name="SensorType" units="" type="enum" elements="1" options="Unknown,NMEA,UBX,UBX7,UBX8" defaultvalue="Unknown" />
|
||||
<field name="AutoConfigStatus" units="" type="enum" elements="1" options="DISABLED,RUNNING,DONE,ERROR" defaultvalue="DISABLED" />
|
||||
<field name="AutoConfigStatus" units="" type="enum" elements="1" options="Disabled,Running,Done,Error" defaultvalue="Disabled" />
|
||||
<field name="BaudRate" units="" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200,230400,Unknown" defaultvalue="Unknown" />
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="false" updatemode="manual" period="0"/>
|
||||
|
@ -1,7 +1,7 @@
|
||||
<xml>
|
||||
<object name="HomeLocation" singleinstance="true" settings="true" category="Navigation">
|
||||
<description>HomeLocation setting which contains the constants to translate from longitude and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule.</description>
|
||||
<field name="Set" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="Set" units="" type="enum" elements="1" options="False,True" defaultvalue="False"/>
|
||||
<field name="Latitude" units="deg * 10e6" type="int32" elements="1" defaultvalue="0"/>
|
||||
<field name="Longitude" units="deg * 10e6" type="int32" elements="1" defaultvalue="0"/>
|
||||
<field name="Altitude" units="m over geoid" type="float" elements="1" defaultvalue="0"/>
|
||||
|
@ -1,10 +1,10 @@
|
||||
<xml>
|
||||
<object name="OPLinkSettings" singleinstance="true" settings="true" category="System">
|
||||
<description>OPLink configurations options.</description>
|
||||
<field name="Coordinator" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="OneWay" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="PPM" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="PPMOnly" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="Coordinator" units="" type="enum" elements="1" options="False,True" defaultvalue="False"/>
|
||||
<field name="OneWay" units="" type="enum" elements="1" options="False,True" defaultvalue="False"/>
|
||||
<field name="PPM" units="" type="enum" elements="1" options="False,True" defaultvalue="False"/>
|
||||
<field name="PPMOnly" units="" type="enum" elements="1" options="False,True" defaultvalue="False"/>
|
||||
<field name="CoordID" units="hex" type="uint32" elements="1" defaultvalue="0"/>
|
||||
<field name="MainPort" units="" type="enum" elements="1" options="Disabled,Telemetry,Serial,PPM,PWM" defaultvalue="Disabled"/>
|
||||
<field name="FlexiPort" units="" type="enum" elements="1" options="Disabled,Telemetry,Serial,PPM,PWM" defaultvalue="Disabled"/>
|
||||
|
@ -6,7 +6,7 @@
|
||||
defaultvalue="1,0,0,0,1,0,0,0,1"/>
|
||||
<!-- These settings are related to how the sensors are post processed -->
|
||||
<!-- TODO: reimplement, put elsewhere (later) -->
|
||||
<field name="BiasCorrectedRaw" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
|
||||
<field name="BiasCorrectedRaw" units="" type="enum" elements="1" options="False,True" defaultvalue="True"/>
|
||||
<field name="MagBiasNullingRate" units="" type="float" elements="1" defaultvalue="0"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
|
@ -18,9 +18,9 @@
|
||||
|
||||
<field name="AcroInsanityFactor" units="percent" type="uint8" elementnames="Roll,Pitch,Yaw" defaultvalue="40" limits="%BE:0:100"/>
|
||||
|
||||
<field name="EnablePiroComp" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
|
||||
<field name="EnablePiroComp" units="" type="enum" elements="1" options="False,True" defaultvalue="True"/>
|
||||
|
||||
<field name="EnableThrustPIDScaling" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="EnableThrustPIDScaling" units="" type="enum" elements="1" options="False,True" defaultvalue="False"/>
|
||||
<field name="ThrustPIDScaleCurve" units="percent" type="int8" elementnames="0,25,50,75,100" defaultvalue="30,15,0,-15,-30"/>
|
||||
<field name="ThrustPIDScaleSource" units="" type="enum" elements="1" options="ManualControlThrottle,StabilizationDesiredThrust,ActuatorDesiredThrust" defaultvalue="ActuatorDesiredThrust" />
|
||||
<field name="ThrustPIDScaleTarget" units="" type="enum" elements="1" options="PID,PI,PD,ID,P,I,D" defaultvalue="PID" />
|
||||
|
@ -15,7 +15,7 @@
|
||||
<field name="VbarYawPI" units="1/(deg/s)" type="float" elementnames="Kp,Ki" defaultvalue="0.005,0.002"/>
|
||||
<field name="VbarTau" units="sec" type="float" elements="1" defaultvalue="0.5"/>
|
||||
<field name="VbarGyroSuppress" units="%" type="int8" elements="1" defaultvalue="30"/>
|
||||
<field name="VbarPiroComp" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="VbarPiroComp" units="" type="enum" elements="1" options="False,True" defaultvalue="False"/>
|
||||
<field name="VbarMaxAngle" units="deg" type="uint8" elements="1" defaultvalue="10"/>
|
||||
|
||||
<field name="GyroTau" units="" type="float" elements="1" defaultvalue="0.003"/>
|
||||
@ -37,12 +37,12 @@
|
||||
<field name="CruiseControlMaxPowerFactor" units="x" type="float" elements="1" defaultvalue="3.0"/>
|
||||
<field name="CruiseControlPowerTrim" units="%" type="float" elements="1" defaultvalue="100.0"/>
|
||||
<field name="CruiseControlPowerDelayComp" units="sec" type="float" elements="1" defaultvalue="0.25"/>
|
||||
<field name="CruiseControlFlightModeSwitchPosEnable" units="" type="enum" elements="6" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="CruiseControlFlightModeSwitchPosEnable" units="" type="enum" elements="6" options="False,True" defaultvalue="False"/>
|
||||
|
||||
<field name="CruiseControlInvertedThrustReversing" units="" type="enum" elements="1" options="Unreversed,Reversed" defaultvalue="Unreversed"/>
|
||||
<field name="CruiseControlInvertedPowerOutput" units="" type="enum" elements="1" options="Zero,Normal,Boosted" defaultvalue="Zero"/>
|
||||
|
||||
<field name="LowThrottleZeroIntegral" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
|
||||
<field name="LowThrottleZeroIntegral" units="" type="enum" elements="1" options="False,True" defaultvalue="True"/>
|
||||
|
||||
<field name="ScaleToAirspeed" units="m/s" type="float" elements="1" defaultvalue="0"/>
|
||||
<field name="ScaleToAirspeedLimits" units="" type="float" elementnames="Min,Max" defaultvalue="0.05,3"/>
|
||||
|
@ -18,9 +18,9 @@
|
||||
|
||||
<field name="AcroInsanityFactor" units="percent" type="uint8" elementnames="Roll,Pitch,Yaw" defaultvalue="40" limits="%BE:0:100"/>
|
||||
|
||||
<field name="EnablePiroComp" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
|
||||
<field name="EnablePiroComp" units="" type="enum" elements="1" options="False,True" defaultvalue="True"/>
|
||||
|
||||
<field name="EnableThrustPIDScaling" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="EnableThrustPIDScaling" units="" type="enum" elements="1" options="False,True" defaultvalue="False"/>
|
||||
<field name="ThrustPIDScaleCurve" units="percent" type="int8" elementnames="0,25,50,75,100" defaultvalue="30,15,0,-15,-30"/>
|
||||
<field name="ThrustPIDScaleSource" units="" type="enum" elements="1" options="ManualControlThrottle,StabilizationDesiredThrust,ActuatorDesiredThrust" defaultvalue="ActuatorDesiredThrust" />
|
||||
<field name="ThrustPIDScaleTarget" units="" type="enum" elements="1" options="PID,PI,PD,ID,P,I,D" defaultvalue="PID" />
|
||||
|
@ -18,9 +18,9 @@
|
||||
|
||||
<field name="AcroInsanityFactor" units="percent" type="uint8" elementnames="Roll,Pitch,Yaw" defaultvalue="40" limits="%BE:0:100"/>
|
||||
|
||||
<field name="EnablePiroComp" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
|
||||
<field name="EnablePiroComp" units="" type="enum" elements="1" options="False,True" defaultvalue="True"/>
|
||||
|
||||
<field name="EnableThrustPIDScaling" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="EnableThrustPIDScaling" units="" type="enum" elements="1" options="False,True" defaultvalue="False"/>
|
||||
<field name="ThrustPIDScaleCurve" units="percent" type="int8" elementnames="0,25,50,75,100" defaultvalue="30,15,0,-15,-30"/>
|
||||
<field name="ThrustPIDScaleSource" units="" type="enum" elements="1" options="ManualControlThrottle,StabilizationDesiredThrust,ActuatorDesiredThrust" defaultvalue="ActuatorDesiredThrust" />
|
||||
<field name="ThrustPIDScaleTarget" units="" type="enum" elements="1" options="PID,PI,PD,ID,P,I,D" defaultvalue="PID" />
|
||||
|
@ -18,9 +18,9 @@
|
||||
|
||||
<field name="AcroInsanityFactor" units="percent" type="uint8" elementnames="Roll,Pitch,Yaw" defaultvalue="40" limits="%BE:0:100"/>
|
||||
|
||||
<field name="EnablePiroComp" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
|
||||
<field name="EnablePiroComp" units="" type="enum" elements="1" options="False,True" defaultvalue="True"/>
|
||||
|
||||
<field name="EnableThrustPIDScaling" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="EnableThrustPIDScaling" units="" type="enum" elements="1" options="False,True" defaultvalue="False"/>
|
||||
<field name="ThrustPIDScaleCurve" units="percent" type="int8" elementnames="0,25,50,75,100" defaultvalue="30,15,0,-15,-30"/>
|
||||
<field name="ThrustPIDScaleSource" units="" type="enum" elements="1" options="ManualControlThrottle,StabilizationDesiredThrust,ActuatorDesiredThrust" defaultvalue="ActuatorDesiredThrust" />
|
||||
<field name="ThrustPIDScaleTarget" units="" type="enum" elements="1" options="PID,PI,PD,ID,P,I,D" defaultvalue="PID" />
|
||||
|
@ -30,7 +30,7 @@
|
||||
|
||||
<field name="EasyTunePitchRollRateFactors" units="" type="float" elementnames="I,D" defaultvalue="3,0.0135"/>
|
||||
<field name="EasyTuneYawRateFactors" units="" type="float" elementnames="P,I,D" defaultvalue="1.5,1.9,0.0085"/>
|
||||
<field name="EasyTuneRatePIDRecalculateYaw" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
|
||||
<field name="EasyTuneRatePIDRecalculateYaw" units="" type="enum" elements="1" options="False,True" defaultvalue="True"/>
|
||||
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
|
@ -11,9 +11,9 @@
|
||||
<field name="VerticalVelPID" units="(m/s^2)/(m/s)" type="float" elementnames="Kp,Ki,Kd,Beta" defaultvalue="0.15, 0.25, 0.005, 0.95"/>
|
||||
<field name="ThrustLimits" units="" type="float" elementnames="Min,Neutral,Max" defaultvalue="0.2, 0.5, 0.9"/>
|
||||
<field name="VelocityFeedforward" units="deg/(m/s)" type="float" elements="1" defaultvalue="2"/>
|
||||
<field name="ThrustControl" units="" type="enum" elements="1" options="manual,auto" defaultvalue="auto"/>
|
||||
<field name="YawControl" units="" type="enum" elements="1" options="manual,tailin,movementdirection,pathdirection,poi" defaultvalue="manual"/>
|
||||
<field name="FlyawayEmergencyFallback" units="switch" type="enum" elements="1" options="disabled,enabled,always,debugtest" defaultvalue="enabled"/>
|
||||
<field name="ThrustControl" units="" type="enum" elements="1" options="Manual,Auto" defaultvalue="Auto"/>
|
||||
<field name="YawControl" units="" type="enum" elements="1" options="Manual,Tailin,MovementDirection,PathDirection,POI" defaultvalue="Manual"/>
|
||||
<field name="FlyawayEmergencyFallback" units="switch" type="enum" elements="1" options="Disabled,Enabled,Always,DebugTest" defaultvalue="Enabled"/>
|
||||
<field name="FlyawayEmergencyFallbackTriggerTime" units="s" type="float" elements="1" defaultvalue="10.0"/>
|
||||
<field name="EmergencyFallbackAttitude" units="deg" type="float" elementnames="Roll,Pitch" defaultvalue="0,-20.0"/>
|
||||
<field name="EmergencyFallbackYawRate" units="(deg/s)/deg" type="float" elementnames="kP,Max" defaultvalue="2.0, 30.0"/>
|
||||
|
Loading…
Reference in New Issue
Block a user