Commit 9efdddb2 authored by Don Gagne's avatar Don Gagne

Merge pull request #2110 from DonLakeFlyer/DecimalPlus

Decimal place support + other fixes
parents 95cec0e0 f1c93eb5
......@@ -131,7 +131,22 @@ QVariant Fact::value(void) const
QString Fact::valueString(void) const
{
return _value.toString();
QString valueString;
switch (type()) {
case FactMetaData::valueTypeFloat:
qDebug() << name() << value() << decimalPlaces();
valueString = QString("%1").arg(value().toFloat(), 0, 'g', decimalPlaces());
break;
case FactMetaData::valueTypeDouble:
valueString = QString("%1").arg(value().toDouble(), 0, 'g', decimalPlaces());
break;
default:
valueString = value().toString();
break;
}
return valueString;
}
QVariant Fact::defaultValue(void) const
......@@ -222,6 +237,16 @@ bool Fact::maxIsDefaultForType(void) const
}
}
int Fact::decimalPlaces(void) const
{
if (_metaData) {
return _metaData->decimalPlaces();
} else {
qWarning() << "Meta data pointer missing";
return FactMetaData::defaultDecimalPlaces;
}
}
QString Fact::group(void) const
{
if (_metaData) {
......
......@@ -46,22 +46,23 @@ public:
const Fact& operator=(const Fact& other);
Q_PROPERTY(int componentId READ componentId CONSTANT)
Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged USER true)
Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged)
Q_PROPERTY(QString units READ units CONSTANT)
Q_PROPERTY(QVariant defaultValue READ defaultValue CONSTANT)
Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable CONSTANT)
Q_PROPERTY(bool valueEqualsDefault READ valueEqualsDefault NOTIFY valueChanged)
Q_PROPERTY(FactMetaData::ValueType_t type READ type CONSTANT)
Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT)
Q_PROPERTY(QString longDescription READ longDescription CONSTANT)
Q_PROPERTY(QVariant min READ min CONSTANT)
Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT)
Q_PROPERTY(QVariant max READ max CONSTANT)
Q_PROPERTY(bool maxIsDefaultForType READ maxIsDefaultForType CONSTANT)
Q_PROPERTY(QString group READ group CONSTANT)
Q_PROPERTY(int componentId READ componentId CONSTANT)
Q_PROPERTY(QString group READ group CONSTANT)
Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged USER true)
Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged)
Q_PROPERTY(QString units READ units CONSTANT)
Q_PROPERTY(QVariant defaultValue READ defaultValue CONSTANT)
Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable CONSTANT)
Q_PROPERTY(bool valueEqualsDefault READ valueEqualsDefault NOTIFY valueChanged)
Q_PROPERTY(FactMetaData::ValueType_t type READ type CONSTANT)
Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT)
Q_PROPERTY(QString longDescription READ longDescription CONSTANT)
Q_PROPERTY(QVariant min READ min CONSTANT)
Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT)
Q_PROPERTY(QVariant max READ max CONSTANT)
Q_PROPERTY(bool maxIsDefaultForType READ maxIsDefaultForType CONSTANT)
Q_PROPERTY(int decimalPlaces READ decimalPlaces CONSTANT)
/// Convert and validate value
/// @param convertOnly true: validate type conversion only, false: validate against meta data as well
......@@ -86,6 +87,7 @@ public:
QVariant max(void) const;
bool maxIsDefaultForType(void) const;
QString group(void) const;
int decimalPlaces(void) const;
/// Sets and sends new value to vehicle even if value is the same
void forceSetValue(const QVariant& value);
......
......@@ -32,30 +32,32 @@
#include <limits>
FactMetaData::FactMetaData(QObject* parent) :
QObject(parent),
_group("*Default Group"),
_type(valueTypeInt32),
_defaultValue(0),
_defaultValueAvailable(false),
_min(_minForType()),
_max(_maxForType()),
_minIsDefaultForType(true),
_maxIsDefaultForType(true)
FactMetaData::FactMetaData(QObject* parent)
: QObject(parent)
, _group("*Default Group")
, _type(valueTypeInt32)
, _defaultValue(0)
, _defaultValueAvailable(false)
, _min(_minForType())
, _max(_maxForType())
, _minIsDefaultForType(true)
, _maxIsDefaultForType(true)
, _decimalPlaces(defaultDecimalPlaces)
{
}
FactMetaData::FactMetaData(ValueType_t type, QObject* parent) :
QObject(parent),
_group("*Default Group"),
_type(type),
_defaultValue(0),
_defaultValueAvailable(false),
_min(_minForType()),
_max(_maxForType()),
_minIsDefaultForType(true),
_maxIsDefaultForType(true)
FactMetaData::FactMetaData(ValueType_t type, QObject* parent)
: QObject(parent)
, _group("*Default Group")
, _type(type)
, _defaultValue(0)
, _defaultValueAvailable(false)
, _min(_minForType())
, _max(_maxForType())
, _minIsDefaultForType(true)
, _maxIsDefaultForType(true)
, _decimalPlaces(defaultDecimalPlaces)
{
}
......@@ -76,6 +78,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other)
_max = other._max;
_minIsDefaultForType = other._minIsDefaultForType;
_maxIsDefaultForType = other._maxIsDefaultForType;
_decimalPlaces = other._decimalPlaces;
return *this;
}
......
......@@ -59,18 +59,19 @@ public:
const FactMetaData& operator=(const FactMetaData& other);
// Property accessors
QString name(void) const { return _name; }
QString group(void) const { return _group; }
ValueType_t type(void) const { return _type; }
QString name(void) const { return _name; }
QString group(void) const { return _group; }
ValueType_t type(void) const { return _type; }
QVariant defaultValue(void) const;
bool defaultValueAvailable(void) const { return _defaultValueAvailable; }
QString shortDescription(void) const { return _shortDescription; }
QString longDescription(void) const { return _longDescription;}
QString units(void) const { return _units; }
QVariant min(void) const { return _min; }
QVariant max(void) const { return _max; }
bool minIsDefaultForType(void) const { return _minIsDefaultForType; }
bool maxIsDefaultForType(void) const { return _maxIsDefaultForType; }
bool defaultValueAvailable(void) const { return _defaultValueAvailable; }
QString shortDescription(void) const { return _shortDescription; }
QString longDescription(void) const { return _longDescription;}
QString units(void) const { return _units; }
QVariant min(void) const { return _min; }
QVariant max(void) const { return _max; }
bool minIsDefaultForType(void) const { return _minIsDefaultForType; }
bool maxIsDefaultForType(void) const { return _maxIsDefaultForType; }
int decimalPlaces(void) const { return _decimalPlaces; }
// Property setters
void setName(const QString& name) { _name = name; }
......@@ -81,6 +82,7 @@ public:
void setUnits(const QString& units) { _units = units; }
void setMin(const QVariant& max);
void setMax(const QVariant& max);
void setDecimalPlaces(int decimalPlaces) { _decimalPlaces = decimalPlaces; }
/// Converts the specified value, validating against meta data
/// @param value Value to convert, can be string
......@@ -90,6 +92,8 @@ public:
/// @returns false: Convert failed, errorString set
bool convertAndValidate(const QVariant& value, bool convertOnly, QVariant& typedValue, QString& errorString);
static const int defaultDecimalPlaces = 3;
private:
QVariant _minForType(void) const;
QVariant _maxForType(void) const;
......@@ -106,6 +110,7 @@ private:
QVariant _max;
bool _minIsDefaultForType;
bool _maxIsDefaultForType;
int _decimalPlaces;
};
#endif
......@@ -299,6 +299,19 @@ void PX4ParameterLoader::loadParameterFactMetaData(void)
qCDebug(PX4ParameterLoaderLog) << "Unit:" << text;
metaData->setUnits(text);
} else if (elementName == "decimal") {
Q_ASSERT(metaData);
QString text = xml.readElementText();
qCDebug(PX4ParameterLoaderLog) << "Decimal:" << text;
bool convertOk;
QVariant varDecimals = QVariant(text).toUInt(&convertOk);
if (convertOk) {
metaData->setDecimalPlaces(varDecimals.toInt());
} else {
qCWarning(PX4ParameterLoaderLog) << "Invalid decimals value, name:" << metaData->name() << " type:" << metaData->type() << " decimals:" << text << " error: invalid number";
}
} else {
qDebug() << "Unknown element in XML: " << elementName;
}
......
......@@ -322,8 +322,6 @@ QGCView {
// Move to the new position
editorMap.latitude = object.coordinate.latitude
editorMap.longitude = object.coordinate.longitude
} else {
itemDragger.clearItem()
}
}
}
......
......@@ -20,15 +20,6 @@ This file is part of the QGROUNDCONTROL project
======================================================================*/
/**
* @file
* @brief MissionItem class
*
* @author Benjamin Knecht <mavteam@student.ethz.ch>
* @author Petri Tanskanen <mavteam@student.ethz.ch>
*
*/
#include <QStringList>
#include <QDebug>
......@@ -115,10 +106,12 @@ MissionItem::MissionItem(QObject* parent,
FactMetaData* latitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _latitudeFact);
latitudeMetaData->setUnits("deg");
latitudeMetaData->setDecimalPlaces(7);
FactMetaData* longitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _longitudeFact);
longitudeMetaData->setUnits("deg");
longitudeMetaData->setDecimalPlaces(7);
FactMetaData* altitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _altitudeFact);
altitudeMetaData->setUnits("meters");
......
......@@ -66,21 +66,23 @@ void MissionController::start(bool editMode)
connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionController::_activeVehicleChanged);
_setupMissionItems(true /* fromVehicle */, true /* force */);
_setupMissionItems(true /* loadFromVehicle */, true /* forceLoad */);
_setupActiveVehicle(multiVehicleMgr->activeVehicle(), true /* forceLoadFromVehicle */);
}
void MissionController::_newMissionItemsAvailableFromVehicle(void)
{
qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";
_setupMissionItems(true /* fromVehicle */, false /* force */);
_setupMissionItems(true /* loadFromVehicle */, false /* forceLoad */);
}
/// @param fromVehicle true: load items from vehicle
/// @param force true: disregard any flags which may prevent load
void MissionController::_setupMissionItems(bool fromVehicle, bool force)
/// @param loadFromVehicle true: load items from vehicle
/// @param forceLoad true: disregard any flags which may prevent load
void MissionController::_setupMissionItems(bool loadFromVehicle, bool forceLoad)
{
qCDebug(MissionControllerLog) << "_setupMissionItems fromVehicle:force:_editMode:_firstItemsFromVehicle" << fromVehicle << force << _editMode << _firstItemsFromVehicle;
qCDebug(MissionControllerLog) << "_setupMissionItems loadFromVehicle:forceLoad:_editMode:_firstItemsFromVehicle"
<< loadFromVehicle << forceLoad << _editMode << _firstItemsFromVehicle;
MissionManager* missionManager = NULL;
if (_activeVehicle) {
......@@ -89,8 +91,8 @@ void MissionController::_setupMissionItems(bool fromVehicle, bool force)
qCDebug(MissionControllerLog) << "running offline";
}
if (!force) {
if (_editMode && fromVehicle) {
if (!forceLoad) {
if (_editMode && loadFromVehicle) {
if (_firstItemsFromVehicle) {
if (missionManager) {
if (missionManager->inProgress()) {
......@@ -126,7 +128,7 @@ void MissionController::_setupMissionItems(bool fromVehicle, bool force)
_missionItems->deleteLater();
}
if (!missionManager || !fromVehicle || missionManager->inProgress()) {
if (!missionManager || !loadFromVehicle || missionManager->inProgress()) {
_canEdit = true;
_missionItems = new QmlObjectListModel(this);
qCDebug(MissionControllerLog) << "creating empty set";
......@@ -440,10 +442,22 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
_activeVehicle = NULL;
// When the active vehicle goes away we toss the editor items
_setupMissionItems(false /* fromVehicle */, true /* force */);
_setupMissionItems(false /* loadFromVehicle */, true /* forceLoad */);
_activeVehicleHomePositionAvailableChanged(false);
}
_setupActiveVehicle(activeVehicle, false /* forceLoadFromVehicle */);
}
void MissionController::_setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle)
{
qCDebug(MissionControllerLog) << "_setupActiveVehicle activeVehicle:forceLoadFromVehicle"
<< activeVehicle << forceLoadFromVehicle;
if (_activeVehicle) {
qCWarning(MissionControllerLog) << "_activeVehicle != NULL";
}
_activeVehicle = activeVehicle;
if (_activeVehicle) {
......@@ -455,7 +469,7 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged);
_firstItemsFromVehicle = true;
_setupMissionItems(true /* fromVehicle */, false /* force */);
_setupMissionItems(true /* fromVehicle */, forceLoadFromVehicle);
_activeVehicleHomePositionChanged(_activeVehicle->homePosition());
_activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
......@@ -464,20 +478,15 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
MissionItem* homeItem = qobject_cast<MissionItem*>(_missionItems->get(0));
if (homePositionAvailable) {
homeItem->setCoordinate(_liveHomePosition);
}
homeItem->setHomePositionValid(homePositionAvailable);
_liveHomePositionAvailable = homePositionAvailable;
qobject_cast<MissionItem*>(_missionItems->get(0))->setHomePositionValid(homePositionAvailable);
emit liveHomePositionAvailableChanged(_liveHomePositionAvailable);
}
void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
_liveHomePosition = homePosition;
qobject_cast<MissionItem*>(_missionItems->get(0))->setCoordinate(_liveHomePosition);
emit liveHomePositionChanged(_liveHomePosition);
}
......
......@@ -94,7 +94,8 @@ private:
void _initMissionItem(MissionItem* item);
void _deinitMissionItem(MissionItem* item);
void _autoSyncSend(void);
void _setupMissionItems(bool fromVehicle, bool force);
void _setupMissionItems(bool loadFromVehicle, bool forceLoad);
void _setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle);
private:
bool _editMode;
......
......@@ -202,17 +202,32 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
void Vehicle::_handleHomePosition(mavlink_message_t& message)
{
bool emitHomePositionChanged = false;
bool emitHomePositionAvailableChanged = false;
mavlink_home_position_t homePos;
mavlink_msg_home_position_decode(&message, &homePos);
_homePosition.setLatitude(homePos.latitude / 10000000.0);
_homePosition.setLongitude(homePos.longitude / 10000000.0);
_homePosition.setAltitude(homePos.altitude / 1000.0);
QGeoCoordinate newHomePosition (homePos.latitude / 10000000.0,
homePos.longitude / 10000000.0,
homePos.altitude / 1000.0);
if (newHomePosition != _homePosition) {
emitHomePositionChanged = true;
_homePosition = newHomePosition;
}
if (!_homePositionAvailable) {
emitHomePositionAvailableChanged = true;
}
_homePositionAvailable = true;
emit homePositionChanged(_homePosition);
emit homePositionAvailableChanged(true);
if (emitHomePositionChanged) {
emit homePositionChanged(_homePosition);
}
if (emitHomePositionAvailableChanged) {
emit homePositionAvailableChanged(true);
}
}
void Vehicle::_handleHeartbeat(mavlink_message_t& message)
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment