12#include <QtCore/QJsonArray>
23, _ignoreRecalc (false)
26 , _cameraCalc (masterController, settingsGroup)
27 , _scanBottomAltFact (settingsGroup, _metaDataMap[scanBottomAltName])
28 , _structureHeightFact (settingsGroup, _metaDataMap[structureHeightName])
29 , _layersFact (settingsGroup, _metaDataMap[layersName])
30 , _gimbalPitchFact (settingsGroup, _metaDataMap[gimbalPitchName])
31 , _startFromTopFact (settingsGroup, _metaDataMap[startFromTopName])
32 , _entranceAltFact (settingsGroup, _metaDataMap[_entranceAltName])
34 _editorQml =
"qrc:/qml/QGroundControl/Controls/StructureScanEditor.qml";
36 _entranceAltFact.setRawValue(SettingsManager::instance()->appSettings()->defaultMissionItemAltitude()->rawValue());
38 connect(&_entranceAltFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_setDirty);
39 connect(&_scanBottomAltFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_setDirty);
40 connect(&_layersFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_setDirty);
41 connect(&_gimbalPitchFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_setDirty);
42 connect(&_startFromTopFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_setDirty);
44 connect(&_startFromTopFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_signalTopBottomAltChanged);
45 connect(&_layersFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_signalTopBottomAltChanged);
47 connect(&_structureHeightFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_recalcLayerInfo);
48 connect(&_scanBottomAltFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_recalcLayerInfo);
49 connect(_cameraCalc.adjustedFootprintFrontal(), &
Fact::valueChanged,
this, &StructureScanComplexItem::_recalcLayerInfo);
51 connect(&_entranceAltFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_updateCoordinateAltitudes);
60 connect(&_layersFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_updateLastSequenceNumber);
64 connect(_cameraCalc.distanceToSurface(), &
Fact::valueChanged,
this, &StructureScanComplexItem::_rebuildFlightPolygon);
67 connect(_cameraCalc.adjustedFootprintSide(), &
Fact::valueChanged,
this, &StructureScanComplexItem::_recalcCameraShots);
68 connect(&_layersFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_recalcCameraShots);
72 connect(&_layersFact, &
Fact::valueChanged,
this, &StructureScanComplexItem::_recalcScanDistance);
105 if (!kmlOrShpFile.isEmpty()) {
106 _structurePolygon.loadKMLOrSHPFile(kmlOrShpFile);
107 _structurePolygon.setDirty(
false);
113void StructureScanComplexItem::_setCameraShots(
int cameraShots)
121void StructureScanComplexItem::_clearInternal(
void)
129void StructureScanComplexItem::_updateLastSequenceNumber(
void)
139 int layerItemCount = _flightPolygon.
count() + 1 + 2;
142 int multiLayerItemCount = layerItemCount * _layersFact.rawValue().toInt();
146 int itemCount = multiLayerItemCount + 2 + 2;
148 return _sequenceNumber + itemCount - 1;
161 QJsonObject saveObject;
168 saveObject[_entranceAltName] = _entranceAltFact.rawValue().toDouble();
171 saveObject[
layersName] = _layersFact.rawValue().toDouble();
175 QJsonObject cameraCalcObject;
176 _cameraCalc.
save(cameraCalcObject);
177 saveObject[_jsonCameraCalcKey] = cameraCalcObject;
181 missionItems.append(saveObject);
195 QList<JsonHelper::KeyValidateInfo> keyInfoList = {
203 { _jsonCameraCalcKey, QJsonValue::Object,
true },
204 { _entranceAltName, QJsonValue::Double,
true },
212 _structurePolygon.clear();
217 errorString = tr(
"%1 does not support loading this complex mission item type: %2:%3").arg(
qgcApp()->applicationName()).arg(itemType).arg(complexType);
230 if (!_cameraCalc.
load(complexObject[_jsonCameraCalcKey].toObject(),
false ,
errorString,
false )) {
235 _layersFact.setRawValue (complexObject[
layersName].toDouble());
238 _entranceAltFact.setRawValue (complexObject[_entranceAltName].toDouble());
239 _gimbalPitchFact.setRawValue (complexObject[
gimbalPitchName].toDouble());
242 _structurePolygon.clear();
249void StructureScanComplexItem::_flightPathChanged(
void)
253 double south = 180.0;
256 double bottom = 100000.;
259 for (
int i = 0; i < vertices.count(); i++) {
260 QGeoCoordinate vertex = vertices[i];
261 double lat = vertex.latitude() + 90.0;
262 double lon = vertex.longitude() + 180.0;
263 north = fmax(north, lat);
264 south = fmin(south, lat);
265 east = fmax(east, lon);
266 west = fmin(west, lon);
267 bottom = fmin(bottom, vertex.altitude());
268 top = fmax(top, vertex.altitude());
272 QGeoCoordinate(north - 90.0, west - 180.0, bottom),
273 QGeoCoordinate(south - 90.0, east - 180.0, top)));
286 double greatestDistance = 0.0;
289 for (
int i=0; i<vertices.count(); i++) {
290 QGeoCoordinate vertex = vertices[i];
291 double distance = vertex.distanceTo(other);
297 return greatestDistance;
302 int seqNum = _sequenceNumber;
303 bool startFromTop = _startFromTopFact.rawValue().toBool();
304 double startAltitude = (
startFromTop ? _structureHeightFact.rawValue().toDouble() : _scanBottomAltFact.rawValue().toDouble());
309 QGeoCoordinate entranceExitCoord = _flightPolygon.
vertexCoordinate(_entryVertex);
311 MAV_CMD_NAV_WAYPOINT,
312 MAV_FRAME_GLOBAL_RELATIVE_ALT,
316 std::numeric_limits<double>::quiet_NaN(),
317 entranceExitCoord.latitude(),
318 entranceExitCoord.longitude(),
319 _entranceAltFact.rawValue().toDouble(),
327 MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET,
330 _gimbalPitchFact.rawValue().toDouble(),
339 double layerAltitude = startAltitude;
342 layerAltitude -= halfLayerHeight;
344 layerAltitude += halfLayerHeight;
347 for (
int layer=0; layer<_layersFact.rawValue().toInt(); layer++) {
348 bool addTriggerStart =
true;
351 int currentVertex = _entryVertex;
352 int processedVertices = 0;
354 QGeoCoordinate vertexCoord = _flightPolygon.
vertexCoordinate(currentVertex);
357 MAV_CMD_NAV_WAYPOINT,
358 MAV_FRAME_GLOBAL_RELATIVE_ALT,
362 std::numeric_limits<double>::quiet_NaN(),
363 vertexCoord.latitude(),
364 vertexCoord.longitude(),
372 if (addTriggerStart) {
373 addTriggerStart =
false;
375 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
389 if (currentVertex >= _flightPolygon.
count()) {
395 done = processedVertices == _flightPolygon.
count() + 1;
400 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
413 layerAltitude -= halfLayerHeight * 2;
415 layerAltitude += halfLayerHeight * 2;
421 MAV_CMD_DO_SET_ROI_NONE,
431 MAV_CMD_NAV_WAYPOINT,
432 MAV_FRAME_GLOBAL_RELATIVE_ALT,
436 std::numeric_limits<double>::quiet_NaN(),
437 entranceExitCoord.latitude(),
438 entranceExitCoord.longitude(),
439 _entranceAltFact.rawValue().toDouble(),
461void StructureScanComplexItem::_setDirty(
void)
468 _entranceAltFact.setRawValue(newAltitude);
473 const QGeoCoordinate oldCoordinate = this->
coordinate();
474 if (!oldCoordinate.isValid() || !
coordinate.isValid() || _structurePolygon.
count() < 3) {
478 const double distanceMeters = oldCoordinate.distanceTo(
coordinate);
479 const double azimuthDegrees = oldCoordinate.azimuthTo(
coordinate);
480 const QList<QGeoCoordinate> vertices = _structurePolygon.
coordinateList();
482 QList<QGeoCoordinate> translatedVertices;
483 translatedVertices.reserve(vertices.count());
484 for (
const QGeoCoordinate& vertex: vertices) {
485 translatedVertices.append(vertex.atDistanceAndAzimuth(distanceMeters, azimuthDegrees));
488 _structurePolygon.
setPath(translatedVertices);
491void StructureScanComplexItem::_polygonDirtyChanged(
bool dirty)
500 return _vehicleSpeed == 0 ? 0 : _cameraCalc.
adjustedFootprintSide()->rawValue().toDouble() / _vehicleSpeed;
505 if (_flightPolygon.
count() > 0) {
509 return QGeoCoordinate();
513void StructureScanComplexItem::_updateCoordinateAltitudes(
void)
521 if (_entryVertex >= _flightPolygon.
count()) {
527void StructureScanComplexItem::_rebuildFlightPolygon(
void)
531 int savedEntryVertex = _entryVertex;
534 _flightPolygon = _structurePolygon;
537 if (savedEntryVertex >= _flightPolygon.
count()) {
540 _entryVertex = savedEntryVertex;
546void StructureScanComplexItem::_recalcCameraShots(
void)
549 if (triggerDistance == 0) {
554 if (_flightPolygon.
count() < 3) {
561 for (
int i=0; i<_flightPolygon.
count(); i++) {
563 QGeoCoordinate coord2 = _flightPolygon.
vertexCoordinate(i + 1 == _flightPolygon.
count() ? 0 : i + 1);
564 distance += coord1.distanceTo(coord2);
572 _setCameraShots(
cameraShots * _layersFact.rawValue().toInt());
575void StructureScanComplexItem::_recalcLayerInfo(
void)
577 double surfaceHeight = qMax(_structureHeightFact.rawValue().toDouble() - _scanBottomAltFact.rawValue().toDouble(), 0.0);
580 _layersFact.setRawValue(qMax(qCeil(surfaceHeight / _cameraCalc.
adjustedFootprintFrontal()->rawValue().toDouble()), 1));
583void StructureScanComplexItem::_updateGimbalPitch(
void)
586 _gimbalPitchFact.setRawValue(0);
592 if (_startFromTopFact.rawValue().toBool()) {
595 return _structureHeightFact.rawValue().toDouble() - layerIncrement;
599 return _scanBottomAltFact.rawValue().toDouble() + layerIncrement;
605 if (_startFromTopFact.rawValue().toBool()) {
608 return _structureHeightFact.rawValue().toDouble() - layerIncrement;
612 return _scanBottomAltFact.rawValue().toDouble() + layerIncrement;
616void StructureScanComplexItem::_signalTopBottomAltChanged(
void)
622void StructureScanComplexItem::_recalcScanDistance()
624 double scanDistance = 0;
626 if (_flightPolygon.
count() > 2) {
628 for (
int i=0; i<vertices.count() - 1; i++) {
629 scanDistance += vertices[i].distanceTo(vertices[i+1]);
631 scanDistance += vertices.last().distanceTo(vertices.first());
633 scanDistance *= _layersFact.rawValue().toInt();
635 double surfaceHeight = qMax(_structureHeightFact.rawValue().toDouble() - _scanBottomAltFact.rawValue().toDouble(), 0.0);
636 scanDistance += surfaceHeight;
638 qCDebug(StructureScanComplexItemLog) <<
"StructureScanComplexItem--_recalcScanDistance layers: "
639 << _layersFact.rawValue().toInt() <<
" structure height: " << surfaceHeight
640 <<
" scanDistance: " << _scanDistance;
644 _scanDistance = scanDistance;
655void StructureScanComplexItem::_updateWizardMode(
void)
664 return _entranceAltFact.rawValue().toDouble();
673void StructureScanComplexItem::_updateFlightPathSegmentsDontCallDirectly(
void)
695 if (_flightPolygon.
count() > 2) {
697 bool startFromTop = _startFromTopFact.rawValue().toBool();
698 double startAltitude = (
startFromTop ? _structureHeightFact.rawValue().toDouble() : _scanBottomAltFact.rawValue().toDouble());
701 double prevLayerAltitude = 0;
702 double layerAltitude = startAltitude;
705 layerAltitude -= halfLayerHeight;
707 layerAltitude += halfLayerHeight;
711 QGeoCoordinate layerEntranceCoord = _flightPolygon.
vertexCoordinate(_entryVertex);
718 for (
int layerIndex=0; layerIndex<_layersFact.rawValue().toInt(); layerIndex++) {
720 if (layerIndex != 0) {
724 QGeoCoordinate prevCoord = QGeoCoordinate();
725 for (
const QGeoCoordinate& coord: _flightPolygon.coordinateList()) {
726 if (prevCoord.isValid()) {
734 prevLayerAltitude = layerAltitude;
736 layerAltitude -= halfLayerHeight * 2;
738 layerAltitude += halfLayerHeight * 2;
757 double minAlt = qMin(
bottomFlightAlt(), _entranceAltFact.rawValue().toDouble());
763 double maxAlt = qMax(
topFlightAlt(), _entranceAltFact.rawValue().toDouble());
767void 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 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.
void offset(double distance)
Offsets the current polygon edges by the specified distance in meters.
void traceModeChanged(bool traceMode)
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
bool isValidChanged(void)
void setShowAltColor(bool showAltColor)
bool loadFromJson(const QJsonObject &json, bool required, QString &errorString)
int count READ count NOTIFY countChanged(QVariantList path READ path NOTIFY pathChanged) 1(double area READ area NOTIFY pathChanged) 1(QmlObjectListModel *pathModel READ qmlPathModel CONSTANT) 1(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) 1(QGeoCoordinate center READ center WRITE setCenter NOTIFY centerChanged) 1(bool centerDrag READ centerDrag WRITE setCenterDrag NOTIFY centerDragChanged) 1(bool interactive READ interactive WRITE setInteractive NOTIFY interactiveChanged) 1(bool isValid READ isValid NOTIFY isValidChanged) 1(bool empty READ empty NOTIFY isEmptyChanged) 1(bool traceMode READ traceMode WRITE setTraceMode NOTIFY traceModeChanged) 1(bool showAltColor READ showAltColor WRITE setShowAltColor NOTIFY showAltColorChanged) 1(int selectedVertex READ selectedVertex WRITE selectVertex NOTIFY selectedVertexChanged) 1 void clear(void)
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
int lastSequenceNumber(void) const final
void setCoordinate(const QGeoCoordinate &coordinate) final
void bottomFlightAltChanged(void)
double topFlightAlt(void) const
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
void rotateEntryPoint(void)
void save(QJsonArray &missionItems) final
static constexpr const char * structureHeightName
int cameraShots(void) const
void timeBetweenShotsChanged(void)
void setMissionFlightStatus(MissionController::MissionFlightStatus_t &missionFlightStatus) final
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)
virtual void setMissionFlightStatus(MissionController::MissionFlightStatus_t &missionFlightStatus)
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)
constexpr const char * jsonVersionKey
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)
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.