12#include <QtCore/QJsonArray>
21, _ignoreRecalc (false)
24 , _cameraCalc (masterController, settingsGroup)
25 , _scanBottomAltFact (settingsGroup, _metaDataMap[scanBottomAltName])
26 , _structureHeightFact (settingsGroup, _metaDataMap[structureHeightName])
27 , _layersFact (settingsGroup, _metaDataMap[layersName])
28 , _gimbalPitchFact (settingsGroup, _metaDataMap[gimbalPitchName])
29 , _startFromTopFact (settingsGroup, _metaDataMap[startFromTopName])
30 , _entranceAltFact (settingsGroup, _metaDataMap[_entranceAltName])
32 _editorQml =
"qrc:/qml/QGroundControl/PlanView/StructureScanEditor.qml";
36 connect(&_entranceAltFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_setDirty);
37 connect(&_scanBottomAltFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_setDirty);
38 connect(&_layersFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_setDirty);
39 connect(&_gimbalPitchFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_setDirty);
40 connect(&_startFromTopFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_setDirty);
42 connect(&_startFromTopFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_signalTopBottomAltChanged);
43 connect(&_layersFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_signalTopBottomAltChanged);
45 connect(&_structureHeightFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_recalcLayerInfo);
46 connect(&_scanBottomAltFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_recalcLayerInfo);
47 connect(_cameraCalc.adjustedFootprintFrontal(), &
Fact::valueChanged,
this, &StructureScanComplexItem::_recalcLayerInfo);
49 connect(&_entranceAltFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_updateCoordinateAltitudes);
58 connect(&_layersFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_updateLastSequenceNumber);
62 connect(_cameraCalc.distanceToSurface(), &
Fact::valueChanged,
this, &StructureScanComplexItem::_rebuildFlightPolygon);
65 connect(_cameraCalc.adjustedFootprintSide(), &
Fact::valueChanged,
this, &StructureScanComplexItem::_recalcCameraShots);
66 connect(&_layersFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_recalcCameraShots);
70 connect(&_layersFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_recalcScanDistance);
103 if (!kmlOrShpFile.isEmpty()) {
104 _structurePolygon.loadKMLOrSHPFile(kmlOrShpFile);
105 _structurePolygon.setDirty(
false);
111void StructureScanComplexItem::_setCameraShots(
int cameraShots)
119void StructureScanComplexItem::_clearInternal(
void)
127void StructureScanComplexItem::_updateLastSequenceNumber(
void)
137 int layerItemCount = _flightPolygon.
count() + 1 + 2;
140 int multiLayerItemCount = layerItemCount * _layersFact.
rawValue().toInt();
144 int itemCount = multiLayerItemCount + 2 + 2;
146 return _sequenceNumber + itemCount - 1;
159 QJsonObject saveObject;
166 saveObject[_entranceAltName] = _entranceAltFact.
rawValue().toDouble();
173 QJsonObject cameraCalcObject;
174 _cameraCalc.
save(cameraCalcObject);
175 saveObject[_jsonCameraCalcKey] = cameraCalcObject;
179 missionItems.append(saveObject);
193 QList<JsonParsing::KeyValidateInfo> keyInfoList = {
201 { _jsonCameraCalcKey, QJsonValue::Object,
true },
202 { _entranceAltName, QJsonValue::Double,
true },
210 _structurePolygon.
clear();
215 errorString = tr(
"%1 does not support loading this complex mission item type: %2:%3").arg(
qgcApp()->applicationName()).arg(itemType).arg(complexType);
228 if (!_cameraCalc.
load(complexObject[_jsonCameraCalcKey].toObject(),
false ,
errorString,
false )) {
236 _entranceAltFact.
setRawValue (complexObject[_entranceAltName].toDouble());
240 _structurePolygon.
clear();
247void StructureScanComplexItem::_flightPathChanged(
void)
251 double south = 180.0;
254 double bottom = 100000.;
257 for (
int i = 0; i < vertices.count(); i++) {
258 QGeoCoordinate vertex = vertices[i];
259 double lat = vertex.latitude() + 90.0;
260 double lon = vertex.longitude() + 180.0;
261 north = fmax(north, lat);
262 south = fmin(south, lat);
263 east = fmax(east, lon);
264 west = fmin(west, lon);
265 bottom = fmin(bottom, vertex.altitude());
266 top = fmax(top, vertex.altitude());
270 QGeoCoordinate(north - 90.0, west - 180.0, bottom),
271 QGeoCoordinate(south - 90.0, east - 180.0, top)));
284 double greatestDistance = 0.0;
287 for (
int i=0; i<vertices.count(); i++) {
288 QGeoCoordinate vertex = vertices[i];
289 double distance = vertex.distanceTo(other);
295 return greatestDistance;
300 int seqNum = _sequenceNumber;
307 QGeoCoordinate entranceExitCoord = _flightPolygon.
vertexCoordinate(_entryVertex);
309 MAV_CMD_NAV_WAYPOINT,
310 MAV_FRAME_GLOBAL_RELATIVE_ALT,
314 std::numeric_limits<double>::quiet_NaN(),
315 entranceExitCoord.latitude(),
316 entranceExitCoord.longitude(),
317 _entranceAltFact.
rawValue().toDouble(),
325 MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET,
328 _gimbalPitchFact.
rawValue().toDouble(),
337 double layerAltitude = startAltitude;
340 layerAltitude -= halfLayerHeight;
342 layerAltitude += halfLayerHeight;
345 for (
int layer=0; layer<_layersFact.
rawValue().toInt(); layer++) {
346 bool addTriggerStart =
true;
349 int currentVertex = _entryVertex;
350 int processedVertices = 0;
352 QGeoCoordinate vertexCoord = _flightPolygon.
vertexCoordinate(currentVertex);
355 MAV_CMD_NAV_WAYPOINT,
356 MAV_FRAME_GLOBAL_RELATIVE_ALT,
360 std::numeric_limits<double>::quiet_NaN(),
361 vertexCoord.latitude(),
362 vertexCoord.longitude(),
370 if (addTriggerStart) {
371 addTriggerStart =
false;
373 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
387 if (currentVertex >= _flightPolygon.
count()) {
393 done = processedVertices == _flightPolygon.
count() + 1;
398 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
411 layerAltitude -= halfLayerHeight * 2;
413 layerAltitude += halfLayerHeight * 2;
419 MAV_CMD_DO_SET_ROI_NONE,
429 MAV_CMD_NAV_WAYPOINT,
430 MAV_FRAME_GLOBAL_RELATIVE_ALT,
434 std::numeric_limits<double>::quiet_NaN(),
435 entranceExitCoord.latitude(),
436 entranceExitCoord.longitude(),
437 _entranceAltFact.
rawValue().toDouble(),
459void StructureScanComplexItem::_setDirty(
void)
471 const QGeoCoordinate oldCoordinate = this->
coordinate();
472 if (!oldCoordinate.isValid() || !
coordinate.isValid() || _structurePolygon.
count() < 3) {
476 const double distanceMeters = oldCoordinate.distanceTo(
coordinate);
477 const double azimuthDegrees = oldCoordinate.azimuthTo(
coordinate);
478 const QList<QGeoCoordinate> vertices = _structurePolygon.
coordinateList();
480 QList<QGeoCoordinate> translatedVertices;
481 translatedVertices.reserve(vertices.count());
482 for (
const QGeoCoordinate& vertex: vertices) {
483 translatedVertices.append(vertex.atDistanceAndAzimuth(distanceMeters, azimuthDegrees));
486 _structurePolygon.
setPath(translatedVertices);
489void StructureScanComplexItem::_polygonDirtyChanged(
bool dirty)
503 if (_flightPolygon.
count() > 0) {
507 return QGeoCoordinate();
511void StructureScanComplexItem::_updateCoordinateAltitudes(
void)
519 if (_entryVertex >= _flightPolygon.
count()) {
525void StructureScanComplexItem::_rebuildFlightPolygon(
void)
529 int savedEntryVertex = _entryVertex;
532 _flightPolygon = _structurePolygon;
535 if (savedEntryVertex >= _flightPolygon.
count()) {
538 _entryVertex = savedEntryVertex;
544void StructureScanComplexItem::_recalcCameraShots(
void)
547 if (triggerDistance == 0) {
552 if (_flightPolygon.
count() < 3) {
559 for (
int i=0; i<_flightPolygon.
count(); i++) {
561 QGeoCoordinate coord2 = _flightPolygon.
vertexCoordinate(i + 1 == _flightPolygon.
count() ? 0 : i + 1);
562 distance += coord1.distanceTo(coord2);
573void StructureScanComplexItem::_recalcLayerInfo(
void)
575 double surfaceHeight = qMax(_structureHeightFact.
rawValue().toDouble() - _scanBottomAltFact.
rawValue().toDouble(), 0.0);
581void StructureScanComplexItem::_updateGimbalPitch(
void)
590 if (_startFromTopFact.
rawValue().toBool()) {
593 return _structureHeightFact.
rawValue().toDouble() - layerIncrement;
597 return _scanBottomAltFact.
rawValue().toDouble() + layerIncrement;
603 if (_startFromTopFact.
rawValue().toBool()) {
606 return _structureHeightFact.
rawValue().toDouble() - layerIncrement;
610 return _scanBottomAltFact.
rawValue().toDouble() + layerIncrement;
614void StructureScanComplexItem::_signalTopBottomAltChanged(
void)
620void StructureScanComplexItem::_recalcScanDistance()
622 double scanDistance = 0;
624 if (_flightPolygon.
count() > 2) {
626 for (
int i=0; i<vertices.count() - 1; i++) {
627 scanDistance += vertices[i].distanceTo(vertices[i+1]);
629 scanDistance += vertices.last().distanceTo(vertices.first());
631 scanDistance *= _layersFact.
rawValue().toInt();
633 double surfaceHeight = qMax(_structureHeightFact.
rawValue().toDouble() - _scanBottomAltFact.
rawValue().toDouble(), 0.0);
634 scanDistance += surfaceHeight;
636 qCDebug(StructureScanComplexItemLog) <<
"StructureScanComplexItem--_recalcScanDistance layers: "
637 << _layersFact.
rawValue().toInt() <<
" structure height: " << surfaceHeight
638 <<
" scanDistance: " << _scanDistance;
642 _scanDistance = scanDistance;
653void StructureScanComplexItem::_updateWizardMode(
void)
662 return _entranceAltFact.
rawValue().toDouble();
671void StructureScanComplexItem::_updateFlightPathSegmentsDontCallDirectly(
void)
693 if (_flightPolygon.
count() > 2) {
699 double prevLayerAltitude = 0;
700 double layerAltitude = startAltitude;
703 layerAltitude -= halfLayerHeight;
705 layerAltitude += halfLayerHeight;
709 QGeoCoordinate layerEntranceCoord = _flightPolygon.
vertexCoordinate(_entryVertex);
716 for (
int layerIndex=0; layerIndex<_layersFact.
rawValue().toInt(); layerIndex++) {
718 if (layerIndex != 0) {
722 QGeoCoordinate prevCoord = QGeoCoordinate();
723 for (
const QGeoCoordinate& coord: _flightPolygon.coordinateList()) {
724 if (prevCoord.isValid()) {
732 prevLayerAltitude = layerAltitude;
734 layerAltitude -= halfLayerHeight * 2;
736 layerAltitude += halfLayerHeight * 2;
765void StructureScanComplexItem::_segmentTerrainCollisionChanged(
bool terrainCollision)
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void save(QJsonObject &json) const
Fact * adjustedFootprintSide(void)
bool isManualCamera(void) const
Fact * distanceToSurface(void)
Fact * adjustedFootprintFrontal(void)
bool load(const QJsonObject &json, bool deprecatedFollowTerrain, QString &errorString, bool forPresets)
void isManualCameraChanged(void)
void isIncompleteChanged(void)
static constexpr const char * jsonComplexItemTypeKey
This mission item attribute specifies the type of the complex item.
void _appendFlightPathSegment(FlightPathSegment::SegmentType segmentType, const QGeoCoordinate &coord1, double coord1AMSLAlt, const QGeoCoordinate &coord2, double coord2AMSLAlt)
QmlObjectListModel _flightPathSegments
void greatestDistanceToChanged(void)
int _cTerrainCollisionSegments
void maxAMSLAltitudeChanged(void)
virtual bool terrainCollision(void) const
void minAMSLAltitudeChanged(void)
void complexDistanceChanged(void)
void terrainCollisionChanged(bool terrainCollision)
virtual void _segmentTerrainCollisionChanged(bool terrainCollision)
void setRawValue(const QVariant &value)
QVariant rawValue() const
Value after translation.
void valueChanged(const QVariant &value)
This signal is only meant for use by the QT property system. It should not be connected to by client ...
void recalcTerrainProfile(void)
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition)
QGeoCoordinate plannedHomePosition(void) const
void endResetModel()
Depth-counted endResetModel — only the outermost call has effect.
void beginResetModel()
Depth-counted beginResetModel — only the outermost call has effect.
Master controller for mission, fence, rally.
MissionController * missionController(void)
void dirtyChanged(bool dirty)
bool traceMode(void) const
QList< QGeoCoordinate > coordinateList(void) const
Returns the path in a list of QGeoCoordinate's format.
Q_INVOKABLE void offset(double distance)
Offsets the current polygon edges by the specified distance in meters.
void traceModeChanged(bool traceMode)
Q_INVOKABLE QGeoCoordinate vertexCoordinate(int vertex) const
Returns the QGeoCoordinate for the vertex specified.
void setPath(const QList< QGeoCoordinate > &path)
void saveToJson(QJsonObject &json)
static constexpr const char * jsonPolygonKey
Q_INVOKABLE void clear(void)
bool isValidChanged(void)
void setShowAltColor(bool showAltColor)
void countChanged(int count)
bool loadFromJson(const QJsonObject &json, bool required, QString &errorString)
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
Provides access to group of settings.
static SettingsManager * instance()
int lastSequenceNumber(void) const final
void setCoordinate(const QGeoCoordinate &coordinate) final
void bottomFlightAltChanged(void)
double topFlightAlt(void) const
void setMissionFlightStatus(MissionFlightStatus_t &missionFlightStatus) final
void applyNewAltitude(double newAltitude) final
Adjust the altitude of the item if appropriate to the new altitude.
Fact * startFromTop(void)
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) final
QGeoCoordinate coordinate(void) const final
Q_INVOKABLE void rotateEntryPoint(void)
void save(QJsonArray &missionItems) final
static constexpr const char * structureHeightName
int cameraShots(void) const
void timeBetweenShotsChanged(void)
void cameraShotsChanged(int cameraShots)
static constexpr const char * layersName
static constexpr const char * jsonComplexItemTypeValue
void topFlightAltChanged(void)
void setSequenceNumber(int sequenceNumber) final
static constexpr const char * scanBottomAltName
ReadyForSaveState readyForSaveState(void) const final
double editableAlt(void) const final
static constexpr const char * gimbalPitchName
double minAMSLAltitude(void) const final
double timeBetweenShots(void)
void _updateFlightPathSegmentsSignal(void)
void setDirty(bool dirty) final
double greatestDistanceTo(const QGeoCoordinate &other) const final
bool dirty(void) const final
double amslEntryAlt(void) const final
double maxAMSLAltitude(void) const final
void appendMissionItems(QList< MissionItem * > &items, QObject *missionItemParent) final
static constexpr const char * startFromTopName
double bottomFlightAlt(void) const
int sequenceNumber(void) const final
PlanMasterController * _masterController
void _setBoundingCube(QGCGeoBoundingCube bc)
static constexpr const char * jsonTypeComplexItemValue
Item type is Complex Item.
void amslExitAltChanged(double alt)
void setWizardMode(bool wizardMode)
void lastSequenceNumberChanged(int sequenceNumber)
void entryCoordinateChanged(const QGeoCoordinate &entryCoordinate)
void specifiesCoordinateChanged(void)
void coordinateChanged(const QGeoCoordinate &coordinate)
void readyForSaveStateChanged(void)
MissionController * _missionController
double distance(void) const
void amslEntryAltChanged(double alt)
bool _wizardMode
true: Item editor is showing wizard completion panel
static constexpr const char * jsonTypeKey
Json file attribute which specifies the item type.
void _amslEntryAltChanged(void)
void dirtyChanged(bool dirty)
void sequenceNumberChanged(int sequenceNumber)
void exitCoordinateChanged(const QGeoCoordinate &exitCoordinate)
void wizardModeChanged(bool wizardMode)
virtual void setMissionFlightStatus(MissionFlightStatus_t &missionFlightStatus)
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)
Validates that all required keys are present and that listed keys have the expected type.
constexpr const char * jsonVersionKey
bool fuzzyCompare(double value1, double value2)
Returns true if the two values are equal or close. Correctly handles 0 and NaN values.
double vehicleSpeed
Either cruise or hover speed based on vehicle type and vtol state.