Commit 073ab854 authored by DonLakeFlyer's avatar DonLakeFlyer

New CameraCalc reusable code for complex items

Converted Structure Scan to use CameraCalc such that it now works with
camera specs.
parent 97891f2d
......@@ -505,7 +505,9 @@ HEADERS += \
src/JsonHelper.h \
src/LogCompressor.h \
src/MG.h \
src/MissionManager/CameraCalc.h \
src/MissionManager/CameraSection.h \
src/MissionManager/CameraSpec.h \
src/MissionManager/ComplexMissionItem.h \
src/MissionManager/FixedWingLandingComplexItem.h \
src/MissionManager/GeoFenceController.h \
......@@ -693,7 +695,9 @@ SOURCES += \
src/Joystick/JoystickManager.cc \
src/JsonHelper.cc \
src/LogCompressor.cc \
src/MissionManager/CameraCalc.cc \
src/MissionManager/CameraSection.cc \
src/MissionManager/CameraSpec.cc \
src/MissionManager/ComplexMissionItem.cc \
src/MissionManager/FixedWingLandingComplexItem.cc \
src/MissionManager/GeoFenceController.cc \
......
......@@ -44,6 +44,7 @@
<file alias="PX4FlowSensor.qml">src/VehicleSetup/PX4FlowSensor.qml</file>
<file alias="QGroundControl/Controls/AnalyzePage.qml">src/AnalyzeView/AnalyzePage.qml</file>
<file alias="QGroundControl/Controls/AppMessages.qml">src/QmlControls/AppMessages.qml</file>
<file alias="QGroundControl/Controls/CameraCalc.qml">src/PlanView/CameraCalc.qml</file>
<file alias="QGroundControl/Controls/CameraSection.qml">src/PlanView/CameraSection.qml</file>
<file alias="QGroundControl/Controls/ClickableColor.qml">src/QmlControls/ClickableColor.qml</file>
<file alias="QGroundControl/Controls/DropButton.qml">src/QmlControls/DropButton.qml</file>
......@@ -203,6 +204,8 @@
<file alias="FWLandingPattern.FactMetaData.json">src/MissionManager/FWLandingPattern.FactMetaData.json</file>
<file alias="USBBoardInfo.json">src/comm/USBBoardInfo.json</file>
<file alias="CameraSection.FactMetaData.json">src/MissionManager/CameraSection.FactMetaData.json</file>
<file alias="CameraCalc.FactMetaData.json">src/MissionManager/CameraCalc.FactMetaData.json</file>
<file alias="CameraSpec.FactMetaData.json">src/MissionManager/CameraSpec.FactMetaData.json</file>
<file alias="SpeedSection.FactMetaData.json">src/MissionManager/SpeedSection.FactMetaData.json</file>
<file alias="MissionSettings.FactMetaData.json">src/MissionManager/MissionSettings.FactMetaData.json</file>
<file alias="Vehicle/VehicleFact.json">src/Vehicle/VehicleFact.json</file>
......
......@@ -89,7 +89,7 @@ void Fact::forceSetRawValue(const QVariant& value)
emit rawValueChanged(_rawValue);
}
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
}
}
......@@ -109,7 +109,7 @@ void Fact::setRawValue(const QVariant& value)
}
}
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
}
}
......@@ -118,7 +118,7 @@ void Fact::setCookedValue(const QVariant& value)
if (_metaData) {
setRawValue(_metaData->cookedTranslator()(value));
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
}
}
......@@ -130,7 +130,7 @@ void Fact::setEnumStringValue(const QString& value)
setCookedValue(_metaData->enumValues()[index]);
}
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
}
}
......@@ -139,7 +139,7 @@ void Fact::setEnumIndex(int index)
if (_metaData) {
setCookedValue(_metaData->enumValues()[index]);
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
}
}
......@@ -168,7 +168,7 @@ QVariant Fact::cookedValue(void) const
if (_metaData) {
return _metaData->rawTranslator()(_rawValue);
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return _rawValue;
}
}
......@@ -181,7 +181,7 @@ QString Fact::enumStringValue(void)
return _metaData->enumStrings()[enumIndex];
}
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
}
return QString();
......@@ -213,7 +213,7 @@ int Fact::enumIndex(void)
return index;
}
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
}
return -1;
}
......@@ -223,7 +223,7 @@ QStringList Fact::enumStrings(void) const
if (_metaData) {
return _metaData->enumStrings();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QStringList();
}
}
......@@ -233,7 +233,7 @@ QVariantList Fact::enumValues(void) const
if (_metaData) {
return _metaData->enumValues();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QVariantList();
}
}
......@@ -243,7 +243,7 @@ void Fact::setEnumInfo(const QStringList& strings, const QVariantList& values)
if (_metaData) {
_metaData->setEnumInfo(strings, values);
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
}
}
......@@ -252,7 +252,7 @@ QStringList Fact::bitmaskStrings(void) const
if (_metaData) {
return _metaData->bitmaskStrings();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QStringList();
}
}
......@@ -262,7 +262,7 @@ QVariantList Fact::bitmaskValues(void) const
if (_metaData) {
return _metaData->bitmaskValues();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QVariantList();
}
}
......@@ -336,7 +336,7 @@ QVariant Fact::rawDefaultValue(void) const
}
return _metaData->rawDefaultValue();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QVariant(0);
}
}
......@@ -349,7 +349,7 @@ QVariant Fact::cookedDefaultValue(void) const
}
return _metaData->cookedDefaultValue();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QVariant(0);
}
}
......@@ -369,7 +369,7 @@ QString Fact::shortDescription(void) const
if (_metaData) {
return _metaData->shortDescription();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QString();
}
}
......@@ -379,7 +379,7 @@ QString Fact::longDescription(void) const
if (_metaData) {
return _metaData->longDescription();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QString();
}
}
......@@ -389,7 +389,7 @@ QString Fact::rawUnits(void) const
if (_metaData) {
return _metaData->rawUnits();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QString();
}
}
......@@ -399,7 +399,7 @@ QString Fact::cookedUnits(void) const
if (_metaData) {
return _metaData->cookedUnits();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QString();
}
}
......@@ -409,7 +409,7 @@ QVariant Fact::rawMin(void) const
if (_metaData) {
return _metaData->rawMin();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QVariant(0);
}
}
......@@ -419,7 +419,7 @@ QVariant Fact::cookedMin(void) const
if (_metaData) {
return _metaData->cookedMin();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QVariant(0);
}
}
......@@ -434,7 +434,7 @@ QVariant Fact::rawMax(void) const
if (_metaData) {
return _metaData->rawMax();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QVariant(0);
}
}
......@@ -444,7 +444,7 @@ QVariant Fact::cookedMax(void) const
if (_metaData) {
return _metaData->cookedMax();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QVariant(0);
}
}
......@@ -459,7 +459,7 @@ bool Fact::minIsDefaultForType(void) const
if (_metaData) {
return _metaData->minIsDefaultForType();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return false;
}
}
......@@ -469,7 +469,7 @@ bool Fact::maxIsDefaultForType(void) const
if (_metaData) {
return _metaData->maxIsDefaultForType();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return false;
}
}
......@@ -479,7 +479,7 @@ int Fact::decimalPlaces(void) const
if (_metaData) {
return _metaData->decimalPlaces();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return FactMetaData::defaultDecimalPlaces;
}
}
......@@ -489,14 +489,17 @@ QString Fact::group(void) const
if (_metaData) {
return _metaData->group();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QString();
}
}
void Fact::setMetaData(FactMetaData* metaData)
void Fact::setMetaData(FactMetaData* metaData, bool setDefaultFromMetaData)
{
_metaData = metaData;
if (setDefaultFromMetaData) {
setRawValue(rawDefaultValue());
}
emit valueChanged(cookedValue());
}
......@@ -509,7 +512,7 @@ bool Fact::valueEqualsDefault(void) const
return false;
}
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return false;
}
}
......@@ -519,7 +522,7 @@ bool Fact::defaultValueAvailable(void) const
if (_metaData) {
return _metaData->defaultValueAvailable();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return false;
}
}
......@@ -534,7 +537,7 @@ QString Fact::validate(const QString& cookedValue, bool convertOnly)
return errorString;
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return QString("Internal error: Meta data pointer missing");
}
}
......@@ -550,7 +553,7 @@ QVariant Fact::clamp(const QString& cookedValue)
return rawValue();
}
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
}
return QVariant();
}
......@@ -560,7 +563,7 @@ bool Fact::rebootRequired(void) const
if (_metaData) {
return _metaData->rebootRequired();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return false;
}
}
......@@ -600,7 +603,7 @@ QString Fact::enumOrValueString(void)
return cookedValueString();
}
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
}
return QString();
}
......@@ -610,7 +613,7 @@ double Fact::increment(void) const
if (_metaData) {
return _metaData->increment();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
}
return std::numeric_limits<double>::quiet_NaN();
}
......@@ -620,7 +623,7 @@ bool Fact::hasControl(void) const
if (_metaData) {
return _metaData->hasControl();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return false;
}
}
......@@ -630,7 +633,7 @@ bool Fact::readOnly(void) const
if (_metaData) {
return _metaData->readOnly();
} else {
qWarning() << kMissingMetadata;
qWarning() << kMissingMetadata << name();
return false;
}
}
......@@ -136,7 +136,9 @@ public:
void forceSetRawValue(const QVariant& value);
/// Sets the meta data associated with the Fact.
void setMetaData(FactMetaData* metaData);
/// @param metaData FactMetaData for Fact
/// @param setDefaultFromMetaData true: set the fact value to the default specified in the meta data
void setMetaData(FactMetaData* metaData, bool setDefaultFromMetaData = false);
FactMetaData* metaData() { return _metaData; }
......
......@@ -7,8 +7,7 @@
*
****************************************************************************/
#ifndef CameraMetaData_H
#define CameraMetaData_H
#pragma once
#include <QObject>
......@@ -29,15 +28,25 @@ public:
double minTriggerInterval,
QObject* parent = NULL);
Q_PROPERTY(QString name MEMBER _name CONSTANT) ///< Camera name
Q_PROPERTY(double sensorWidth MEMBER _sensorWidth CONSTANT) ///< Sensor size in millimeters
Q_PROPERTY(double sensorHeight MEMBER _sensorHeight CONSTANT) ///< Sensor size in millimeters
Q_PROPERTY(double imageWidth MEMBER _imageWidth CONSTANT) ///< Image size in pixels
Q_PROPERTY(double imageHeight MEMBER _imageHeight CONSTANT) ///< Image size in pixels
Q_PROPERTY(double focalLength MEMBER _focalLength CONSTANT) ///< Focal length in millimeters
Q_PROPERTY(bool landscape MEMBER _landscape CONSTANT) ///< true: camera is in landscape orientation
Q_PROPERTY(bool fixedOrientation MEMBER _fixedOrientation CONSTANT) ///< true: camera is in fixed orientation
Q_PROPERTY(double minTriggerInterval MEMBER _minTriggerInterval CONSTANT) ///< Minimum time in seconds between each photo taken, 0 for not specified
Q_PROPERTY(QString name READ name CONSTANT) ///< Camera name
Q_PROPERTY(double sensorWidth READ sensorWidth CONSTANT) ///< Sensor size in millimeters
Q_PROPERTY(double sensorHeight READ sensorHeight CONSTANT) ///< Sensor size in millimeters
Q_PROPERTY(double imageWidth READ imageWidth CONSTANT) ///< Image size in pixels
Q_PROPERTY(double imageHeight READ imageHeight CONSTANT) ///< Image size in pixels
Q_PROPERTY(double focalLength READ focalLength CONSTANT) ///< Focal length in millimeters
Q_PROPERTY(bool landscape READ landscape CONSTANT) ///< true: camera is in landscape orientation
Q_PROPERTY(bool fixedOrientation READ fixedOrientation CONSTANT) ///< true: camera is in fixed orientation
Q_PROPERTY(double minTriggerInterval READ minTriggerInterval CONSTANT) ///< Minimum time in seconds between each photo taken, 0 for not specified
QString name (void) const { return _name; }
double sensorWidth (void) const { return _sensorWidth; }
double sensorHeight (void) const { return _sensorHeight; }
double imageWidth (void) const { return _imageWidth; }
double imageHeight (void) const { return _imageHeight; }
double focalLength (void) const { return _focalLength; }
bool landscape (void) const { return _landscape; }
bool fixedOrientation (void) const { return _fixedOrientation; }
double minTriggerInterval (void) const { return _minTriggerInterval; }
private:
QString _name;
......@@ -50,5 +59,3 @@ private:
bool _fixedOrientation;
double _minTriggerInterval;
};
#endif
[
{
"name": "ValueSetIsDistance",
"shortDescription": "Value specified is distance to surface.",
"type": "bool",
"defaultValue": 1
},
{
"name": "DistanceToSurface",
"shortDescription": "Distance vehicle is away from surface.",
"type": "double",
"min": 0.1,
"units": "m",
"decimalPlaces": 2,
"defaultValue": 100.0
},
{
"name": "ImageDensity",
"shortDescription": "Image desity at surface.",
"type": "double",
"min": 0,
"units": "cm/px",
"decimalPlaces": 1,
"defaultValue": 25
},
{
"name": "FrontalOverlap",
"shortDescription": "Amount of overlap between images in the forward facing direction.",
"type": "double",
"decimalPlaces": 0,
"min": 0,
"max": 85,
"units": "%",
"defaultValue": 70
},
{
"name": "SideOverlap",
"shortDescription": "Amount of overlap between images in the side facing direction.",
"type": "double",
"decimalPlaces": 0,
"min": 0,
"max": 85,
"units": "%",
"defaultValue": 70
},
{
"name": "AdjustedFootprintFrontal",
"type": "double",
"decimalPlaces": 2,
"min": 0,
"units": "m",
"defaultValue": 25
},
{
"name": "AdjustedFootprintSide",
"type": "double",
"decimalPlaces": 2,
"min": 0,
"units": "m",
"defaultValue": 25
}
]
This diff is collapsed.
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "CameraSpec.h"
class Vehicle;
class CameraCalc : public CameraSpec
{
Q_OBJECT
public:
CameraCalc(Vehicle* vehicle, QObject* parent = NULL);
Q_ENUMS(CameraSpecType)
Q_PROPERTY(CameraSpecType cameraSpecType MEMBER _cameraSpecType NOTIFY cameraSpecTypeChanged)
Q_PROPERTY(QString knownCameraName MEMBER _knownCameraName NOTIFY knownCameraNameChanged)
Q_PROPERTY(Fact* valueSetIsDistance READ valueSetIsDistance CONSTANT) ///< true: distance specified, resolution calculated
Q_PROPERTY(Fact* distanceToSurface READ distanceToSurface CONSTANT) ///< Distance to surface for image foot print calculation
Q_PROPERTY(Fact* imageDensity READ imageDensity CONSTANT) ///< Image density on surface (cm/px)
Q_PROPERTY(Fact* frontalOverlap READ frontalOverlap CONSTANT)
Q_PROPERTY(Fact* sideOverlap READ sideOverlap CONSTANT)
Q_PROPERTY(Fact* adjustedFootprintSide READ adjustedFootprintSide CONSTANT) ///< Side footprint adjusted down for overlap
Q_PROPERTY(Fact* adjustedFootprintFrontal READ adjustedFootprintFrontal CONSTANT) ///< Frontal footprint adjusted down for overlap
// The following values are calculated from the camera properties
Q_PROPERTY(double imageFootprintSide READ imageFootprintSide NOTIFY imageFootprintSideChanged) ///< Size of image size side in meters
Q_PROPERTY(double imageFootprintFrontal READ imageFootprintFrontal NOTIFY imageFootprintFrontalChanged) ///< Size of image size frontal in meters
enum CameraSpecType {
CameraSpecNone,
CameraSpecCustom,
CameraSpecKnown
};
Fact* valueSetIsDistance (void) { return &_valueSetIsDistanceFact; }
Fact* distanceToSurface (void) { return &_distanceToSurfaceFact; }
Fact* imageDensity (void) { return &_imageDensityFact; }
Fact* frontalOverlap (void) { return &_frontalOverlapFact; }
Fact* sideOverlap (void) { return &_sideOverlapFact; }
Fact* adjustedFootprintSide (void) { return &_adjustedFootprintSideFact; }
Fact* adjustedFootprintFrontal (void) { return &_adjustedFootprintFrontalFact; }
double imageFootprintSide (void) const { return _imageFootprintSide; }
double imageFootprintFrontal (void) const { return _imageFootprintFrontal; }
bool dirty (void) const { return _dirty; }
void setDirty (bool dirty);
void save(QJsonObject& json) const;
bool load(const QJsonObject& json, QString& errorString);
signals:
void cameraSpecTypeChanged (CameraSpecType cameraSpecType);
void knownCameraNameChanged (QString knownCameraName);
void dirtyChanged (bool dirty);
void imageFootprintSideChanged (double imageFootprintSide);
void imageFootprintFrontalChanged (double imageFootprintFrontal);
private slots:
void _knownCameraNameChanged(QString knownCameraName);
void _recalcTriggerDistance(void);
private:
Vehicle* _vehicle;
bool _dirty;
CameraSpecType _cameraSpecType;
QString _knownCameraName;
bool _disableRecalc;
QMap<QString, FactMetaData*> _metaDataMap;
Fact _valueSetIsDistanceFact;
Fact _distanceToSurfaceFact;
Fact _imageDensityFact;
Fact _frontalOverlapFact;
Fact _sideOverlapFact;
Fact _adjustedFootprintSideFact;
Fact _adjustedFootprintFrontalFact;
double _imageFootprintSide;
double _imageFootprintFrontal;
QVariantList _knownCameraList;
static const char* _valueSetIsDistanceName;
static const char* _distanceToSurfaceName;
static const char* _imageDensityName;
static const char* _frontalOverlapName;
static const char* _sideOverlapName;
static const char* _adjustedFootprintSideName;
static const char* _adjustedFootprintFrontalName;
};
[
{
"name": "Name",
"shortDescription": "Camera name.",
"type": "string",
"defaultValue": ""
},
{
"name": "SensorWidth",
"shortDescription": "Width of camera image sensor.",
"type": "double",
"decimalPlaces": 2,
"min": 1,
"units": "mm",
"defaultValue": 6.17
},
{
"name": "SensorHeight",
"shortDescription": "Height of camera image sensor.",
"type": "double",
"decimalPlaces": 2,
"min": 1,
"units": "mm",
"defaultValue": 4.55
},
{
"name": "ImageWidth",
"shortDescription": "Camera image resolution width.",
"type": "uint32",
"min": 1,
"units": "px",
"defaultValue": 4000
},
{
"name": "ImageHeight",
"shortDescription": "Camera image resolution height.",
"type": "uint32",
"min": 1,
"units": "px",
"defaultValue": 3000
},
{
"name": "FocalLength",
"shortDescription": "Focal length of camera lens.",
"type": "double",
"decimalPlaces": 1,
"min": 1,
"units": "mm",
"defaultValue": 4.5
},
{
"name": "Landscape",
"shortDescription": "Camera on vehicle is in landscape orientation.",
"type": "bool",
"defaultValue": 1
},
{
"name": "FixedOrientation",
"shortDescription": "Camera orientation ix fixed and cannot be changed.",
"type": "bool",
"defaultValue": 0
},
{
"name": "MinTriggerInterval",
"shortDescription": "Minimum amount of time between each camera trigger.",
"type": "double",
"min": 0.1,
"units": "secs",
"defaultValue": 1.0
}
]
This diff is collapsed.
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "Fact.h"
class CameraSpec : public QObject
{
Q_OBJECT
public:
CameraSpec(QObject* parent = NULL);
CameraSpec(const QString& name,
double sensorWidth,
double sensorHeight,
double imageWidth,
double imageHeight,
double focalLength,
bool landscape,
bool fixedOrientation,
double minTriggerInterval,
QObject* parent = NULL);
CameraSpec(const CameraSpec& other, QObject* parent);
const CameraSpec& operator=(const CameraSpec& other);
// These properties are persisted to Json
Q_PROPERTY(Fact* name READ name CONSTANT) ///< Camera name
Q_PROPERTY(Fact* sensorWidth READ sensorWidth CONSTANT) ///< Sensor size in millimeters
Q_PROPERTY(Fact* sensorHeight READ sensorHeight CONSTANT) ///< Sensor size in millimeters
Q_PROPERTY(Fact* imageWidth READ imageWidth CONSTANT) ///< Image size in pixels
Q_PROPERTY(Fact* imageHeight READ imageHeight CONSTANT) ///< Image size in pixels
Q_PROPERTY(Fact* focalLength READ focalLength CONSTANT) ///< Focal length in millimeters
Q_PROPERTY(Fact* landscape READ landscape CONSTANT) ///< true: camera is in landscape orientation
Q_PROPERTY(Fact* fixedOrientation READ fixedOrientation CONSTANT) ///< true: camera is in fixed orientation
Q_PROPERTY(Fact* minTriggerInterval READ minTriggerInterval CONSTANT) ///< Minimum time in seconds between each photo taken, 0 for not specified
Fact* name (void) { return &_nameFact; }
Fact* sensorWidth (void) { return &_sensorWidthFact; }
Fact* sensorHeight (void) { return &_sensorHeightFact; }
Fact* imageWidth (void) { return &_imageWidthFact; }
Fact* imageHeight (void) { return &_imageHeightFact; }
Fact* focalLength (void) { return &_focalLengthFact; }
Fact* landscape (void) { return &_landscapeFact; }
Fact* fixedOrientation (void) { return &_fixedOrientationFact; }
Fact* minTriggerInterval(void) { return &_minTriggerIntervalFact; }
bool dirty (void) const { return _dirty; }
void setDirty (bool dirty);
void save(QJsonObject& json) const;
bool load(const QJsonObject& json, QString& errorString);
signals:
void dirtyChanged(bool dirty);
private:
void _init(bool setDefaults);
bool _dirty;
QMap<QString, FactMetaData*> _metaDataMap;
Fact _nameFact;
Fact _sensorWidthFact;
Fact _sensorHeightFact;
Fact _imageWidthFact;
Fact _imageHeightFact;
Fact _focalLengthFact;
Fact _landscapeFact;
Fact _fixedOrientationFact;
Fact _minTriggerIntervalFact;
static const char* _nameName;
static const char* _sensorWidthName;
static const char* _sensorHeightName;
static const char* _imageWidthName;
static const char* _imageHeightName;
static const char* _focalLengthName;
static const char* _landscapeName;
static const char* _fixedOrientationName;
static const char* _minTriggerIntervalName;
static const char* _jsonNameKey;
static const char* _jsonSensorWidthKey;
static const char* _jsonSensorHeightKey;
static const char* _jsonImageWidthKey;
static const char* _jsonImageHeightKey;
static const char* _jsonFocalLengthKey;
static const char* _jsonLandscapeKey;
static const char* _jsonFixedOrientationKey;
static const char* _jsonMinTriggerIntervalKey;
};
......@@ -25,9 +25,6 @@ const char* StructureScanComplexItem::jsonComplexItemTypeValue = "Stru
const char* StructureScanComplexItem::_altitudeFactName = "Altitude";
const char* StructureScanComplexItem::_layersFactName = "Layers";
const char* StructureScanComplexItem::_layerDistanceFactName = "Layer distance";
const char* StructureScanComplexItem::_cameraTriggerDistanceFactName = "Trigger distance";
const char* StructureScanComplexItem::_scanDistanceFactName = "Scan distance";
QMap<QString, FactMetaData*> StructureScanComplexItem::_metaDataMap;
......@@ -41,11 +38,9 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
, _scanDistance (0.0)
, _cameraShots (0)
, _cameraMinTriggerInterval (0)
, _cameraCalc (vehicle)
, _altitudeFact (0, _altitudeFactName, FactMetaData::valueTypeDouble)
, _layersFact (0, _layersFactName, FactMetaData::valueTypeUint32)
, _layerDistanceFact (0, _layerDistanceFactName, FactMetaData::valueTypeDouble)
, _cameraTriggerDistanceFact(0, _cameraTriggerDistanceFactName, FactMetaData::valueTypeDouble)
, _scanDistanceFact (0, _scanDistanceFactName, FactMetaData::valueTypeDouble)
{
_editorQml = "qrc:/qml/StructureScanEditor.qml";
......@@ -53,26 +48,16 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/StructureScan.SettingsGroup.json"), NULL /* QObject parent */);
}
qDebug() << _metaDataMap[_altitudeFactName];
_altitudeFact.setMetaData (_metaDataMap[_altitudeFactName]);
_layersFact.setMetaData (_metaDataMap[_layersFactName]);
_layerDistanceFact.setMetaData (_metaDataMap[_layerDistanceFactName]);
_cameraTriggerDistanceFact.setMetaData (_metaDataMap[_cameraTriggerDistanceFactName]);
_scanDistanceFact.setMetaData (_metaDataMap[_scanDistanceFactName]);
_altitudeFact.setMetaData (_metaDataMap[_altitudeFactName]);
_layersFact.setMetaData (_metaDataMap[_layersFactName]);
_altitudeFact.setRawValue (_altitudeFact.rawDefaultValue());
_layersFact.setRawValue (_layersFact.rawDefaultValue());
_layerDistanceFact.setRawValue (_layerDistanceFact.rawDefaultValue());
_cameraTriggerDistanceFact.setRawValue (_cameraTriggerDistanceFact.rawDefaultValue());
_scanDistanceFact.setRawValue (_scanDistanceFact.rawDefaultValue());
_altitudeFact.setRawValue (_altitudeFact.rawDefaultValue());
_layersFact.setRawValue (_layersFact.rawDefaultValue());
_altitudeFact.setRawValue(qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue());
connect(&_altitudeFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
connect(&_layerDistanceFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
connect(&_scanDistanceFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
connect(&_altitudeFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
connect(this, &StructureScanComplexItem::altitudeRelativeChanged, this, &StructureScanComplexItem::_setDirty);
connect(this, &StructureScanComplexItem::altitudeRelativeChanged, this, &StructureScanComplexItem::coordinateHasRelativeAltitudeChanged);
......@@ -86,7 +71,7 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
connect(&_flightPolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_flightPathChanged);
connect(&_scanDistanceFact, &Fact::valueChanged, this, &StructureScanComplexItem::_rebuildFlightPolygon);
connect(_cameraCalc.distanceToSurface(), &Fact::valueChanged, this, &StructureScanComplexItem::_rebuildFlightPolygon);
}
void StructureScanComplexItem::_setScanDistance(double scanDistance)
......@@ -395,7 +380,7 @@ void StructureScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QO
items.append(item);
for (int layer=0; layer<_layersFact.rawValue().toInt(); layer++) {
double layerAltitude = baseAltitude + (layer * _layerDistanceFact.rawValue().toDouble());
double layerAltitude = baseAltitude + (layer * _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble());
for (int i=0; i<_flightPolygon.count(); i++) {
QGeoCoordinate vertexCoord = _flightPolygon.vertexCoordinate(i);
......@@ -466,9 +451,9 @@ void StructureScanComplexItem::_polygonDirtyChanged(bool dirty)
}
}
double StructureScanComplexItem::timeBetweenShots(void) const
double StructureScanComplexItem::timeBetweenShots(void)
{
return _cruiseSpeed == 0 ? 0 :_cameraTriggerDistanceFact.rawValue().toDouble() / _cruiseSpeed;
return _cruiseSpeed == 0 ? 0 : _cameraCalc.adjustedFootprintSide()->rawValue().toDouble() / _cruiseSpeed;
}
QGeoCoordinate StructureScanComplexItem::coordinate(void) const
......@@ -505,5 +490,5 @@ void StructureScanComplexItem::rotateEntryPoint(void)
void StructureScanComplexItem::_rebuildFlightPolygon(void)
{
_flightPolygon = _structurePolygon;
_flightPolygon.offset(_scanDistanceFact.rawValue().toDouble());
_flightPolygon.offset(_cameraCalc.distanceToSurface()->rawValue().toDouble());
}
......@@ -16,6 +16,7 @@
#include "SettingsFact.h"
#include "QGCLoggingCategory.h"
#include "QGCMapPolygon.h"
#include "CameraCalc.h"
Q_DECLARE_LOGGING_CATEGORY(StructureScanComplexItemLog)
......@@ -26,11 +27,9 @@ class StructureScanComplexItem : public ComplexMissionItem
public:
StructureScanComplexItem(Vehicle* vehicle, QObject* parent = NULL);
Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
Q_PROPERTY(Fact* altitude READ altitude CONSTANT)
Q_PROPERTY(Fact* layers READ layers CONSTANT)
Q_PROPERTY(Fact* layerDistance READ layerDistance CONSTANT)
Q_PROPERTY(Fact* cameraTriggerDistance READ cameraTriggerDistance CONSTANT)
Q_PROPERTY(Fact* scanDistance READ scanDistance CONSTANT)
Q_PROPERTY(bool altitudeRelative MEMBER _altitudeRelative NOTIFY altitudeRelativeChanged)
Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged)
Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged)
......@@ -38,14 +37,12 @@ public:
Q_PROPERTY(QGCMapPolygon* structurePolygon READ structurePolygon CONSTANT)
Q_PROPERTY(QGCMapPolygon* flightPolygon READ flightPolygon CONSTANT)
Fact* altitude (void) { return &_altitudeFact; }
Fact* layers (void) { return &_layersFact; }
Fact* layerDistance (void) { return &_layerDistanceFact; }
Fact* cameraTriggerDistance (void) { return &_cameraTriggerDistanceFact; }
Fact* scanDistance (void) { return &_scanDistanceFact; }
CameraCalc* cameraCalc (void) { return &_cameraCalc; }
Fact* altitude (void) { return &_altitudeFact; }
Fact* layers (void) { return &_layersFact; }
int cameraShots (void) const;
double timeBetweenShots(void) const;
double timeBetweenShots(void);
QGCMapPolygon* structurePolygon(void) { return &_structurePolygon; }
QGCMapPolygon* flightPolygon (void) { return &_flightPolygon; }
......@@ -123,20 +120,15 @@ private:
double _timeBetweenShots;
double _cameraMinTriggerInterval;
double _cruiseSpeed;
CameraCalc _cameraCalc;
static QMap<QString, FactMetaData*> _metaDataMap;
Fact _altitudeFact;
Fact _layersFact;
Fact _layerDistanceFact;
Fact _cameraTriggerDistanceFact;
Fact _scanDistanceFact;
static const char* _altitudeFactName;
static const char* _layersFactName;
static const char* _layerDistanceFactName;
static const char* _cameraTriggerDistanceFactName;
static const char* _scanDistanceFactName;
};
#endif
This diff is collapsed.
......@@ -60,7 +60,7 @@ Rectangle {
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
text: qsTr("WARNING: WORK IN PROGRESS. USE AT YOUR OWN RISK. MEANT FOR DISCUSSION ONLY. DO NOT REPORT BUGS.")
text: qsTr("WARNING: WORK IN PROGRESS. DO NOT FLY. NO BUG REPORTS.")
wrapMode: Text.WordWrap
color: qgcPal.warningText
}
......@@ -82,59 +82,61 @@ Rectangle {
visible: missionItem.cameraShots > 0 && missionItem.cameraMinTriggerInterval !== 0 && missionItem.cameraMinTriggerInterval > missionItem.timeBetweenShots
}
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
QGCLabel { text: qsTr("Altitude") }
FactTextField {
fact: missionItem.altitude
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Layers") }
FactTextField {
fact: missionItem.layers
Layout.fillWidth: true
}
CameraCalc {
cameraCalc: missionItem.cameraCalc
vehicleFlightIsFrontal: false
distanceToSurfaceLabel: qsTr("Scan Distance")
frontalDistanceLabel: qsTr("Layer Height")
sideDistanceLabel: qsTr("Trigger Distance")
}
QGCLabel { text: qsTr("Layer distance") }
FactTextField {
fact: missionItem.layerDistance
Layout.fillWidth: true
}
SectionHeader {
id: scanHeader
text: qsTr("Scan")
}
QGCLabel { text: qsTr("Scan distance") }
FactTextField {
fact: missionItem.scanDistance
Layout.fillWidth: true
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: scanHeader.checked
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
QGCLabel { text: qsTr("Layers") }
FactTextField {
fact: missionItem.layers
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Altitude") }
FactTextField {
fact: missionItem.altitude
Layout.fillWidth: true
}
QGCCheckBox {
text: qsTr("Relative altitude")
checked: missionItem.altitudeRelative
Layout.columnSpan: 2
onClicked: missionItem.altitudeRelative = checked
}
}
QGCLabel { text: qsTr("Trigger Distance") }
FactTextField {
fact: missionItem.cameraTriggerDistance
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Point camera to structure using:") }
QGCRadioButton { text: qsTr("Vehicle yaw"); enabled: false }
QGCRadioButton { text: qsTr("Gimbal yaw"); checked: true; enabled: false }
QGCCheckBox {
text: qsTr("Relative altitude")
checked: missionItem.altitudeRelative
Layout.columnSpan: 2
onClicked: missionItem.altitudeRelative = checked
QGCButton {
text: qsTr("Rotate entry point")
onClicked: missionItem.rotateEntryPoint()
}
}
QGCLabel { text: qsTr("Point camera to structure using:") }
QGCRadioButton { text: qsTr("Vehicle yaw"); enabled: false }
QGCRadioButton { text: qsTr("Gimbal yaw"); checked: true; enabled: false }
QGCButton {
text: qsTr("Rotate entry point")
onClicked: missionItem.rotateEntryPoint()
}
} // Column - Scan
SectionHeader {
id: statsHeader
......@@ -152,6 +154,5 @@ Rectangle {
QGCLabel { text: qsTr("Photo interval") }
QGCLabel { text: missionItem.timeBetweenShots.toFixed(1) + " " + qsTr("secs") }
}
}
}
} // Column
} // Rectangle
......@@ -81,6 +81,7 @@
#include "SettingsManager.h"
#include "QGCCorePlugin.h"
#include "QGCCameraManager.h"
#include "CameraCalc.h"
#ifndef NO_SERIAL_LINK
#include "SerialLink.h"
......@@ -348,6 +349,7 @@ void QGCApplication::_initCommon(void)
qmlRegisterUncreatableType<CoordinateVector> ("QGroundControl", 1, 0, "CoordinateVector", "Reference only");
qmlRegisterUncreatableType<QmlObjectListModel> ("QGroundControl", 1, 0, "QmlObjectListModel", "Reference only");
qmlRegisterUncreatableType<MissionCommandTree> ("QGroundControl", 1, 0, "MissionCommandTree", "Reference only");
qmlRegisterUncreatableType<CameraCalc> ("QGroundControl", 1, 0, "CameraCalc", "Reference only");
qmlRegisterUncreatableType<AutoPilotPlugin> ("QGroundControl.AutoPilotPlugin", 1, 0, "AutoPilotPlugin", "Reference only");
qmlRegisterUncreatableType<VehicleComponent> ("QGroundControl.AutoPilotPlugin", 1, 0, "VehicleComponent", "Reference only");
......
......@@ -2,6 +2,7 @@ Module QGroundControl.Controls
AnalyzePage 1.0 AnalyzePage.qml
AppMessages 1.0 AppMessages.qml
CameraCalc 1.0 CameraCalc.qml
CameraSection 1.0 CameraSection.qml
ClickableColor 1.0 ClickableColor.qml
DropButton 1.0 DropButton.qml
......
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